19 #include "nav2_costmap_2d/footprint_subscriber.hpp"
20 #pragma GCC diagnostic push
21 #pragma GCC diagnostic ignored "-Wpedantic"
22 #include "tf2/utils.h"
23 #pragma GCC diagnostic pop
29 const nav2_util::LifecycleNode::WeakPtr & parent,
30 const std::string & topic_name,
32 std::string robot_base_frame,
33 double transform_tolerance)
35 robot_base_frame_(robot_base_frame),
36 transform_tolerance_(transform_tolerance)
38 auto node = parent.lock();
39 footprint_sub_ = node->create_subscription<geometry_msgs::msg::PolygonStamped>(
40 topic_name, rclcpp::SystemDefaultsQoS(),
45 const rclcpp::Node::WeakPtr & parent,
46 const std::string & topic_name,
48 std::string robot_base_frame,
49 double transform_tolerance)
51 robot_base_frame_(robot_base_frame),
52 transform_tolerance_(transform_tolerance)
54 auto node = parent.lock();
55 footprint_sub_ = node->create_subscription<geometry_msgs::msg::PolygonStamped>(
56 topic_name, rclcpp::SystemDefaultsQoS(),
62 std::vector<geometry_msgs::msg::Point> & footprint,
63 std_msgs::msg::Header & footprint_header)
65 if (!footprint_received_) {
69 auto current_footprint = std::atomic_load(&footprint_);
71 std::make_shared<geometry_msgs::msg::Polygon>(current_footprint->polygon));
72 footprint_header = current_footprint->header;
79 std::vector<geometry_msgs::msg::Point> & footprint,
80 std_msgs::msg::Header & footprint_header)
86 geometry_msgs::msg::PoseStamped current_pose;
87 if (!nav2_util::getCurrentPose(
88 current_pose, tf_, footprint_header.frame_id, robot_base_frame_,
89 transform_tolerance_, footprint_header.stamp))
94 double x = current_pose.pose.position.x;
95 double y = current_pose.pose.position.y;
96 double theta = tf2::getYaw(current_pose.pose.orientation);
98 std::vector<geometry_msgs::msg::Point> temp;
102 footprint_header.frame_id = robot_base_frame_;
103 footprint_header.stamp = current_pose.header.stamp;
111 std::atomic_store(&footprint_, msg);
112 if (!footprint_received_) {
113 footprint_received_ =
true;
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::msg::Point > &footprint_spec, std::vector< geometry_msgs::msg::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points)
std::vector< geometry_msgs::msg::Point > toPointVector(geometry_msgs::msg::Polygon::SharedPtr polygon)
Convert Polygon msg to vector of Points.