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_ros_common/lifecycle_node.hpp"
24 #include "nav2_util/robot_utils.hpp"
39 template<
typename NodeT>
42 const std::string & topic_name,
44 std::string robot_base_frame =
"base_link",
45 double transform_tolerance = 0.1)
47 robot_base_frame_(robot_base_frame),
48 transform_tolerance_(transform_tolerance)
52 footprint_sub_ = nav2::interfaces::create_subscription<geometry_msgs::msg::PolygonStamped>(
70 std::vector<geometry_msgs::msg::Point> & footprint,
71 std_msgs::msg::Header & footprint_header);
81 std::vector<geometry_msgs::msg::Point> & footprint,
82 std_msgs::msg::Header & footprint_header);
90 tf2_ros::Buffer & tf_;
91 std::string robot_base_frame_;
92 double transform_tolerance_;
93 bool footprint_received_{
false};
94 geometry_msgs::msg::PolygonStamped::SharedPtr footprint_;
95 nav2::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr footprint_sub_;