35 #ifndef NAV_2D_UTILS_CONVERSIONS_H 36 #define NAV_2D_UTILS_CONVERSIONS_H 39 #include <geometry_msgs/Pose.h> 40 #include <geometry_msgs/Twist.h> 41 #include <nav_2d_msgs/Twist2D.h> 42 #include <nav_2d_msgs/Path2D.h> 43 #include <nav_2d_msgs/Pose2DStamped.h> 44 #include <nav_2d_msgs/NavGridInfo.h> 45 #include <nav_2d_msgs/UIntBounds.h> 46 #include <nav_msgs/MapMetaData.h> 47 #include <nav_msgs/Path.h> 57 geometry_msgs::Twist
twist2Dto3D(
const nav_2d_msgs::Twist2D& cmd_vel_2d);
58 nav_2d_msgs::Twist2D
twist3Dto2D(
const geometry_msgs::Twist& cmd_vel);
63 geometry_msgs::Pose
pose2DToPose(
const geometry_msgs::Pose2D& pose2d);
66 const std::string& frame,
const ros::Time& stamp);
69 nav_2d_msgs::Path2D
pathToPath(
const nav_msgs::Path& path);
70 nav_msgs::Path
posesToPath(
const std::vector<geometry_msgs::PoseStamped>& poses);
71 nav_2d_msgs::Path2D
posesToPath2D(
const std::vector<geometry_msgs::PoseStamped>& poses);
72 nav_msgs::Path
poses2DToPath(
const std::vector<geometry_msgs::Pose2D>& poses,
73 const std::string& frame,
const ros::Time& stamp);
74 nav_msgs::Path
pathToPath(
const nav_2d_msgs::Path2D& path2d);
88 #endif // NAV_2D_UTILS_CONVERSIONS_H geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D &pose2d)
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)
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)
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)
nav_2d_msgs::Pose2DStamped stampedPoseToPose2D(const tf::Stamped< tf::Pose > &pose)
nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData &metadata)
nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist &cmd_vel)