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 "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
45 #pragma GCC diagnostic push
46 #pragma GCC diagnostic ignored "-Wpedantic"
47 #include "tf2/utils.h"
48 #pragma GCC diagnostic pop
50 #include "nav2_util/geometry_utils.hpp"
52 namespace nav_2d_utils
54 using nav2_util::geometry_utils::orientationAroundZAxis;
56 geometry_msgs::msg::Twist twist2Dto3D(
const nav_2d_msgs::msg::Twist2D & cmd_vel_2d)
58 geometry_msgs::msg::Twist cmd_vel;
59 cmd_vel.linear.x = cmd_vel_2d.x;
60 cmd_vel.linear.y = cmd_vel_2d.y;
61 cmd_vel.angular.z = cmd_vel_2d.theta;
65 nav_2d_msgs::msg::Twist2D twist3Dto2D(
const geometry_msgs::msg::Twist & cmd_vel)
67 nav_2d_msgs::msg::Twist2D cmd_vel_2d;
68 cmd_vel_2d.x = cmd_vel.linear.x;
69 cmd_vel_2d.y = cmd_vel.linear.y;
70 cmd_vel_2d.theta = cmd_vel.angular.z;
85 nav_2d_msgs::msg::Pose2DStamped poseStampedToPose2D(
const geometry_msgs::msg::PoseStamped & pose)
87 nav_2d_msgs::msg::Pose2DStamped pose2d;
88 pose2d.header = pose.header;
89 pose2d.pose.x = pose.pose.position.x;
90 pose2d.pose.y = pose.pose.position.y;
91 pose2d.pose.theta = tf2::getYaw(pose.pose.orientation);
95 geometry_msgs::msg::Pose2D poseToPose2D(
const geometry_msgs::msg::Pose & pose)
97 geometry_msgs::msg::Pose2D pose2d;
98 pose2d.x = pose.position.x;
99 pose2d.y = pose.position.y;
100 pose2d.theta = tf2::getYaw(pose.orientation);
104 geometry_msgs::msg::Pose pose2DToPose(
const geometry_msgs::msg::Pose2D & pose2d)
106 geometry_msgs::msg::Pose pose;
107 pose.position.x = pose2d.x;
108 pose.position.y = pose2d.y;
109 pose.orientation = orientationAroundZAxis(pose2d.theta);
113 geometry_msgs::msg::PoseStamped pose2DToPoseStamped(
114 const nav_2d_msgs::msg::Pose2DStamped & pose2d)
116 geometry_msgs::msg::PoseStamped pose;
117 pose.header = pose2d.header;
118 pose.pose = pose2DToPose(pose2d.pose);
122 geometry_msgs::msg::PoseStamped pose2DToPoseStamped(
123 const geometry_msgs::msg::Pose2D & pose2d,
124 const std::string & frame,
const rclcpp::Time & stamp)
126 geometry_msgs::msg::PoseStamped pose;
127 pose.header.frame_id = frame;
128 pose.header.stamp = stamp;
129 pose.pose.position.x = pose2d.x;
130 pose.pose.position.y = pose2d.y;
131 pose.pose.orientation = orientationAroundZAxis(pose2d.theta);
135 nav_msgs::msg::Path posesToPath(
const std::vector<geometry_msgs::msg::PoseStamped> & poses)
137 nav_msgs::msg::Path path;
141 path.poses.resize(poses.size());
142 path.header.frame_id = poses[0].header.frame_id;
143 path.header.stamp = poses[0].header.stamp;
144 for (
unsigned int i = 0; i < poses.size(); i++) {
145 path.poses[i] = poses[i];
150 nav_2d_msgs::msg::Path2D pathToPath2D(
const nav_msgs::msg::Path & path)
152 nav_2d_msgs::msg::Path2D path2d;
153 path2d.header = path.header;
154 for (
auto & pose : path.poses) {
155 path2d.poses.push_back(poseToPose2D(pose.pose));
161 nav_msgs::msg::Path poses2DToPath(
162 const std::vector<geometry_msgs::msg::Pose2D> & poses,
163 const std::string & frame,
const rclcpp::Time & stamp)
165 nav_msgs::msg::Path path;
166 path.poses.resize(poses.size());
167 path.header.frame_id = frame;
168 path.header.stamp = stamp;
169 for (
unsigned int i = 0; i < poses.size(); i++) {
170 path.poses[i] = pose2DToPoseStamped(poses[i], frame, stamp);
175 nav_msgs::msg::Path pathToPath(
const nav_2d_msgs::msg::Path2D & path2d)
177 nav_msgs::msg::Path path;
178 path.header = path2d.header;
179 path.poses.resize(path2d.poses.size());
180 for (
unsigned int i = 0; i < path.poses.size(); i++) {
181 path.poses[i].header = path2d.header;
182 path.poses[i].pose = pose2DToPose(path2d.poses[i]);