conversions.cpp
Go to the documentation of this file.
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  */
35 #include <vector>
36 #include <string>
37 
38 namespace nav_2d_utils
39 {
40 
41 geometry_msgs::Twist twist2Dto3D(const nav_2d_msgs::Twist2D& cmd_vel_2d)
42 {
43  geometry_msgs::Twist cmd_vel;
44  cmd_vel.linear.x = cmd_vel_2d.x;
45  cmd_vel.linear.y = cmd_vel_2d.y;
46  cmd_vel.angular.z = cmd_vel_2d.theta;
47  return cmd_vel;
48 }
49 
50 
51 nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist& cmd_vel)
52 {
53  nav_2d_msgs::Twist2D cmd_vel_2d;
54  cmd_vel_2d.x = cmd_vel.linear.x;
55  cmd_vel_2d.y = cmd_vel.linear.y;
56  cmd_vel_2d.theta = cmd_vel.angular.z;
57  return cmd_vel_2d;
58 }
59 
60 nav_2d_msgs::Point2D pointToPoint2D(const geometry_msgs::Point& point)
61 {
62  nav_2d_msgs::Point2D output;
63  output.x = point.x;
64  output.y = point.y;
65  return output;
66 }
67 
68 nav_2d_msgs::Point2D pointToPoint2D(const geometry_msgs::Point32& point)
69 {
70  nav_2d_msgs::Point2D output;
71  output.x = point.x;
72  output.y = point.y;
73  return output;
74 }
75 
76 geometry_msgs::Point pointToPoint3D(const nav_2d_msgs::Point2D& point)
77 {
78  geometry_msgs::Point output;
79  output.x = point.x;
80  output.y = point.y;
81  return output;
82 }
83 
84 geometry_msgs::Point32 pointToPoint32(const nav_2d_msgs::Point2D& point)
85 {
86  geometry_msgs::Point32 output;
87  output.x = point.x;
88  output.y = point.y;
89  return output;
90 }
91 
92 nav_2d_msgs::Pose2DStamped stampedPoseToPose2D(const tf::Stamped<tf::Pose>& pose)
93 {
94  nav_2d_msgs::Pose2DStamped pose2d;
95  pose2d.header.stamp = pose.stamp_;
96  pose2d.header.frame_id = pose.frame_id_;
97  pose2d.pose.x = pose.getOrigin().getX();
98  pose2d.pose.y = pose.getOrigin().getY();
99  pose2d.pose.theta = tf::getYaw(pose.getRotation());
100  return pose2d;
101 }
102 
103 nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped& pose)
104 {
105  nav_2d_msgs::Pose2DStamped pose2d;
106  pose2d.header = pose.header;
107  pose2d.pose.x = pose.pose.position.x;
108  pose2d.pose.y = pose.pose.position.y;
109  pose2d.pose.theta = tf::getYaw(pose.pose.orientation);
110  return pose2d;
111 }
112 
113 geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D& pose2d)
114 {
115  geometry_msgs::Pose pose;
116  pose.position.x = pose2d.x;
117  pose.position.y = pose2d.y;
118  pose.orientation = tf::createQuaternionMsgFromYaw(pose2d.theta);
119  return pose;
120 }
121 
122 geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped& pose2d)
123 {
124  geometry_msgs::PoseStamped pose;
125  pose.header = pose2d.header;
126  pose.pose = pose2DToPose(pose2d.pose);
127  return pose;
128 }
129 
130 geometry_msgs::PoseStamped pose2DToPoseStamped(const geometry_msgs::Pose2D& pose2d,
131  const std::string& frame, const ros::Time& stamp)
132 {
133  geometry_msgs::PoseStamped pose;
134  pose.header.frame_id = frame;
135  pose.header.stamp = stamp;
136  pose.pose.position.x = pose2d.x;
137  pose.pose.position.y = pose2d.y;
138  pose.pose.orientation = tf::createQuaternionMsgFromYaw(pose2d.theta);
139  return pose;
140 }
141 
142 nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path& path)
143 {
144  nav_2d_msgs::Path2D path2d;
145  path2d.header = path.header;
146  nav_2d_msgs::Pose2DStamped stamped_2d;
147  path2d.poses.resize(path.poses.size());
148  for (unsigned int i = 0; i < path.poses.size(); i++)
149  {
150  stamped_2d = poseStampedToPose2D(path.poses[i]);
151  path2d.poses[i] = stamped_2d.pose;
152  }
153  return path2d;
154 }
155 
156 nav_msgs::Path posesToPath(const std::vector<geometry_msgs::PoseStamped>& poses)
157 {
158  nav_msgs::Path path;
159  if (poses.empty())
160  return path;
161 
162  path.poses.resize(poses.size());
163  path.header.frame_id = poses[0].header.frame_id;
164  path.header.stamp = poses[0].header.stamp;
165  for (unsigned int i = 0; i < poses.size(); i++)
166  {
167  path.poses[i] = poses[i];
168  }
169  return path;
170 }
171 
172 nav_2d_msgs::Path2D posesToPath2D(const std::vector<geometry_msgs::PoseStamped>& poses)
173 {
174  nav_2d_msgs::Path2D path;
175  if (poses.empty())
176  return path;
177 
178  nav_2d_msgs::Pose2DStamped pose;
179  path.poses.resize(poses.size());
180  path.header.frame_id = poses[0].header.frame_id;
181  path.header.stamp = poses[0].header.stamp;
182  for (unsigned int i = 0; i < poses.size(); i++)
183  {
184  pose = poseStampedToPose2D(poses[i]);
185  path.poses[i] = pose.pose;
186  }
187  return path;
188 }
189 
190 
191 nav_msgs::Path poses2DToPath(const std::vector<geometry_msgs::Pose2D>& poses,
192  const std::string& frame, const ros::Time& stamp)
193 {
194  nav_msgs::Path path;
195  path.poses.resize(poses.size());
196  path.header.frame_id = frame;
197  path.header.stamp = stamp;
198  for (unsigned int i = 0; i < poses.size(); i++)
199  {
200  path.poses[i] = pose2DToPoseStamped(poses[i], frame, stamp);
201  }
202  return path;
203 }
204 
205 nav_msgs::Path pathToPath(const nav_2d_msgs::Path2D& path2d)
206 {
207  nav_msgs::Path path;
208  path.header = path2d.header;
209  path.poses.resize(path2d.poses.size());
210  for (unsigned int i = 0; i < path.poses.size(); i++)
211  {
212  path.poses[i].header = path2d.header;
213  path.poses[i].pose = pose2DToPose(path2d.poses[i]);
214  }
215  return path;
216 }
217 
218 geometry_msgs::Polygon polygon2Dto3D(const nav_2d_msgs::Polygon2D& polygon_2d)
219 {
220  geometry_msgs::Polygon polygon;
221  polygon.points.reserve(polygon_2d.points.size());
222  for (const auto& pt : polygon_2d.points)
223  {
224  polygon.points.push_back(pointToPoint32(pt));
225  }
226  return polygon;
227 }
228 
229 nav_2d_msgs::Polygon2D polygon3Dto2D(const geometry_msgs::Polygon& polygon_3d)
230 {
231  nav_2d_msgs::Polygon2D polygon;
232  polygon.points.reserve(polygon_3d.points.size());
233  for (const auto& pt : polygon_3d.points)
234  {
235  polygon.points.push_back(pointToPoint2D(pt));
236  }
237  return polygon;
238 }
239 
240 geometry_msgs::PolygonStamped polygon2Dto3D(const nav_2d_msgs::Polygon2DStamped& polygon_2d)
241 {
242  geometry_msgs::PolygonStamped polygon;
243  polygon.header = polygon_2d.header;
244  polygon.polygon = polygon2Dto3D(polygon_2d.polygon);
245  return polygon;
246 }
247 
248 nav_2d_msgs::Polygon2DStamped polygon3Dto2D(const geometry_msgs::PolygonStamped& polygon_3d)
249 {
250  nav_2d_msgs::Polygon2DStamped polygon;
251  polygon.header = polygon_3d.header;
252  polygon.polygon = polygon3Dto2D(polygon_3d.polygon);
253  return polygon;
254 }
255 
256 nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo& info)
257 {
258  nav_2d_msgs::NavGridInfo msg;
259  msg.width = info.width;
260  msg.height = info.height;
261  msg.resolution = info.resolution;
262  msg.frame_id = info.frame_id;
263  msg.origin_x = info.origin_x;
264  msg.origin_y = info.origin_y;
265  return msg;
266 }
267 
268 nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo& msg)
269 {
271  info.width = msg.width;
272  info.height = msg.height;
273  info.resolution = msg.resolution;
274  info.frame_id = msg.frame_id;
275  info.origin_x = msg.origin_x;
276  info.origin_y = msg.origin_y;
277  return info;
278 }
279 
280 nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData& metadata, const std::string& frame)
281 {
283  info.frame_id = frame;
284  info.resolution = metadata.resolution;
285  info.width = metadata.width;
286  info.height = metadata.height;
287  info.origin_x = metadata.origin.position.x;
288  info.origin_y = metadata.origin.position.y;
289  if (std::abs(tf::getYaw(metadata.origin.orientation)) > 1e-5)
290  {
291  ROS_WARN_NAMED("nav_2d_utils",
292  "Conversion from MapMetaData to NavGridInfo encountered a non-zero rotation. Ignoring.");
293  }
294  return info;
295 }
296 
297 geometry_msgs::Pose getOrigin3D(const nav_grid::NavGridInfo& info)
298 {
299  geometry_msgs::Pose origin;
300  origin.position.x = info.origin_x;
301  origin.position.y = info.origin_y;
302  origin.orientation.w = 1.0;
303  return origin;
304 }
305 
306 geometry_msgs::Pose2D getOrigin2D(const nav_grid::NavGridInfo& info)
307 {
308  geometry_msgs::Pose2D origin;
309  origin.x = info.origin_x;
310  origin.y = info.origin_y;
311  return origin;
312 }
313 
314 nav_msgs::MapMetaData infoToInfo(const nav_grid::NavGridInfo & info)
315 {
316  nav_msgs::MapMetaData metadata;
317  metadata.resolution = info.resolution;
318  metadata.width = info.width;
319  metadata.height = info.height;
320  metadata.origin = getOrigin3D(info);
321  return metadata;
322 }
323 
324 nav_2d_msgs::UIntBounds toMsg(const nav_core2::UIntBounds& bounds)
325 {
326  nav_2d_msgs::UIntBounds msg;
327  msg.min_x = bounds.getMinX();
328  msg.min_y = bounds.getMinY();
329  msg.max_x = bounds.getMaxX();
330  msg.max_y = bounds.getMaxY();
331  return msg;
332 }
333 
334 nav_core2::UIntBounds fromMsg(const nav_2d_msgs::UIntBounds& msg)
335 {
336  return nav_core2::UIntBounds(msg.min_x, msg.min_y, msg.max_x, msg.max_y);
337 }
338 
339 
340 } // namespace nav_2d_utils
nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData &metadata, const std::string &frame)
geometry_msgs::Point32 pointToPoint32(const nav_2d_msgs::Point2D &point)
Definition: conversions.cpp:84
unsigned int getMaxX() const
geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D &pose2d)
A set of utility functions for Bounds objects interacting with other messages/types.
Definition: bounds.h:45
#define ROS_WARN_NAMED(name,...)
unsigned int getMinX() const
unsigned int getMinY() const
static double getYaw(const Quaternion &bt_q)
nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo &info)
nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path &path)
geometry_msgs::Point pointToPoint3D(const nav_2d_msgs::Point2D &point)
Definition: conversions.cpp:76
nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo &msg)
geometry_msgs::Twist twist2Dto3D(const nav_2d_msgs::Twist2D &cmd_vel_2d)
Definition: conversions.cpp:41
nav_msgs::Path posesToPath(const std::vector< geometry_msgs::PoseStamped > &poses)
nav_2d_msgs::Path2D posesToPath2D(const std::vector< geometry_msgs::PoseStamped > &poses)
nav_2d_msgs::Point2D pointToPoint2D(const geometry_msgs::Point &point)
Definition: conversions.cpp:60
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
nav_msgs::Path poses2DToPath(const std::vector< geometry_msgs::Pose2D > &poses, const std::string &frame, const ros::Time &stamp)
geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped &pose2d)
geometry_msgs::Pose getOrigin3D(const nav_grid::NavGridInfo &info)
nav_2d_msgs::Pose2DStamped stampedPoseToPose2D(const tf::Stamped< tf::Pose > &pose)
Definition: conversions.cpp:92
geometry_msgs::Pose2D getOrigin2D(const nav_grid::NavGridInfo &info)
ros::Time stamp_
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
std::string frame_id_
geometry_msgs::Polygon polygon2Dto3D(const nav_2d_msgs::Polygon2D &polygon_2d)
nav_2d_msgs::Polygon2D polygon3Dto2D(const geometry_msgs::Polygon &polygon_3d)
unsigned int getMaxY() const
nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist &cmd_vel)
Definition: conversions.cpp:51


nav_2d_utils
Author(s):
autogenerated on Sun Jan 10 2021 04:08:32