35 #include "nav_2d_utils/conversions.hpp"
40 #include "geometry_msgs/msg/pose.hpp"
41 #include "geometry_msgs/msg/pose_stamped.hpp"
42 #include "geometry_msgs/msg/twist.hpp"
43 #include "nav_msgs/msg/path.hpp"
44 #include "nav_2d_msgs/msg/twist2_d.hpp"
45 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
46 #pragma GCC diagnostic push
47 #pragma GCC diagnostic ignored "-Wpedantic"
48 #include "tf2/utils.hpp"
49 #pragma GCC diagnostic pop
51 #include "nav2_util/geometry_utils.hpp"
53 namespace nav_2d_utils
55 using nav2_util::geometry_utils::orientationAroundZAxis;
57 geometry_msgs::msg::Twist twist2Dto3D(
const nav_2d_msgs::msg::Twist2D & cmd_vel_2d)
59 geometry_msgs::msg::Twist cmd_vel;
60 cmd_vel.linear.x = cmd_vel_2d.x;
61 cmd_vel.linear.y = cmd_vel_2d.y;
62 cmd_vel.angular.z = cmd_vel_2d.theta;
66 nav_2d_msgs::msg::Twist2D twist3Dto2D(
const geometry_msgs::msg::Twist & cmd_vel)
68 nav_2d_msgs::msg::Twist2D cmd_vel_2d;
69 cmd_vel_2d.x = cmd_vel.linear.x;
70 cmd_vel_2d.y = cmd_vel.linear.y;
71 cmd_vel_2d.theta = cmd_vel.angular.z;
75 nav_msgs::msg::Path posesToPath(
76 const std::vector<geometry_msgs::msg::Pose> & poses,
77 const std::string & frame,
const rclcpp::Time & stamp)
79 nav_msgs::msg::Path path;
80 path.poses.resize(poses.size());
81 path.header.frame_id = frame;
82 path.header.stamp = stamp;
83 for (
unsigned int i = 0; i < poses.size(); i++) {
84 path.poses[i].header.frame_id = frame;
85 path.poses[i].header.stamp = stamp;
86 path.poses[i].pose = poses[i];