Nav2 Navigation Stack - kilted  kilted
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 "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
53 
54 #include "nav2_util/geometry_utils.hpp"
55 
56 namespace nav_2d_utils
57 {
58 using nav2_util::geometry_utils::orientationAroundZAxis;
59 
60 geometry_msgs::msg::Twist twist2Dto3D(const nav_2d_msgs::msg::Twist2D & cmd_vel_2d)
61 {
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;
66  return cmd_vel;
67 }
68 
69 nav_2d_msgs::msg::Twist2D twist3Dto2D(const geometry_msgs::msg::Twist & cmd_vel)
70 {
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;
75  return cmd_vel_2d;
76 }
77 
78 // nav_2d_msgs::msg::Pose2DStamped stampedPoseToPose2D(const tf2::Stamped<tf2::Pose>& pose)
79 // {
80 // nav_2d_msgs::msg::Pose2DStamped pose2d;
81 // pose2d.header.stamp = pose.stamp_;
82 // pose2d.header.frame_id = pose.frame_id_;
83 // pose2d.pose.x = pose.getOrigin().getX();
84 // pose2d.pose.y = pose.getOrigin().getY();
85 // pose2d.pose.theta = tf::getYaw(pose.getRotation());
86 // return pose2d;
87 // }
88 
89 nav_2d_msgs::msg::Pose2DStamped poseStampedToPose2D(const geometry_msgs::msg::PoseStamped & pose)
90 {
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);
96  return pose2d;
97 }
98 
99 geometry_msgs::msg::Pose2D poseToPose2D(const geometry_msgs::msg::Pose & pose)
100 {
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);
105  return pose2d;
106 }
107 
108 geometry_msgs::msg::Pose pose2DToPose(const geometry_msgs::msg::Pose2D & pose2d)
109 {
110  geometry_msgs::msg::Pose pose;
111  pose.position.x = pose2d.x;
112  pose.position.y = pose2d.y;
113  pose.orientation = orientationAroundZAxis(pose2d.theta);
114  return pose;
115 }
116 
117 geometry_msgs::msg::PoseStamped pose2DToPoseStamped(
118  const nav_2d_msgs::msg::Pose2DStamped & pose2d)
119 {
120  geometry_msgs::msg::PoseStamped pose;
121  pose.header = pose2d.header;
122  pose.pose = pose2DToPose(pose2d.pose);
123  return pose;
124 }
125 
126 geometry_msgs::msg::PoseStamped pose2DToPoseStamped(
127  const geometry_msgs::msg::Pose2D & pose2d,
128  const std::string & frame, const rclcpp::Time & stamp)
129 {
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);
136  return pose;
137 }
138 
139 nav_msgs::msg::Path posesToPath(const std::vector<geometry_msgs::msg::PoseStamped> & poses)
140 {
141  nav_msgs::msg::Path path;
142  if (poses.empty()) {
143  return path;
144  }
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];
150  }
151  return path;
152 }
153 
154 nav_2d_msgs::msg::Path2D pathToPath2D(const nav_msgs::msg::Path & path)
155 {
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));
160  }
161  return path2d;
162 }
163 
164 
165 nav_msgs::msg::Path poses2DToPath(
166  const std::vector<geometry_msgs::msg::Pose2D> & poses,
167  const std::string & frame, const rclcpp::Time & stamp)
168 {
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);
175  }
176  return path;
177 }
178 
179 nav_msgs::msg::Path pathToPath(const nav_2d_msgs::msg::Path2D & path2d)
180 {
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]);
187  }
188  return path;
189 }
190 
191 } // namespace nav_2d_utils