19 #include "nav2_costmap_2d/costmap_subscriber.hpp"
26 if (!isCostmapReceived()) {
27 throw std::runtime_error(
"Costmap is not available");
30 processCurrentCostmapMsg();
38 std::lock_guard<std::mutex> lock(costmap_msg_mutex_);
40 frame_id_ = costmap_msg_->header.frame_id;
42 if (!isCostmapReceived()) {
43 costmap_ = std::make_shared<Costmap2D>(
44 msg->metadata.size_x, msg->metadata.size_y,
45 msg->metadata.resolution, msg->metadata.origin.position.x,
46 msg->metadata.origin.position.y);
48 processCurrentCostmapMsg();
53 const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg)
55 if (isCostmapReceived()) {
57 processCurrentCostmapMsg();
60 std::lock_guard<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
62 auto map_cell_size_x = costmap_->getSizeInCellsX();
63 auto map_call_size_y = costmap_->getSizeInCellsY();
65 if (map_cell_size_x < update_msg->x + update_msg->size_x ||
66 map_call_size_y < update_msg->y + update_msg->size_y)
69 logger_,
"Update area outside of original map area. Costmap bounds: %d X %d, "
70 "Update origin: %d, %d bounds: %d X %d", map_cell_size_x, map_call_size_y,
71 update_msg->x, update_msg->y, update_msg->size_x, update_msg->size_y);
74 unsigned char * master_array = costmap_->getCharMap();
76 for (
size_t y = 0; y < update_msg->size_y; ++y) {
77 auto starting_index_of_row_update_in_costmap = (y + update_msg->y) * map_cell_size_x +
81 update_msg->data.begin() + (y * update_msg->size_x),
82 update_msg->size_x, &master_array[starting_index_of_row_update_in_costmap]);
85 RCLCPP_WARN(logger_,
"No costmap received.");
89 void CostmapSubscriber::processCurrentCostmapMsg()
91 std::scoped_lock lock(*(costmap_->getMutex()), costmap_msg_mutex_);
92 if (haveCostmapParametersChanged()) {
94 costmap_msg_->metadata.size_x, costmap_msg_->metadata.size_y,
95 costmap_msg_->metadata.resolution,
96 costmap_msg_->metadata.origin.position.x,
97 costmap_msg_->metadata.origin.position.y);
100 unsigned char * master_array = costmap_->getCharMap();
101 std::copy(costmap_msg_->data.begin(), costmap_msg_->data.end(), master_array);
102 costmap_msg_.reset();
105 bool CostmapSubscriber::haveCostmapParametersChanged()
107 return hasCostmapSizeChanged() ||
108 hasCostmapResolutionChanged() ||
109 hasCostmapOriginPositionChanged();
112 bool CostmapSubscriber::hasCostmapSizeChanged()
114 return costmap_->getSizeInCellsX() != costmap_msg_->metadata.size_x ||
115 costmap_->getSizeInCellsY() != costmap_msg_->metadata.size_y;
118 bool CostmapSubscriber::hasCostmapResolutionChanged()
120 return costmap_->getResolution() != costmap_msg_->metadata.resolution;
123 bool CostmapSubscriber::hasCostmapOriginPositionChanged()
125 return costmap_->getOriginX() != costmap_msg_->metadata.origin.position.x ||
126 costmap_->getOriginY() != costmap_msg_->metadata.origin.position.y;
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.