Go to the documentation of this file.00001 #ifndef MRPT_BRIDGE_POSE_H
00002 #define MRPT_BRIDGE_POSE_H
00003
00004 #include <cstring>
00005
00006 namespace std{
00007 template <class T> class allocator;
00008 }
00009
00010 namespace tf{
00011 class Transform;
00012 class Matrix3x3;
00013 }
00014
00015 namespace geometry_msgs{
00016 template <class ContainerAllocator> struct Pose_;
00017 typedef Pose_<std::allocator<void> > Pose;
00018 template <class ContainerAllocator> struct PoseWithCovariance_;
00019 typedef PoseWithCovariance_<std::allocator<void> > PoseWithCovariance;
00020 template <class ContainerAllocator> struct Quaternion_;
00021 typedef Quaternion_<std::allocator<void> > Quaternion;
00022 }
00023
00024 namespace mrpt{
00025 namespace math{
00026 template<class T> class CQuaternion;
00027 template <typename T,size_t NROWS,size_t NCOLS> class CMatrixFixedNumeric;
00028 typedef CMatrixFixedNumeric<double,3,3> CMatrixDouble33;
00029 }
00030 namespace poses{
00031 class CPose2D;
00032 class CPose3D;
00033 class CPosePDFGaussian;
00034 class CPose3DPDFGaussian;
00035 typedef math::CQuaternion<double> CQuaternionDouble;
00036 }
00037 }
00038
00039 namespace mrpt_bridge
00040 {
00042 mrpt::math::CMatrixDouble33& convert( const tf::Matrix3x3& _src, mrpt::math::CMatrixDouble33& _des);
00043
00045 tf::Matrix3x3& convert( const mrpt::math::CMatrixDouble33& _src, tf::Matrix3x3& _des);
00046
00048 tf::Transform& convert( const mrpt::poses::CPose3D& _src, tf::Transform& _des);
00050 mrpt::poses::CPose3D& convert( const tf::Transform& _src, mrpt::poses::CPose3D& _des);
00051
00053 geometry_msgs::Pose& convert( const mrpt::poses::CPose3D& _src, geometry_msgs::Pose& _des);
00054
00056 geometry_msgs::Pose& convert( const mrpt::poses::CPose2D& _src, geometry_msgs::Pose& _des);
00057
00059 geometry_msgs::PoseWithCovariance& convert( const mrpt::poses::CPose3DPDFGaussian& _src, geometry_msgs::PoseWithCovariance& _des);
00060
00062 tf::Transform& convert( const mrpt::poses::CPose3DPDFGaussian& _src, tf::Transform&);
00063
00065 geometry_msgs::PoseWithCovariance& convert( const mrpt::poses::CPosePDFGaussian& _src, geometry_msgs::PoseWithCovariance& _des);
00066
00068 geometry_msgs::Quaternion& convert( const mrpt::poses::CQuaternionDouble& _src, geometry_msgs::Quaternion& _des);
00069
00071 mrpt::poses::CPose2D& convert(const geometry_msgs::Pose& _src, mrpt::poses::CPose2D& _des);
00072
00074 mrpt::poses::CPose3D& convert( const geometry_msgs::Pose& _src, mrpt::poses::CPose3D& _des);
00075
00077 mrpt::poses::CPose3DPDFGaussian& convert( const geometry_msgs::PoseWithCovariance& _src, mrpt::poses::CPose3DPDFGaussian& _des);
00078
00080 mrpt::poses::CPosePDFGaussian& convert( const geometry_msgs::PoseWithCovariance& _src, mrpt::poses::CPosePDFGaussian& _des);
00081
00083 mrpt::poses::CQuaternionDouble& convert( const geometry_msgs::Quaternion& _src, mrpt::poses::CQuaternionDouble& _des);
00084
00085 }
00086
00087 #endif