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 {
00008 template <class T>
00009 class allocator;
00010 }
00011
00012 namespace tf
00013 {
00014 class Transform;
00015 class Matrix3x3;
00016 }
00017
00018 namespace geometry_msgs
00019 {
00020 template <class ContainerAllocator>
00021 struct Pose_;
00022 typedef Pose_<std::allocator<void>> Pose;
00023 template <class ContainerAllocator>
00024 struct PoseWithCovariance_;
00025 typedef PoseWithCovariance_<std::allocator<void>> PoseWithCovariance;
00026 template <class ContainerAllocator>
00027 struct Quaternion_;
00028 typedef Quaternion_<std::allocator<void>> Quaternion;
00029 }
00030
00031 namespace mrpt
00032 {
00033 namespace math
00034 {
00035 template <class T>
00036 class CQuaternion;
00037 template <typename T, size_t NROWS, size_t NCOLS>
00038 class CMatrixFixedNumeric;
00039 typedef CMatrixFixedNumeric<double, 3, 3> CMatrixDouble33;
00040 struct TPose3D;
00041 struct TPose2D;
00042 }
00043 namespace poses
00044 {
00045 class CPose2D;
00046 class CPose3D;
00047 class CPosePDFGaussian;
00048 class CPosePDFGaussianInf;
00049 class CPose3DPDFGaussian;
00050 class CPose3DPDFGaussianInf;
00051 typedef math::CQuaternion<double> CQuaternionDouble;
00052 }
00053 }
00054
00055 namespace mrpt_bridge
00056 {
00061 tf::Matrix3x3& convert(
00062 const mrpt::math::CMatrixDouble33& _src, tf::Matrix3x3& _des);
00063
00065 tf::Transform& convert(const mrpt::poses::CPose3D& _src, tf::Transform& _des);
00066
00068 tf::Transform& convert(const mrpt::math::TPose3D& _src, tf::Transform& _des);
00070 tf::Transform& convert(const mrpt::poses::CPose2D& _src, tf::Transform& _des);
00072 tf::Transform& convert(const mrpt::math::TPose2D& _src, tf::Transform& _des);
00073
00075 geometry_msgs::Pose& convert(
00076 const mrpt::poses::CPose3D& _src, geometry_msgs::Pose& _des);
00077
00079 geometry_msgs::Pose& convert(
00080 const mrpt::poses::CPose2D& _src, geometry_msgs::Pose& _des);
00081
00083 geometry_msgs::PoseWithCovariance& convert(
00084 const mrpt::poses::CPose3DPDFGaussian& _src,
00085 geometry_msgs::PoseWithCovariance& _des);
00086
00089 geometry_msgs::PoseWithCovariance& convert(
00090 const mrpt::poses::CPose3DPDFGaussianInf& _src,
00091 geometry_msgs::PoseWithCovariance& _des);
00092
00094 tf::Transform& convert(
00095 const mrpt::poses::CPose3DPDFGaussian& _src, tf::Transform& _des);
00096
00099 geometry_msgs::PoseWithCovariance& convert(
00100 const mrpt::poses::CPosePDFGaussian& _src,
00101 geometry_msgs::PoseWithCovariance& _des);
00102
00105 geometry_msgs::PoseWithCovariance& convert(
00106 const mrpt::poses::CPosePDFGaussianInf& _src,
00107 geometry_msgs::PoseWithCovariance& _des);
00108
00110 geometry_msgs::Quaternion& convert(
00111 const mrpt::poses::CQuaternionDouble& _src,
00112 geometry_msgs::Quaternion& _des);
00113
00120 mrpt::poses::CPose3D& convert(
00121 const tf::Transform& _src, mrpt::poses::CPose3D& _des);
00122
00124 mrpt::math::CMatrixDouble33& convert(
00125 const tf::Matrix3x3& _src, mrpt::math::CMatrixDouble33& _des);
00126
00128 mrpt::poses::CPose2D& convert(
00129 const geometry_msgs::Pose& _src, mrpt::poses::CPose2D& _des);
00130
00132 mrpt::poses::CPose3D& convert(
00133 const geometry_msgs::Pose& _src, mrpt::poses::CPose3D& _des);
00134
00136 mrpt::poses::CPose3DPDFGaussian& convert(
00137 const geometry_msgs::PoseWithCovariance& _src,
00138 mrpt::poses::CPose3DPDFGaussian& _des);
00139
00142 mrpt::poses::CPose3DPDFGaussianInf& convert(
00143 const geometry_msgs::PoseWithCovariance& _src,
00144 mrpt::poses::CPose3DPDFGaussianInf& _des);
00145
00148 mrpt::poses::CPosePDFGaussian& convert(
00149 const geometry_msgs::PoseWithCovariance& _src,
00150 mrpt::poses::CPosePDFGaussian& _des);
00151
00154 mrpt::poses::CPosePDFGaussianInf& convert(
00155 const geometry_msgs::PoseWithCovariance& _src,
00156 mrpt::poses::CPosePDFGaussianInf& _des);
00157
00159 mrpt::poses::CQuaternionDouble& convert(
00160 const geometry_msgs::Quaternion& _src,
00161 mrpt::poses::CQuaternionDouble& _des);
00162
00164 }
00165
00166 #endif