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_ros_common/lifecycle_node.hpp"
40 const nav2::LifecycleNode::WeakPtr & parent,
41 const std::string & topic_name);
43 template<
typename NodeT>
46 const std::string & topic_name)
47 : topic_name_(topic_name)
49 logger_ = parent->get_logger();
53 costmap_sub_ = nav2::interfaces::create_subscription<nav2_msgs::msg::Costmap>(
58 costmap_update_sub_ = nav2::interfaces::create_subscription<nav2_msgs::msg::CostmapUpdate>(
59 parent, topic_name_ +
"_updates",
82 std::string getFrameID()
const
88 bool isCostmapReceived() {
return costmap_ !=
nullptr;}
89 void processCurrentCostmapMsg();
91 bool haveCostmapParametersChanged();
92 bool hasCostmapSizeChanged();
93 bool hasCostmapResolutionChanged();
94 bool hasCostmapOriginPositionChanged();
96 nav2::Subscription<nav2_msgs::msg::Costmap>::SharedPtr costmap_sub_;
97 nav2::Subscription<nav2_msgs::msg::CostmapUpdate>::SharedPtr costmap_update_sub_;
99 std::shared_ptr<Costmap2D> costmap_;
100 nav2_msgs::msg::Costmap::SharedPtr costmap_msg_;
102 std::string topic_name_;
103 std::string frame_id_;
104 std::mutex costmap_msg_mutex_;
105 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_costmap_2d")};
A QoS profile for latched, reliable topics with a history of 10 messages.
Subscribes to the costmap via a ros topic.
void costmapUpdateCallback(const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg)
Callback for the costmap's update topic.
CostmapSubscriber(const nav2::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.
std::shared_ptr< Costmap2D > getCostmap()
Get current costmap.