pose.h
Go to the documentation of this file.
00001 #ifndef MRPT_BRIDGE_POSE_H
00002 #define MRPT_BRIDGE_POSE_H
00003 
00004 
00005 namespace std{
00006     template <class T> class allocator;
00007 }
00008 
00009 namespace tf{
00010     class Transform;
00011     class Matrix3x3;
00012 }
00013 
00014 namespace geometry_msgs{
00015     template <class ContainerAllocator> struct Pose_;
00016     typedef Pose_<std::allocator<void> > Pose;
00017     template <class ContainerAllocator> struct PoseWithCovariance_;
00018     typedef PoseWithCovariance_<std::allocator<void> > PoseWithCovariance;
00019     template <class ContainerAllocator> struct Quaternion_;
00020     typedef Quaternion_<std::allocator<void> > Quaternion;
00021 }
00022 
00023 namespace mrpt{
00024 namespace math{
00025     template<class T> class CQuaternion;
00026     template <typename T,size_t NROWS,size_t NCOLS> class CMatrixFixedNumeric;
00027     typedef CMatrixFixedNumeric<double,3,3> CMatrixDouble33;
00028 }
00029 namespace poses{
00030         class CPose2D;
00031         class CPose3D;
00032         class CPosePDFGaussian;
00033         class CPose3DPDFGaussian;
00034         typedef math::CQuaternion<double> CQuaternionDouble;
00035     }
00036 }
00037 
00038 namespace mrpt_bridge
00039 {
00041     mrpt::math::CMatrixDouble33& convert( const tf::Matrix3x3& _src, mrpt::math::CMatrixDouble33& _des);
00042 
00044     tf::Matrix3x3& convert( const mrpt::math::CMatrixDouble33& _src, tf::Matrix3x3& _des);
00045 
00047     tf::Transform& convert( const mrpt::poses::CPose3D& _src, tf::Transform&  _des);
00049     mrpt::poses::CPose3D& convert( const tf::Transform& _src, mrpt::poses::CPose3D& _des);
00050     
00052     geometry_msgs::Pose&  convert( const mrpt::poses::CPose3D& _src, geometry_msgs::Pose& _des);
00053 
00055     geometry_msgs::Pose& convert( const mrpt::poses::CPose2D& _src, geometry_msgs::Pose& _des);
00056 
00058     geometry_msgs::PoseWithCovariance& convert( const mrpt::poses::CPose3DPDFGaussian& _src, geometry_msgs::PoseWithCovariance& _des);
00059 
00061     tf::Transform& convert( const mrpt::poses::CPose3DPDFGaussian& _src, tf::Transform&);
00062 
00064     geometry_msgs::PoseWithCovariance& convert( const mrpt::poses::CPosePDFGaussian& _src, geometry_msgs::PoseWithCovariance& _des);
00065 
00067     geometry_msgs::Quaternion& convert(  const mrpt::poses::CQuaternionDouble& _src, geometry_msgs::Quaternion& _des);
00068 
00070     mrpt::poses::CPose2D& convert(const geometry_msgs::Pose& _src, mrpt::poses::CPose2D& _des);
00071 
00073     mrpt::poses::CPose3D& convert( const geometry_msgs::Pose& _src, mrpt::poses::CPose3D& _des);
00074 
00076     mrpt::poses::CPose3DPDFGaussian& convert( const geometry_msgs::PoseWithCovariance& _src, mrpt::poses::CPose3DPDFGaussian& _des);
00077 
00079     mrpt::poses::CPosePDFGaussian& convert( const geometry_msgs::PoseWithCovariance& _src, mrpt::poses::CPosePDFGaussian& _des);
00080 
00082     mrpt::poses::CQuaternionDouble& convert( const geometry_msgs::Quaternion& _src, mrpt::poses::CQuaternionDouble& _des);
00083 
00084 }
00085 
00086 #endif /* MRPT_BRIDGE_POSE_H */


mrpt_bridge
Author(s):
autogenerated on Tue Aug 5 2014 10:58:06