35 #ifndef NAV_2D_UTILS_CONVERSIONS_H 36 #define NAV_2D_UTILS_CONVERSIONS_H 39 #include <geometry_msgs/Point.h> 40 #include <geometry_msgs/Pose.h> 41 #include <geometry_msgs/Twist.h> 42 #include <geometry_msgs/PolygonStamped.h> 43 #include <nav_2d_msgs/Twist2D.h> 44 #include <nav_2d_msgs/Path2D.h> 45 #include <nav_2d_msgs/Point2D.h> 46 #include <nav_2d_msgs/Polygon2D.h> 47 #include <nav_2d_msgs/Polygon2DStamped.h> 48 #include <nav_2d_msgs/Pose2DStamped.h> 49 #include <nav_2d_msgs/NavGridInfo.h> 50 #include <nav_2d_msgs/UIntBounds.h> 51 #include <nav_msgs/MapMetaData.h> 52 #include <nav_msgs/Path.h> 62 geometry_msgs::Twist
twist2Dto3D(
const nav_2d_msgs::Twist2D& cmd_vel_2d);
63 nav_2d_msgs::Twist2D
twist3Dto2D(
const geometry_msgs::Twist& cmd_vel);
66 nav_2d_msgs::Point2D
pointToPoint2D(
const geometry_msgs::Point& point);
67 nav_2d_msgs::Point2D
pointToPoint2D(
const geometry_msgs::Point32& point);
68 geometry_msgs::Point
pointToPoint3D(
const nav_2d_msgs::Point2D& point);
69 geometry_msgs::Point32
pointToPoint32(
const nav_2d_msgs::Point2D& point);
74 geometry_msgs::Pose
pose2DToPose(
const geometry_msgs::Pose2D& pose2d);
77 const std::string& frame,
const ros::Time& stamp);
80 nav_2d_msgs::Path2D
pathToPath(
const nav_msgs::Path& path);
81 nav_msgs::Path
posesToPath(
const std::vector<geometry_msgs::PoseStamped>& poses);
82 nav_2d_msgs::Path2D
posesToPath2D(
const std::vector<geometry_msgs::PoseStamped>& poses);
83 nav_msgs::Path
poses2DToPath(
const std::vector<geometry_msgs::Pose2D>& poses,
84 const std::string& frame,
const ros::Time& stamp);
85 nav_msgs::Path
pathToPath(
const nav_2d_msgs::Path2D& path2d);
88 geometry_msgs::Polygon
polygon2Dto3D(
const nav_2d_msgs::Polygon2D& polygon_2d);
89 nav_2d_msgs::Polygon2D
polygon3Dto2D(
const geometry_msgs::Polygon& polygon_3d);
90 geometry_msgs::PolygonStamped
polygon2Dto3D(
const nav_2d_msgs::Polygon2DStamped& polygon_2d);
91 nav_2d_msgs::Polygon2DStamped
polygon3Dto2D(
const geometry_msgs::PolygonStamped& polygon_3d);
107 #endif // NAV_2D_UTILS_CONVERSIONS_H nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData &metadata, const std::string &frame)
geometry_msgs::Point32 pointToPoint32(const nav_2d_msgs::Point2D &point)
geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D &pose2d)
A set of utility functions for Bounds objects interacting with other messages/types.
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)
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::Point2D pointToPoint2D(const geometry_msgs::Point &point)
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)
geometry_msgs::Pose2D getOrigin2D(const nav_grid::NavGridInfo &info)
geometry_msgs::Polygon polygon2Dto3D(const nav_2d_msgs::Polygon2D &polygon_2d)
nav_2d_msgs::Polygon2D polygon3Dto2D(const geometry_msgs::Polygon &polygon_3d)
nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist &cmd_vel)