19 #include "nav2_costmap_2d/footprint_subscriber.hpp"
20 #pragma GCC diagnostic push
21 #pragma GCC diagnostic ignored "-Wpedantic"
22 #include "tf2/utils.hpp"
23 #pragma GCC diagnostic pop
30 std::vector<geometry_msgs::msg::Point> & footprint,
31 std_msgs::msg::Header & footprint_header)
33 if (!footprint_received_) {
37 auto current_footprint = std::atomic_load(&footprint_);
39 footprint_header = current_footprint->header;
46 std::vector<geometry_msgs::msg::Point> & footprint,
47 std_msgs::msg::Header & footprint_header)
53 geometry_msgs::msg::PoseStamped current_pose;
54 if (!nav2_util::getCurrentPose(
55 current_pose, tf_, footprint_header.frame_id, robot_base_frame_,
56 transform_tolerance_, footprint_header.stamp))
61 double x = current_pose.pose.position.x;
62 double y = current_pose.pose.position.y;
63 double theta = tf2::getYaw(current_pose.pose.orientation);
65 std::vector<geometry_msgs::msg::Point> temp;
69 footprint_header.frame_id = robot_base_frame_;
70 footprint_header.stamp = current_pose.header.stamp;
78 std::atomic_store(&footprint_, msg);
79 if (!footprint_received_) {
80 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(const geometry_msgs::msg::Polygon &polygon)
Convert Polygon msg to vector of Points.