|
Nav2 Navigation Stack - kilted
kilted
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 () |
| Get current costmap. | |
| void | costmapCallback (const nav2_msgs::msg::Costmap::SharedPtr msg) |
| Callback for the costmap topic. | |
| void | costmapUpdateCallback (const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg) |
| Callback for the costmap's update topic. | |
| std::string | getFrameID () const |
Protected Attributes | |
| rclcpp::Subscription< nav2_msgs::msg::Costmap >::SharedPtr | costmap_sub_ |
| rclcpp::Subscription< nav2_msgs::msg::CostmapUpdate >::SharedPtr | costmap_update_sub_ |
| std::shared_ptr< Costmap2D > | costmap_ |
| nav2_msgs::msg::Costmap::SharedPtr | costmap_msg_ |
| std::string | topic_name_ |
| std::string | frame_id_ |
| std::mutex | costmap_msg_mutex_ |
| rclcpp::Logger | logger_ {rclcpp::get_logger("nav2_costmap_2d")} |
Subscribes to the costmap via a ros topic.
Definition at line 33 of file costmap_subscriber.hpp.