|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
Subscribes to the costmap via a ros topic. More...
#include <nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp>

Public Member Functions | |
| CostmapSubscriber (const nav2_util::LifecycleNode::WeakPtr &parent, const std::string &topic_name) | |
| A constructor. | |
| CostmapSubscriber (const rclcpp::Node::WeakPtr &parent, const std::string &topic_name) | |
| A constructor. | |
| ~CostmapSubscriber () | |
| A destructor. | |
| std::shared_ptr< Costmap2D > | getCostmap () |
| A Get the costmap from topic. | |
| void | toCostmap2D () |
| Convert an occ grid message into a costmap object. | |
| void | costmapCallback (const nav2_msgs::msg::Costmap::SharedPtr msg) |
| Callback for the costmap topic. | |
Protected Attributes | |
| std::shared_ptr< Costmap2D > | costmap_ |
| nav2_msgs::msg::Costmap::SharedPtr | costmap_msg_ |
| std::string | topic_name_ |
| bool | costmap_received_ {false} |
| rclcpp::Subscription< nav2_msgs::msg::Costmap >::SharedPtr | costmap_sub_ |
Subscribes to the costmap via a ros topic.
Definition at line 32 of file costmap_subscriber.hpp.