Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
conversions.cpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include "nav_2d_utils/conversions.hpp"
36 
37 #include <vector>
38 #include <string>
39 
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
49 
50 #include "nav2_util/geometry_utils.hpp"
51 
52 namespace nav_2d_utils
53 {
54 using nav2_util::geometry_utils::orientationAroundZAxis;
55 
56 geometry_msgs::msg::Twist twist2Dto3D(const nav_2d_msgs::msg::Twist2D & cmd_vel_2d)
57 {
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;
62  return cmd_vel;
63 }
64 
65 nav_2d_msgs::msg::Twist2D twist3Dto2D(const geometry_msgs::msg::Twist & cmd_vel)
66 {
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;
71  return cmd_vel_2d;
72 }
73 
74 // nav_2d_msgs::msg::Pose2DStamped stampedPoseToPose2D(const tf2::Stamped<tf2::Pose>& pose)
75 // {
76 // nav_2d_msgs::msg::Pose2DStamped pose2d;
77 // pose2d.header.stamp = pose.stamp_;
78 // pose2d.header.frame_id = pose.frame_id_;
79 // pose2d.pose.x = pose.getOrigin().getX();
80 // pose2d.pose.y = pose.getOrigin().getY();
81 // pose2d.pose.theta = tf::getYaw(pose.getRotation());
82 // return pose2d;
83 // }
84 
85 nav_2d_msgs::msg::Pose2DStamped poseStampedToPose2D(const geometry_msgs::msg::PoseStamped & pose)
86 {
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);
92  return pose2d;
93 }
94 
95 geometry_msgs::msg::Pose2D poseToPose2D(const geometry_msgs::msg::Pose & pose)
96 {
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);
101  return pose2d;
102 }
103 
104 geometry_msgs::msg::Pose pose2DToPose(const geometry_msgs::msg::Pose2D & pose2d)
105 {
106  geometry_msgs::msg::Pose pose;
107  pose.position.x = pose2d.x;
108  pose.position.y = pose2d.y;
109  pose.orientation = orientationAroundZAxis(pose2d.theta);
110  return pose;
111 }
112 
113 geometry_msgs::msg::PoseStamped pose2DToPoseStamped(
114  const nav_2d_msgs::msg::Pose2DStamped & pose2d)
115 {
116  geometry_msgs::msg::PoseStamped pose;
117  pose.header = pose2d.header;
118  pose.pose = pose2DToPose(pose2d.pose);
119  return pose;
120 }
121 
122 geometry_msgs::msg::PoseStamped pose2DToPoseStamped(
123  const geometry_msgs::msg::Pose2D & pose2d,
124  const std::string & frame, const rclcpp::Time & stamp)
125 {
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);
132  return pose;
133 }
134 
135 nav_msgs::msg::Path posesToPath(const std::vector<geometry_msgs::msg::PoseStamped> & poses)
136 {
137  nav_msgs::msg::Path path;
138  if (poses.empty()) {
139  return path;
140  }
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];
146  }
147  return path;
148 }
149 
150 nav_2d_msgs::msg::Path2D pathToPath2D(const nav_msgs::msg::Path & path)
151 {
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));
156  }
157  return path2d;
158 }
159 
160 
161 nav_msgs::msg::Path poses2DToPath(
162  const std::vector<geometry_msgs::msg::Pose2D> & poses,
163  const std::string & frame, const rclcpp::Time & stamp)
164 {
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);
171  }
172  return path;
173 }
174 
175 nav_msgs::msg::Path pathToPath(const nav_2d_msgs::msg::Path2D & path2d)
176 {
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]);
183  }
184  return path;
185 }
186 
187 } // namespace nav_2d_utils