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::Pose2DStamped stampedPoseToPose2D(const tf::Stamped<tf::Pose>& pose)
61 {
62  nav_2d_msgs::Pose2DStamped pose2d;
63  pose2d.header.stamp = pose.stamp_;
64  pose2d.header.frame_id = pose.frame_id_;
65  pose2d.pose.x = pose.getOrigin().getX();
66  pose2d.pose.y = pose.getOrigin().getY();
67  pose2d.pose.theta = tf::getYaw(pose.getRotation());
68  return pose2d;
69 }
70 
71 nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped& pose)
72 {
73  nav_2d_msgs::Pose2DStamped pose2d;
74  pose2d.header = pose.header;
75  pose2d.pose.x = pose.pose.position.x;
76  pose2d.pose.y = pose.pose.position.y;
77  pose2d.pose.theta = tf::getYaw(pose.pose.orientation);
78  return pose2d;
79 }
80 
81 geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D& pose2d)
82 {
83  geometry_msgs::Pose pose;
84  pose.position.x = pose2d.x;
85  pose.position.y = pose2d.y;
86  pose.orientation = tf::createQuaternionMsgFromYaw(pose2d.theta);
87  return pose;
88 }
89 
90 geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped& pose2d)
91 {
92  geometry_msgs::PoseStamped pose;
93  pose.header = pose2d.header;
94  pose.pose = pose2DToPose(pose2d.pose);
95  return pose;
96 }
97 
98 geometry_msgs::PoseStamped pose2DToPoseStamped(const geometry_msgs::Pose2D& pose2d,
99  const std::string& frame, const ros::Time& stamp)
100 {
101  geometry_msgs::PoseStamped pose;
102  pose.header.frame_id = frame;
103  pose.header.stamp = stamp;
104  pose.pose.position.x = pose2d.x;
105  pose.pose.position.y = pose2d.y;
106  pose.pose.orientation = tf::createQuaternionMsgFromYaw(pose2d.theta);
107  return pose;
108 }
109 
110 nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path& path)
111 {
112  nav_2d_msgs::Path2D path2d;
113  path2d.header = path.header;
114  nav_2d_msgs::Pose2DStamped stamped_2d;
115  path2d.poses.resize(path.poses.size());
116  for (unsigned int i = 0; i < path.poses.size(); i++)
117  {
118  stamped_2d = poseStampedToPose2D(path.poses[i]);
119  path2d.poses[i] = stamped_2d.pose;
120  }
121  return path2d;
122 }
123 
124 nav_msgs::Path posesToPath(const std::vector<geometry_msgs::PoseStamped>& poses)
125 {
126  nav_msgs::Path path;
127  if (poses.empty())
128  return path;
129 
130  path.poses.resize(poses.size());
131  path.header.frame_id = poses[0].header.frame_id;
132  path.header.stamp = poses[0].header.stamp;
133  for (unsigned int i = 0; i < poses.size(); i++)
134  {
135  path.poses[i] = poses[i];
136  }
137  return path;
138 }
139 
140 nav_2d_msgs::Path2D posesToPath2D(const std::vector<geometry_msgs::PoseStamped>& poses)
141 {
142  nav_2d_msgs::Path2D path;
143  if (poses.empty())
144  return path;
145 
146  nav_2d_msgs::Pose2DStamped pose;
147  path.poses.resize(poses.size());
148  path.header.frame_id = poses[0].header.frame_id;
149  path.header.stamp = poses[0].header.stamp;
150  for (unsigned int i = 0; i < poses.size(); i++)
151  {
152  pose = poseStampedToPose2D(poses[i]);
153  path.poses[i] = pose.pose;
154  }
155  return path;
156 }
157 
158 
159 nav_msgs::Path poses2DToPath(const std::vector<geometry_msgs::Pose2D>& poses,
160  const std::string& frame, const ros::Time& stamp)
161 {
162  nav_msgs::Path path;
163  path.poses.resize(poses.size());
164  path.header.frame_id = frame;
165  path.header.stamp = stamp;
166  for (unsigned int i = 0; i < poses.size(); i++)
167  {
168  path.poses[i] = pose2DToPoseStamped(poses[i], frame, stamp);
169  }
170  return path;
171 }
172 
173 nav_msgs::Path pathToPath(const nav_2d_msgs::Path2D& path2d)
174 {
175  nav_msgs::Path path;
176  path.header = path2d.header;
177  path.poses.resize(path2d.poses.size());
178  for (unsigned int i = 0; i < path.poses.size(); i++)
179  {
180  path.poses[i].header = path2d.header;
181  path.poses[i].pose = pose2DToPose(path2d.poses[i]);
182  }
183  return path;
184 }
185 
186 nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo& info)
187 {
188  nav_2d_msgs::NavGridInfo msg;
189  msg.width = info.width;
190  msg.height = info.height;
191  msg.resolution = info.resolution;
192  msg.frame_id = info.frame_id;
193  msg.origin_x = info.origin_x;
194  msg.origin_y = info.origin_y;
195  return msg;
196 }
197 
198 nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo& msg)
199 {
201  info.width = msg.width;
202  info.height = msg.height;
203  info.resolution = msg.resolution;
204  info.frame_id = msg.frame_id;
205  info.origin_x = msg.origin_x;
206  info.origin_y = msg.origin_y;
207  return info;
208 }
209 
210 nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData& metadata)
211 {
213  info.resolution = metadata.resolution;
214  info.width = metadata.width;
215  info.height = metadata.height;
216  info.origin_x = metadata.origin.position.x;
217  info.origin_y = metadata.origin.position.y;
218  if (std::abs(tf::getYaw(metadata.origin.orientation)) > 1e-5)
219  {
220  ROS_WARN_NAMED("nav_2d_utils",
221  "Conversion from MapMetaData to NavGridInfo encountered a non-zero rotation. Ignoring.");
222  }
223  return info;
224 }
225 
226 nav_msgs::MapMetaData infoToInfo(const nav_grid::NavGridInfo & info)
227 {
228  nav_msgs::MapMetaData metadata;
229  metadata.resolution = info.resolution;
230  metadata.width = info.width;
231  metadata.height = info.height;
232  metadata.origin.position.x = info.origin_x;
233  metadata.origin.position.y = info.origin_y;
234  metadata.origin.orientation.w = 1.0;
235  return metadata;
236 }
237 
238 nav_2d_msgs::UIntBounds toMsg(const nav_core2::UIntBounds& bounds)
239 {
240  nav_2d_msgs::UIntBounds msg;
241  msg.min_x = bounds.getMinX();
242  msg.min_y = bounds.getMinY();
243  msg.max_x = bounds.getMaxX();
244  msg.max_y = bounds.getMaxY();
245  return msg;
246 }
247 
248 nav_core2::UIntBounds fromMsg(const nav_2d_msgs::UIntBounds& msg)
249 {
250  return nav_core2::UIntBounds(msg.min_x, msg.min_y, msg.max_x, msg.max_y);
251 }
252 
253 
254 } // namespace nav_2d_utils
unsigned int getMaxX() const
geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D &pose2d)
Definition: conversions.cpp:81
#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)
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::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
Definition: conversions.cpp:71
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)
Definition: conversions.cpp:90
nav_2d_msgs::Pose2DStamped stampedPoseToPose2D(const tf::Stamped< tf::Pose > &pose)
Definition: conversions.cpp:60
ros::Time stamp_
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
std::string frame_id_
unsigned int getMaxY() const
nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData &metadata)
nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist &cmd_vel)
Definition: conversions.cpp:51


nav_2d_utils
Author(s):
autogenerated on Wed Jun 26 2019 20:06:11