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_msgs/msg/costmap_update.hpp"
25 #include "nav2_util/lifecycle_node.hpp"
40 const nav2_util::LifecycleNode::WeakPtr & parent,
41 const std::string & topic_name);
47 const rclcpp::Node::WeakPtr & parent,
48 const std::string & topic_name);
69 bool isCostmapReceived() {
return costmap_ !=
nullptr;}
70 void processCurrentCostmapMsg();
72 bool haveCostmapParametersChanged();
73 bool hasCostmapSizeChanged();
74 bool hasCostmapResolutionChanged();
75 bool hasCostmapOriginPositionChanged();
77 rclcpp::Subscription<nav2_msgs::msg::Costmap>::SharedPtr costmap_sub_;
78 rclcpp::Subscription<nav2_msgs::msg::CostmapUpdate>::SharedPtr costmap_update_sub_;
80 std::shared_ptr<Costmap2D> costmap_;
81 nav2_msgs::msg::Costmap::SharedPtr costmap_msg_;
83 std::string topic_name_;
84 std::mutex costmap_msg_mutex_;
85 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_costmap_2d")};
Subscribes to the costmap via a ros topic.
CostmapSubscriber(const nav2_util::LifecycleNode::WeakPtr &parent, const std::string &topic_name)
A constructor.
void costmapUpdateCallback(const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg)
Callback for the costmap's update topic.
void costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg)
Callback for the costmap topic.
~CostmapSubscriber()
A destructor.
std::shared_ptr< Costmap2D > getCostmap()
Get current costmap.