Nav2 Navigation Stack - jazzy  jazzy
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 constexpr int costmapUpdateQueueDepth = 10;
25 
27  const nav2_util::LifecycleNode::WeakPtr & parent,
28  const std::string & topic_name)
29 : topic_name_(topic_name)
30 {
31  auto node = parent.lock();
32  logger_ = node->get_logger();
33  costmap_sub_ = node->create_subscription<nav2_msgs::msg::Costmap>(
34  topic_name_,
35  rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
36  std::bind(&CostmapSubscriber::costmapCallback, this, std::placeholders::_1));
37  costmap_update_sub_ = node->create_subscription<nav2_msgs::msg::CostmapUpdate>(
38  topic_name_ + "_updates",
39  rclcpp::QoS(rclcpp::KeepLast(costmapUpdateQueueDepth)).transient_local().reliable(),
40  std::bind(&CostmapSubscriber::costmapUpdateCallback, this, std::placeholders::_1));
41 }
42 
44  const rclcpp::Node::WeakPtr & parent,
45  const std::string & topic_name)
46 : topic_name_(topic_name)
47 {
48  auto node = parent.lock();
49  logger_ = node->get_logger();
50  costmap_sub_ = node->create_subscription<nav2_msgs::msg::Costmap>(
51  topic_name_,
52  rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
53  std::bind(&CostmapSubscriber::costmapCallback, this, std::placeholders::_1));
54  costmap_update_sub_ = node->create_subscription<nav2_msgs::msg::CostmapUpdate>(
55  topic_name_ + "_updates",
56  rclcpp::QoS(rclcpp::KeepLast(costmapUpdateQueueDepth)).transient_local().reliable(),
57  std::bind(&CostmapSubscriber::costmapUpdateCallback, this, std::placeholders::_1));
58 }
59 
60 std::shared_ptr<Costmap2D> CostmapSubscriber::getCostmap()
61 {
62  if (!isCostmapReceived()) {
63  throw std::runtime_error("Costmap is not available");
64  }
65  if (costmap_msg_) {
66  processCurrentCostmapMsg();
67  }
68  return costmap_;
69 }
70 
71 void CostmapSubscriber::costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg)
72 {
73  {
74  std::lock_guard<std::mutex> lock(costmap_msg_mutex_);
75  costmap_msg_ = msg;
76  }
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);
82 
83  processCurrentCostmapMsg();
84  }
85 }
86 
88  const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg)
89 {
90  if (isCostmapReceived()) {
91  if (costmap_msg_) {
92  processCurrentCostmapMsg();
93  }
94 
95  std::lock_guard<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
96 
97  auto map_cell_size_x = costmap_->getSizeInCellsX();
98  auto map_call_size_y = costmap_->getSizeInCellsY();
99 
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)
102  {
103  RCLCPP_WARN(
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);
107  return;
108  }
109  unsigned char * master_array = costmap_->getCharMap();
110  // copy update msg row-wise
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 +
113  update_msg->x;
114 
115  std::copy_n(
116  update_msg->data.begin() + (y * update_msg->size_x),
117  update_msg->size_x, &master_array[starting_index_of_row_update_in_costmap]);
118  }
119  } else {
120  RCLCPP_WARN(logger_, "No costmap received.");
121  }
122 }
123 
124 void CostmapSubscriber::processCurrentCostmapMsg()
125 {
126  std::scoped_lock lock(*(costmap_->getMutex()), costmap_msg_mutex_);
127  if (haveCostmapParametersChanged()) {
128  costmap_->resizeMap(
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);
133  }
134 
135  unsigned char * master_array = costmap_->getCharMap();
136  std::copy(costmap_msg_->data.begin(), costmap_msg_->data.end(), master_array);
137  costmap_msg_.reset();
138 }
139 
140 bool CostmapSubscriber::haveCostmapParametersChanged()
141 {
142  return hasCostmapSizeChanged() ||
143  hasCostmapResolutionChanged() ||
144  hasCostmapOriginPositionChanged();
145 }
146 
147 bool CostmapSubscriber::hasCostmapSizeChanged()
148 {
149  return costmap_->getSizeInCellsX() != costmap_msg_->metadata.size_x ||
150  costmap_->getSizeInCellsY() != costmap_msg_->metadata.size_y;
151 }
152 
153 bool CostmapSubscriber::hasCostmapResolutionChanged()
154 {
155  return costmap_->getResolution() != costmap_msg_->metadata.resolution;
156 }
157 
158 bool CostmapSubscriber::hasCostmapOriginPositionChanged()
159 {
160  return costmap_->getOriginX() != costmap_msg_->metadata.origin.position.x ||
161  costmap_->getOriginY() != costmap_msg_->metadata.origin.position.y;
162 }
163 
164 } // namespace nav2_costmap_2d
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.