35 #include "nav_2d_utils/conversions.hpp"
40 #include "geometry_msgs/msg/pose.hpp"
41 #include "geometry_msgs/msg/pose2_d.hpp"
42 #include "geometry_msgs/msg/pose_stamped.hpp"
43 #include "geometry_msgs/msg/twist.hpp"
44 #include "nav_msgs/msg/path.hpp"
45 #include "nav_2d_msgs/msg/twist2_d.hpp"
46 #include "nav_2d_msgs/msg/pose2_d_stamped.hpp"
47 #include "nav_2d_msgs/msg/path2_d.hpp"
48 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
49 #pragma GCC diagnostic push
50 #pragma GCC diagnostic ignored "-Wpedantic"
51 #include "tf2/utils.hpp"
52 #pragma GCC diagnostic pop
54 #include "nav2_util/geometry_utils.hpp"
56 namespace nav_2d_utils
58 using nav2_util::geometry_utils::orientationAroundZAxis;
60 geometry_msgs::msg::Twist twist2Dto3D(
const nav_2d_msgs::msg::Twist2D & cmd_vel_2d)
62 geometry_msgs::msg::Twist cmd_vel;
63 cmd_vel.linear.x = cmd_vel_2d.x;
64 cmd_vel.linear.y = cmd_vel_2d.y;
65 cmd_vel.angular.z = cmd_vel_2d.theta;
69 nav_2d_msgs::msg::Twist2D twist3Dto2D(
const geometry_msgs::msg::Twist & cmd_vel)
71 nav_2d_msgs::msg::Twist2D cmd_vel_2d;
72 cmd_vel_2d.x = cmd_vel.linear.x;
73 cmd_vel_2d.y = cmd_vel.linear.y;
74 cmd_vel_2d.theta = cmd_vel.angular.z;
89 nav_2d_msgs::msg::Pose2DStamped poseStampedToPose2D(
const geometry_msgs::msg::PoseStamped & pose)
91 nav_2d_msgs::msg::Pose2DStamped pose2d;
92 pose2d.header = pose.header;
93 pose2d.pose.x = pose.pose.position.x;
94 pose2d.pose.y = pose.pose.position.y;
95 pose2d.pose.theta = tf2::getYaw(pose.pose.orientation);
99 geometry_msgs::msg::Pose2D poseToPose2D(
const geometry_msgs::msg::Pose & pose)
101 geometry_msgs::msg::Pose2D pose2d;
102 pose2d.x = pose.position.x;
103 pose2d.y = pose.position.y;
104 pose2d.theta = tf2::getYaw(pose.orientation);
108 geometry_msgs::msg::Pose pose2DToPose(
const geometry_msgs::msg::Pose2D & pose2d)
110 geometry_msgs::msg::Pose pose;
111 pose.position.x = pose2d.x;
112 pose.position.y = pose2d.y;
113 pose.orientation = orientationAroundZAxis(pose2d.theta);
117 geometry_msgs::msg::PoseStamped pose2DToPoseStamped(
118 const nav_2d_msgs::msg::Pose2DStamped & pose2d)
120 geometry_msgs::msg::PoseStamped pose;
121 pose.header = pose2d.header;
122 pose.pose = pose2DToPose(pose2d.pose);
126 geometry_msgs::msg::PoseStamped pose2DToPoseStamped(
127 const geometry_msgs::msg::Pose2D & pose2d,
128 const std::string & frame,
const rclcpp::Time & stamp)
130 geometry_msgs::msg::PoseStamped pose;
131 pose.header.frame_id = frame;
132 pose.header.stamp = stamp;
133 pose.pose.position.x = pose2d.x;
134 pose.pose.position.y = pose2d.y;
135 pose.pose.orientation = orientationAroundZAxis(pose2d.theta);
139 nav_msgs::msg::Path posesToPath(
const std::vector<geometry_msgs::msg::PoseStamped> & poses)
141 nav_msgs::msg::Path path;
145 path.poses.resize(poses.size());
146 path.header.frame_id = poses[0].header.frame_id;
147 path.header.stamp = poses[0].header.stamp;
148 for (
unsigned int i = 0; i < poses.size(); i++) {
149 path.poses[i] = poses[i];
154 nav_2d_msgs::msg::Path2D pathToPath2D(
const nav_msgs::msg::Path & path)
156 nav_2d_msgs::msg::Path2D path2d;
157 path2d.header = path.header;
158 for (
auto & pose : path.poses) {
159 path2d.poses.push_back(poseToPose2D(pose.pose));
165 nav_msgs::msg::Path poses2DToPath(
166 const std::vector<geometry_msgs::msg::Pose2D> & poses,
167 const std::string & frame,
const rclcpp::Time & stamp)
169 nav_msgs::msg::Path path;
170 path.poses.resize(poses.size());
171 path.header.frame_id = frame;
172 path.header.stamp = stamp;
173 for (
unsigned int i = 0; i < poses.size(); i++) {
174 path.poses[i] = pose2DToPoseStamped(poses[i], frame, stamp);
179 nav_msgs::msg::Path pathToPath(
const nav_2d_msgs::msg::Path2D & path2d)
181 nav_msgs::msg::Path path;
182 path.header = path2d.header;
183 path.poses.resize(path2d.poses.size());
184 for (
unsigned int i = 0; i < path.poses.size(); i++) {
185 path.poses[i].header = path2d.header;
186 path.poses[i].pose = pose2DToPose(path2d.poses[i]);