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
00035 #ifndef NAV_2D_UTILS_CONVERSIONS_H
00036 #define NAV_2D_UTILS_CONVERSIONS_H
00037
00038 #include <ros/ros.h>
00039 #include <geometry_msgs/Pose.h>
00040 #include <geometry_msgs/Twist.h>
00041 #include <nav_2d_msgs/Twist2D.h>
00042 #include <nav_2d_msgs/Path2D.h>
00043 #include <nav_2d_msgs/Pose2DStamped.h>
00044 #include <nav_2d_msgs/NavGridInfo.h>
00045 #include <nav_2d_msgs/UIntBounds.h>
00046 #include <nav_msgs/MapMetaData.h>
00047 #include <nav_msgs/Path.h>
00048 #include <nav_grid/nav_grid.h>
00049 #include <nav_core2/bounds.h>
00050 #include <tf/tf.h>
00051 #include <vector>
00052 #include <string>
00053
00054 namespace nav_2d_utils
00055 {
00056
00057 geometry_msgs::Twist twist2Dto3D(const nav_2d_msgs::Twist2D& cmd_vel_2d);
00058 nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist& cmd_vel);
00059
00060
00061 nav_2d_msgs::Pose2DStamped stampedPoseToPose2D(const tf::Stamped<tf::Pose>& pose);
00062 nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped& pose);
00063 geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D& pose2d);
00064 geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped& pose2d);
00065 geometry_msgs::PoseStamped pose2DToPoseStamped(const geometry_msgs::Pose2D& pose2d,
00066 const std::string& frame, const ros::Time& stamp);
00067
00068
00069 nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path& path);
00070 nav_msgs::Path posesToPath(const std::vector<geometry_msgs::PoseStamped>& poses);
00071 nav_2d_msgs::Path2D posesToPath2D(const std::vector<geometry_msgs::PoseStamped>& poses);
00072 nav_msgs::Path poses2DToPath(const std::vector<geometry_msgs::Pose2D>& poses,
00073 const std::string& frame, const ros::Time& stamp);
00074 nav_msgs::Path pathToPath(const nav_2d_msgs::Path2D& path2d);
00075
00076
00077 nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo& info);
00078 nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo& msg);
00079 nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData& metadata);
00080 nav_msgs::MapMetaData infoToInfo(const nav_grid::NavGridInfo & info);
00081
00082
00083 nav_2d_msgs::UIntBounds toMsg(const nav_core2::UIntBounds& bounds);
00084 nav_core2::UIntBounds fromMsg(const nav_2d_msgs::UIntBounds& msg);
00085
00086 }
00087
00088 #endif // NAV_2D_UTILS_CONVERSIONS_H