18 #include "nav2_costmap_2d/costmap_subscriber.hpp"
24 const nav2_util::LifecycleNode::WeakPtr & parent,
25 const std::string & topic_name)
26 : topic_name_(topic_name)
28 auto node = parent.lock();
29 costmap_sub_ = node->create_subscription<nav2_msgs::msg::Costmap>(
31 rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
36 const rclcpp::Node::WeakPtr & parent,
37 const std::string & topic_name)
38 : topic_name_(topic_name)
40 auto node = parent.lock();
41 costmap_sub_ = node->create_subscription<nav2_msgs::msg::Costmap>(
43 rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
49 if (!costmap_received_) {
50 throw std::runtime_error(
"Costmap is not available");
58 auto current_costmap_msg = std::atomic_load(&costmap_msg_);
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 ||
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)
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);
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];
91 std::atomic_store(&costmap_msg_, msg);
92 if (!costmap_received_) {
93 costmap_received_ =
true;
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.