Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
costmap_subscriber.cpp
1 // Copyright (c) 2019 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <string>
16 #include <memory>
17 #include <mutex>
18 
19 #include "nav2_costmap_2d/costmap_subscriber.hpp"
20 
21 namespace nav2_costmap_2d
22 {
23 
24 std::shared_ptr<Costmap2D> CostmapSubscriber::getCostmap()
25 {
26  if (!isCostmapReceived()) {
27  throw std::runtime_error("Costmap is not available");
28  }
29  if (costmap_msg_) {
30  processCurrentCostmapMsg();
31  }
32  return costmap_;
33 }
34 
35 void CostmapSubscriber::costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg)
36 {
37  {
38  std::lock_guard<std::mutex> lock(costmap_msg_mutex_);
39  costmap_msg_ = msg;
40  frame_id_ = costmap_msg_->header.frame_id;
41  }
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);
47 
48  processCurrentCostmapMsg();
49  }
50 }
51 
53  const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg)
54 {
55  if (isCostmapReceived()) {
56  if (costmap_msg_) {
57  processCurrentCostmapMsg();
58  }
59 
60  std::lock_guard<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
61 
62  auto map_cell_size_x = costmap_->getSizeInCellsX();
63  auto map_call_size_y = costmap_->getSizeInCellsY();
64 
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)
67  {
68  RCLCPP_WARN(
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);
72  return;
73  }
74  unsigned char * master_array = costmap_->getCharMap();
75  // copy update msg row-wise
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 +
78  update_msg->x;
79 
80  std::copy_n(
81  update_msg->data.begin() + (y * update_msg->size_x),
82  update_msg->size_x, &master_array[starting_index_of_row_update_in_costmap]);
83  }
84  } else {
85  RCLCPP_WARN(logger_, "No costmap received.");
86  }
87 }
88 
89 void CostmapSubscriber::processCurrentCostmapMsg()
90 {
91  std::scoped_lock lock(*(costmap_->getMutex()), costmap_msg_mutex_);
92  if (haveCostmapParametersChanged()) {
93  costmap_->resizeMap(
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);
98  }
99 
100  unsigned char * master_array = costmap_->getCharMap();
101  std::copy(costmap_msg_->data.begin(), costmap_msg_->data.end(), master_array);
102  costmap_msg_.reset();
103 }
104 
105 bool CostmapSubscriber::haveCostmapParametersChanged()
106 {
107  return hasCostmapSizeChanged() ||
108  hasCostmapResolutionChanged() ||
109  hasCostmapOriginPositionChanged();
110 }
111 
112 bool CostmapSubscriber::hasCostmapSizeChanged()
113 {
114  return costmap_->getSizeInCellsX() != costmap_msg_->metadata.size_x ||
115  costmap_->getSizeInCellsY() != costmap_msg_->metadata.size_y;
116 }
117 
118 bool CostmapSubscriber::hasCostmapResolutionChanged()
119 {
120  return costmap_->getResolution() != costmap_msg_->metadata.resolution;
121 }
122 
123 bool CostmapSubscriber::hasCostmapOriginPositionChanged()
124 {
125  return costmap_->getOriginX() != costmap_msg_->metadata.origin.position.x ||
126  costmap_->getOriginY() != costmap_msg_->metadata.origin.position.y;
127 }
128 
129 } // namespace nav2_costmap_2d
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.