Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef TRANSFORM_H_
00029 #define TRANSFORM_H_
00030
00031 #include <rtabmap/core/RtabmapExp.h>
00032 #include <vector>
00033 #include <string>
00034 #include <Eigen/Core>
00035 #include <Eigen/Geometry>
00036 #include <opencv2/core/core.hpp>
00037
00038 namespace rtabmap {
00039
00040 class RTABMAP_EXP Transform
00041 {
00042 public:
00043
00044
00045 Transform();
00046
00047 Transform(float r11, float r12, float r13, float o14,
00048 float r21, float r22, float r23, float o24,
00049 float r31, float r32, float r33, float o34);
00050
00051 Transform(const cv::Mat & transformationMatrix);
00052
00053 Transform(float x, float y, float z, float roll, float pitch, float yaw);
00054
00055 Transform(float x, float y, float z, float qx, float qy, float qz, float qw);
00056
00057 Transform(float x, float y, float theta);
00058
00059 float r11() const {return data()[0];}
00060 float r12() const {return data()[1];}
00061 float r13() const {return data()[2];}
00062 float r21() const {return data()[4];}
00063 float r22() const {return data()[5];}
00064 float r23() const {return data()[6];}
00065 float r31() const {return data()[8];}
00066 float r32() const {return data()[9];}
00067 float r33() const {return data()[10];}
00068
00069 float o14() const {return data()[3];}
00070 float o24() const {return data()[7];}
00071 float o34() const {return data()[11];}
00072
00073 float & operator[](int index) {return data()[index];}
00074 const float & operator[](int index) const {return data()[index];}
00075 float & operator()(int row, int col) {return data()[row*4 + col];}
00076 const float & operator()(int row, int col) const {return data()[row*4 + col];}
00077
00078 bool isNull() const;
00079 bool isIdentity() const;
00080
00081 void setNull();
00082 void setIdentity();
00083
00084 const cv::Mat & dataMatrix() const {return data_;}
00085 const float * data() const {return (const float *)data_.data;}
00086 float * data() {return (float *)data_.data;}
00087 int size() const {return 12;}
00088
00089 float & x() {return data()[3];}
00090 float & y() {return data()[7];}
00091 float & z() {return data()[11];}
00092 const float & x() const {return data()[3];}
00093 const float & y() const {return data()[7];}
00094 const float & z() const {return data()[11];}
00095
00096 float theta() const;
00097
00098 Transform inverse() const;
00099 Transform rotation() const;
00100 Transform translation() const;
00101 Transform to3DoF() const;
00102
00103 cv::Mat rotationMatrix() const;
00104 cv::Mat translationMatrix() const;
00105
00106 void getTranslationAndEulerAngles(float & x, float & y, float & z, float & roll, float & pitch, float & yaw) const;
00107 void getEulerAngles(float & roll, float & pitch, float & yaw) const;
00108 void getTranslation(float & x, float & y, float & z) const;
00109 float getNorm() const;
00110 float getNormSquared() const;
00111 float getDistance(const Transform & t) const;
00112 float getDistanceSquared(const Transform & t) const;
00113 Transform interpolate(float t, const Transform & other) const;
00114 std::string prettyPrint() const;
00115
00116 Transform operator*(const Transform & t) const;
00117 Transform & operator*=(const Transform & t);
00118 bool operator==(const Transform & t) const;
00119 bool operator!=(const Transform & t) const;
00120
00121 Eigen::Matrix4f toEigen4f() const;
00122 Eigen::Matrix4d toEigen4d() const;
00123 Eigen::Affine3f toEigen3f() const;
00124 Eigen::Affine3d toEigen3d() const;
00125
00126 Eigen::Quaternionf getQuaternionf() const;
00127 Eigen::Quaterniond getQuaterniond() const;
00128
00129 public:
00130 static Transform getIdentity();
00131 static Transform fromEigen4f(const Eigen::Matrix4f & matrix);
00132 static Transform fromEigen4d(const Eigen::Matrix4d & matrix);
00133 static Transform fromEigen3f(const Eigen::Affine3f & matrix);
00134 static Transform fromEigen3d(const Eigen::Affine3d & matrix);
00135 static Transform fromEigen3f(const Eigen::Isometry3f & matrix);
00136 static Transform fromEigen3d(const Eigen::Isometry3d & matrix);
00137
00145 static Transform fromString(const std::string & string);
00146 static bool canParseString(const std::string & string);
00147
00148 private:
00149 cv::Mat data_;
00150 };
00151
00152 RTABMAP_EXP std::ostream& operator<<(std::ostream& os, const Transform& s);
00153
00154 }
00155
00156 #endif