Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <nav_2d_utils/conversions.h>
00035 #include <vector>
00036 #include <string>
00037
00038 namespace nav_2d_utils
00039 {
00040
00041 geometry_msgs::Twist twist2Dto3D(const nav_2d_msgs::Twist2D& cmd_vel_2d)
00042 {
00043 geometry_msgs::Twist cmd_vel;
00044 cmd_vel.linear.x = cmd_vel_2d.x;
00045 cmd_vel.linear.y = cmd_vel_2d.y;
00046 cmd_vel.angular.z = cmd_vel_2d.theta;
00047 return cmd_vel;
00048 }
00049
00050
00051 nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist& cmd_vel)
00052 {
00053 nav_2d_msgs::Twist2D cmd_vel_2d;
00054 cmd_vel_2d.x = cmd_vel.linear.x;
00055 cmd_vel_2d.y = cmd_vel.linear.y;
00056 cmd_vel_2d.theta = cmd_vel.angular.z;
00057 return cmd_vel_2d;
00058 }
00059
00060 nav_2d_msgs::Pose2DStamped stampedPoseToPose2D(const tf::Stamped<tf::Pose>& pose)
00061 {
00062 nav_2d_msgs::Pose2DStamped pose2d;
00063 pose2d.header.stamp = pose.stamp_;
00064 pose2d.header.frame_id = pose.frame_id_;
00065 pose2d.pose.x = pose.getOrigin().getX();
00066 pose2d.pose.y = pose.getOrigin().getY();
00067 pose2d.pose.theta = tf::getYaw(pose.getRotation());
00068 return pose2d;
00069 }
00070
00071 nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped& pose)
00072 {
00073 nav_2d_msgs::Pose2DStamped pose2d;
00074 pose2d.header = pose.header;
00075 pose2d.pose.x = pose.pose.position.x;
00076 pose2d.pose.y = pose.pose.position.y;
00077 pose2d.pose.theta = tf::getYaw(pose.pose.orientation);
00078 return pose2d;
00079 }
00080
00081 geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D& pose2d)
00082 {
00083 geometry_msgs::Pose pose;
00084 pose.position.x = pose2d.x;
00085 pose.position.y = pose2d.y;
00086 pose.orientation = tf::createQuaternionMsgFromYaw(pose2d.theta);
00087 return pose;
00088 }
00089
00090 geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped& pose2d)
00091 {
00092 geometry_msgs::PoseStamped pose;
00093 pose.header = pose2d.header;
00094 pose.pose = pose2DToPose(pose2d.pose);
00095 return pose;
00096 }
00097
00098 geometry_msgs::PoseStamped pose2DToPoseStamped(const geometry_msgs::Pose2D& pose2d,
00099 const std::string& frame, const ros::Time& stamp)
00100 {
00101 geometry_msgs::PoseStamped pose;
00102 pose.header.frame_id = frame;
00103 pose.header.stamp = stamp;
00104 pose.pose.position.x = pose2d.x;
00105 pose.pose.position.y = pose2d.y;
00106 pose.pose.orientation = tf::createQuaternionMsgFromYaw(pose2d.theta);
00107 return pose;
00108 }
00109
00110 nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path& path)
00111 {
00112 nav_2d_msgs::Path2D path2d;
00113 path2d.header = path.header;
00114 nav_2d_msgs::Pose2DStamped stamped_2d;
00115 path2d.poses.resize(path.poses.size());
00116 for (unsigned int i = 0; i < path.poses.size(); i++)
00117 {
00118 stamped_2d = poseStampedToPose2D(path.poses[i]);
00119 path2d.poses[i] = stamped_2d.pose;
00120 }
00121 return path2d;
00122 }
00123
00124 nav_msgs::Path posesToPath(const std::vector<geometry_msgs::PoseStamped>& poses)
00125 {
00126 nav_msgs::Path path;
00127 if (poses.empty())
00128 return path;
00129
00130 path.poses.resize(poses.size());
00131 path.header.frame_id = poses[0].header.frame_id;
00132 path.header.stamp = poses[0].header.stamp;
00133 for (unsigned int i = 0; i < poses.size(); i++)
00134 {
00135 path.poses[i] = poses[i];
00136 }
00137 return path;
00138 }
00139
00140 nav_2d_msgs::Path2D posesToPath2D(const std::vector<geometry_msgs::PoseStamped>& poses)
00141 {
00142 nav_2d_msgs::Path2D path;
00143 if (poses.empty())
00144 return path;
00145
00146 nav_2d_msgs::Pose2DStamped pose;
00147 path.poses.resize(poses.size());
00148 path.header.frame_id = poses[0].header.frame_id;
00149 path.header.stamp = poses[0].header.stamp;
00150 for (unsigned int i = 0; i < poses.size(); i++)
00151 {
00152 pose = poseStampedToPose2D(poses[i]);
00153 path.poses[i] = pose.pose;
00154 }
00155 return path;
00156 }
00157
00158
00159 nav_msgs::Path poses2DToPath(const std::vector<geometry_msgs::Pose2D>& poses,
00160 const std::string& frame, const ros::Time& stamp)
00161 {
00162 nav_msgs::Path path;
00163 path.poses.resize(poses.size());
00164 path.header.frame_id = frame;
00165 path.header.stamp = stamp;
00166 for (unsigned int i = 0; i < poses.size(); i++)
00167 {
00168 path.poses[i] = pose2DToPoseStamped(poses[i], frame, stamp);
00169 }
00170 return path;
00171 }
00172
00173 nav_msgs::Path pathToPath(const nav_2d_msgs::Path2D& path2d)
00174 {
00175 nav_msgs::Path path;
00176 path.header = path2d.header;
00177 path.poses.resize(path2d.poses.size());
00178 for (unsigned int i = 0; i < path.poses.size(); i++)
00179 {
00180 path.poses[i].header = path2d.header;
00181 path.poses[i].pose = pose2DToPose(path2d.poses[i]);
00182 }
00183 return path;
00184 }
00185
00186 nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo& info)
00187 {
00188 nav_2d_msgs::NavGridInfo msg;
00189 msg.width = info.width;
00190 msg.height = info.height;
00191 msg.resolution = info.resolution;
00192 msg.frame_id = info.frame_id;
00193 msg.origin_x = info.origin_x;
00194 msg.origin_y = info.origin_y;
00195 return msg;
00196 }
00197
00198 nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo& msg)
00199 {
00200 nav_grid::NavGridInfo info;
00201 info.width = msg.width;
00202 info.height = msg.height;
00203 info.resolution = msg.resolution;
00204 info.frame_id = msg.frame_id;
00205 info.origin_x = msg.origin_x;
00206 info.origin_y = msg.origin_y;
00207 return info;
00208 }
00209
00210 nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData& metadata)
00211 {
00212 nav_grid::NavGridInfo info;
00213 info.resolution = metadata.resolution;
00214 info.width = metadata.width;
00215 info.height = metadata.height;
00216 info.origin_x = metadata.origin.position.x;
00217 info.origin_y = metadata.origin.position.y;
00218 if (std::abs(tf::getYaw(metadata.origin.orientation)) > 1e-5)
00219 {
00220 ROS_WARN_NAMED("nav_2d_utils",
00221 "Conversion from MapMetaData to NavGridInfo encountered a non-zero rotation. Ignoring.");
00222 }
00223 return info;
00224 }
00225
00226 nav_msgs::MapMetaData infoToInfo(const nav_grid::NavGridInfo & info)
00227 {
00228 nav_msgs::MapMetaData metadata;
00229 metadata.resolution = info.resolution;
00230 metadata.width = info.width;
00231 metadata.height = info.height;
00232 metadata.origin.position.x = info.origin_x;
00233 metadata.origin.position.y = info.origin_y;
00234 metadata.origin.orientation.w = 1.0;
00235 return metadata;
00236 }
00237
00238 nav_2d_msgs::UIntBounds toMsg(const nav_core2::UIntBounds& bounds)
00239 {
00240 nav_2d_msgs::UIntBounds msg;
00241 msg.min_x = bounds.getMinX();
00242 msg.min_y = bounds.getMinY();
00243 msg.max_x = bounds.getMaxX();
00244 msg.max_y = bounds.getMaxY();
00245 return msg;
00246 }
00247
00248 nav_core2::UIntBounds fromMsg(const nav_2d_msgs::UIntBounds& msg)
00249 {
00250 return nav_core2::UIntBounds(msg.min_x, msg.min_y, msg.max_x, msg.max_y);
00251 }
00252
00253
00254 }