Go to the documentation of this file.00001 #ifndef WALK_MSGS_CONVERSION_HH
00002 # define WALK_MSGS_CONVERSION_HH
00003 # include <string>
00004
00005 # include <walk_interfaces/discretized-trajectory.hh>
00006 # include <walk_interfaces/types.hh>
00007
00008 # include "geometry_msgs/Point.h"
00009 # include "geometry_msgs/Pose.h"
00010
00011 # include "nav_msgs/Path.h"
00012
00013 # include "walk_msgs/Footprint2d.h"
00014 # include "walk_msgs/PathPoint2d.h"
00015 # include "walk_msgs/PathPoint3d.h"
00016
00017 namespace walk_msgs
00018 {
00019 void convertPoseToHomogeneousMatrix(walk::HomogeneousMatrix3d& dst,
00020 const geometry_msgs::Pose& src);
00021 void convertHomogeneousMatrixToPose(geometry_msgs::Pose&,
00022 const walk::HomogeneousMatrix3d&);
00023
00024 void convertTrajectoryToPath(nav_msgs::Path&,
00025 const walk::DiscretizedTrajectory3d&,
00026 const std::string& frameName);
00027
00028 void convertTrajectoryV2dToPath(walk_msgs::PathPoint2d&,
00029 const walk::DiscretizedTrajectoryV2d&,
00030 const std::string& frameName);
00031 void convertTrajectoryV2dToPath(nav_msgs::Path& dst,
00032 const walk::DiscretizedTrajectoryV2d& src,
00033 const std::string& frameName);
00034
00035 void convertTrajectoryV3dToPath(walk_msgs::PathPoint3d& dst,
00036 const walk::DiscretizedTrajectoryV3d& src,
00037 const std::string& frameName);
00038 void convertTrajectoryV3dToPath(nav_msgs::Path& dst,
00039 const walk::DiscretizedTrajectoryV3d& src,
00040 const std::string& frameName);
00041
00042 void convertPointToVector3d(walk::Vector3d& dst,
00043 const geometry_msgs::Point& src);
00044
00045 void convertFootprint2dToHomogeneousMatrix3d
00046 (walk::HomogeneousMatrix3d& dst, const walk_msgs::Footprint2d& src);
00047
00048 void convertHomogeneousMatrix3dToFootprint2d
00049 (walk_msgs::Footprint2d& dst, const walk::HomogeneousMatrix3d& src);
00050
00051 }
00052
00053 #endif //! WALK_MSGS_CONVERSION_HH