15 #ifndef NAV2_COSTMAP_2D__COSTMAP_SUBSCRIBER_HPP_
16 #define NAV2_COSTMAP_2D__COSTMAP_SUBSCRIBER_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "nav2_costmap_2d/costmap_2d.hpp"
23 #include "nav2_msgs/msg/costmap.hpp"
24 #include "nav2_util/lifecycle_node.hpp"
39 const nav2_util::LifecycleNode::WeakPtr & parent,
40 const std::string & topic_name);
46 const rclcpp::Node::WeakPtr & parent,
47 const std::string & topic_name);
69 std::shared_ptr<Costmap2D> costmap_;
70 nav2_msgs::msg::Costmap::SharedPtr costmap_msg_;
71 std::string topic_name_;
72 bool costmap_received_{
false};
73 rclcpp::Subscription<nav2_msgs::msg::Costmap>::SharedPtr costmap_sub_;
Subscribes to the costmap via a ros topic.
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.
~CostmapSubscriber()
A destructor.
void toCostmap2D()
Convert an occ grid message into a costmap object.
std::shared_ptr< Costmap2D > getCostmap()
A Get the costmap from topic.