Nav2 Navigation Stack - humble  humble
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 
18 #include "nav2_costmap_2d/costmap_subscriber.hpp"
19 
20 namespace nav2_costmap_2d
21 {
22 
24  const nav2_util::LifecycleNode::WeakPtr & parent,
25  const std::string & topic_name)
26 : topic_name_(topic_name)
27 {
28  auto node = parent.lock();
29  costmap_sub_ = node->create_subscription<nav2_msgs::msg::Costmap>(
30  topic_name_,
31  rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
32  std::bind(&CostmapSubscriber::costmapCallback, this, std::placeholders::_1));
33 }
34 
36  const rclcpp::Node::WeakPtr & parent,
37  const std::string & topic_name)
38 : topic_name_(topic_name)
39 {
40  auto node = parent.lock();
41  costmap_sub_ = node->create_subscription<nav2_msgs::msg::Costmap>(
42  topic_name_,
43  rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
44  std::bind(&CostmapSubscriber::costmapCallback, this, std::placeholders::_1));
45 }
46 
47 std::shared_ptr<Costmap2D> CostmapSubscriber::getCostmap()
48 {
49  if (!costmap_received_) {
50  throw std::runtime_error("Costmap is not available");
51  }
52  toCostmap2D();
53  return costmap_;
54 }
55 
57 {
58  auto current_costmap_msg = std::atomic_load(&costmap_msg_);
59 
60  if (costmap_ == nullptr) {
61  costmap_ = std::make_shared<Costmap2D>(
62  current_costmap_msg->metadata.size_x, current_costmap_msg->metadata.size_y,
63  current_costmap_msg->metadata.resolution, current_costmap_msg->metadata.origin.position.x,
64  current_costmap_msg->metadata.origin.position.y);
65  } else if (costmap_->getSizeInCellsX() != current_costmap_msg->metadata.size_x || // NOLINT
66  costmap_->getSizeInCellsY() != current_costmap_msg->metadata.size_y ||
67  costmap_->getResolution() != current_costmap_msg->metadata.resolution ||
68  costmap_->getOriginX() != current_costmap_msg->metadata.origin.position.x ||
69  costmap_->getOriginY() != current_costmap_msg->metadata.origin.position.y)
70  {
71  // Update the size of the costmap
72  costmap_->resizeMap(
73  current_costmap_msg->metadata.size_x, current_costmap_msg->metadata.size_y,
74  current_costmap_msg->metadata.resolution,
75  current_costmap_msg->metadata.origin.position.x,
76  current_costmap_msg->metadata.origin.position.y);
77  }
78 
79  unsigned char * master_array = costmap_->getCharMap();
80  unsigned int index = 0;
81  for (unsigned int i = 0; i < current_costmap_msg->metadata.size_x; ++i) {
82  for (unsigned int j = 0; j < current_costmap_msg->metadata.size_y; ++j) {
83  master_array[index] = current_costmap_msg->data[index];
84  ++index;
85  }
86  }
87 }
88 
89 void CostmapSubscriber::costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg)
90 {
91  std::atomic_store(&costmap_msg_, msg);
92  if (!costmap_received_) {
93  costmap_received_ = true;
94  }
95 }
96 
97 } // namespace nav2_costmap_2d
CostmapSubscriber(const nav2_util::LifecycleNode::WeakPtr &parent, const std::string &topic_name)
A constructor.
void costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg)
Callback for the costmap topic.
void toCostmap2D()
Convert an occ grid message into a costmap object.
std::shared_ptr< Costmap2D > getCostmap()
A Get the costmap from topic.