15 #ifndef NAV2_COSTMAP_2D__FOOTPRINT_SUBSCRIBER_HPP_
16 #define NAV2_COSTMAP_2D__FOOTPRINT_SUBSCRIBER_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "nav2_costmap_2d/footprint.hpp"
23 #include "nav2_util/lifecycle_node.hpp"
24 #include "nav2_util/robot_utils.hpp"
40 const nav2_util::LifecycleNode::WeakPtr & parent,
41 const std::string & topic_name,
43 std::string robot_base_frame =
"base_link",
44 double transform_tolerance = 0.1);
50 const rclcpp::Node::WeakPtr & parent,
51 const std::string & topic_name,
53 std::string robot_base_frame =
"base_link",
54 double transform_tolerance = 0.1);
69 std::vector<geometry_msgs::msg::Point> & footprint,
70 std_msgs::msg::Header & footprint_header);
80 std::vector<geometry_msgs::msg::Point> & footprint,
81 std_msgs::msg::Header & footprint_header);
89 tf2_ros::Buffer & tf_;
90 std::string robot_base_frame_;
91 double transform_tolerance_;
92 bool footprint_received_{
false};
93 geometry_msgs::msg::PolygonStamped::SharedPtr footprint_;
94 rclcpp::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr footprint_sub_;