19 #include "nav2_costmap_2d/costmap_subscriber.hpp"
24 constexpr
int costmapUpdateQueueDepth = 10;
27 const nav2_util::LifecycleNode::WeakPtr & parent,
28 const std::string & topic_name)
29 : topic_name_(topic_name)
31 auto node = parent.lock();
32 logger_ = node->get_logger();
33 costmap_sub_ = node->create_subscription<nav2_msgs::msg::Costmap>(
35 rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
37 costmap_update_sub_ = node->create_subscription<nav2_msgs::msg::CostmapUpdate>(
38 topic_name_ +
"_updates",
39 rclcpp::QoS(rclcpp::KeepLast(costmapUpdateQueueDepth)).transient_local().reliable(),
44 const rclcpp::Node::WeakPtr & parent,
45 const std::string & topic_name)
46 : topic_name_(topic_name)
48 auto node = parent.lock();
49 logger_ = node->get_logger();
50 costmap_sub_ = node->create_subscription<nav2_msgs::msg::Costmap>(
52 rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
54 costmap_update_sub_ = node->create_subscription<nav2_msgs::msg::CostmapUpdate>(
55 topic_name_ +
"_updates",
56 rclcpp::QoS(rclcpp::KeepLast(costmapUpdateQueueDepth)).transient_local().reliable(),
62 if (!isCostmapReceived()) {
63 throw std::runtime_error(
"Costmap is not available");
66 processCurrentCostmapMsg();
74 std::lock_guard<std::mutex> lock(costmap_msg_mutex_);
77 if (!isCostmapReceived()) {
78 costmap_ = std::make_shared<Costmap2D>(
79 msg->metadata.size_x, msg->metadata.size_y,
80 msg->metadata.resolution, msg->metadata.origin.position.x,
81 msg->metadata.origin.position.y);
83 processCurrentCostmapMsg();
88 const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg)
90 if (isCostmapReceived()) {
92 processCurrentCostmapMsg();
95 std::lock_guard<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
97 auto map_cell_size_x = costmap_->getSizeInCellsX();
98 auto map_call_size_y = costmap_->getSizeInCellsY();
100 if (map_cell_size_x < update_msg->x + update_msg->size_x ||
101 map_call_size_y < update_msg->y + update_msg->size_y)
104 logger_,
"Update area outside of original map area. Costmap bounds: %d X %d, "
105 "Update origin: %d, %d bounds: %d X %d", map_cell_size_x, map_call_size_y,
106 update_msg->x, update_msg->y, update_msg->size_x, update_msg->size_y);
109 unsigned char * master_array = costmap_->getCharMap();
111 for (
size_t y = 0; y < update_msg->size_y; ++y) {
112 auto starting_index_of_row_update_in_costmap = (y + update_msg->y) * map_cell_size_x +
116 update_msg->data.begin() + (y * update_msg->size_x),
117 update_msg->size_x, &master_array[starting_index_of_row_update_in_costmap]);
120 RCLCPP_WARN(logger_,
"No costmap received.");
124 void CostmapSubscriber::processCurrentCostmapMsg()
126 std::scoped_lock lock(*(costmap_->getMutex()), costmap_msg_mutex_);
127 if (haveCostmapParametersChanged()) {
129 costmap_msg_->metadata.size_x, costmap_msg_->metadata.size_y,
130 costmap_msg_->metadata.resolution,
131 costmap_msg_->metadata.origin.position.x,
132 costmap_msg_->metadata.origin.position.y);
135 unsigned char * master_array = costmap_->getCharMap();
136 std::copy(costmap_msg_->data.begin(), costmap_msg_->data.end(), master_array);
137 costmap_msg_.reset();
140 bool CostmapSubscriber::haveCostmapParametersChanged()
142 return hasCostmapSizeChanged() ||
143 hasCostmapResolutionChanged() ||
144 hasCostmapOriginPositionChanged();
147 bool CostmapSubscriber::hasCostmapSizeChanged()
149 return costmap_->getSizeInCellsX() != costmap_msg_->metadata.size_x ||
150 costmap_->getSizeInCellsY() != costmap_msg_->metadata.size_y;
153 bool CostmapSubscriber::hasCostmapResolutionChanged()
155 return costmap_->getResolution() != costmap_msg_->metadata.resolution;
158 bool CostmapSubscriber::hasCostmapOriginPositionChanged()
160 return costmap_->getOriginX() != costmap_msg_->metadata.origin.position.x ||
161 costmap_->getOriginY() != costmap_msg_->metadata.origin.position.y;
CostmapSubscriber(const nav2_util::LifecycleNode::WeakPtr &parent, const std::string &topic_name)
A constructor.
void costmapUpdateCallback(const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg)
Callback for the costmap's update topic.
void costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg)
Callback for the costmap topic.
std::shared_ptr< Costmap2D > getCostmap()
Get current costmap.