35 #include <Eigen/Geometry> 36 #include <opencv2/core/core.hpp> 47 Transform(
float r11,
float r12,
float r13,
float o14,
48 float r21,
float r22,
float r23,
float o24,
49 float r31,
float r32,
float r33,
float o34);
51 Transform(
const cv::Mat & transformationMatrix);
55 Transform(
float x,
float y,
float z,
float qx,
float qy,
float qz,
float qw);
61 float r11()
const {
return data()[0];}
62 float r12()
const {
return data()[1];}
63 float r13()
const {
return data()[2];}
64 float r21()
const {
return data()[4];}
65 float r22()
const {
return data()[5];}
66 float r23()
const {
return data()[6];}
67 float r31()
const {
return data()[8];}
68 float r32()
const {
return data()[9];}
69 float r33()
const {
return data()[10];}
71 float o14()
const {
return data()[3];}
72 float o24()
const {
return data()[7];}
73 float o34()
const {
return data()[11];}
76 const float &
operator[](
int index)
const {
return data()[index];}
78 const float &
operator()(
int row,
int col)
const {
return data()[row*4 + col];}
87 const float *
data()
const {
return (
const float *)data_.data;}
88 float *
data() {
return (
float *)data_.data;}
89 int size()
const {
return 12;}
91 float &
x() {
return data()[3];}
92 float &
y() {
return data()[7];}
93 float &
z() {
return data()[11];}
94 const float &
x()
const {
return data()[3];}
95 const float &
y()
const {
return data()[7];}
96 const float &
z()
const {
return data()[11];}
105 cv::Mat rotationMatrix()
const;
106 cv::Mat translationMatrix()
const;
108 void getTranslationAndEulerAngles(
float & x,
float & y,
float & z,
float & roll,
float & pitch,
float & yaw)
const;
109 void getEulerAngles(
float & roll,
float & pitch,
float & yaw)
const;
110 void getTranslation(
float & x,
float & y,
float & z)
const;
111 float getAngle(
float x=1.0
f,
float y=0.0
f,
float z=0.0
f)
const;
112 float getNorm()
const;
113 float getNormSquared()
const;
114 float getDistance(
const Transform & t)
const;
115 float getDistanceSquared(
const Transform & t)
const;
117 void normalizeRotation();
118 std::string prettyPrint()
const;
125 Eigen::Matrix4f toEigen4f()
const;
126 Eigen::Matrix4d toEigen4d()
const;
127 Eigen::Affine3f toEigen3f()
const;
128 Eigen::Affine3d toEigen3d()
const;
130 Eigen::Quaternionf getQuaternionf()
const;
131 Eigen::Quaterniond getQuaterniond()
const;
135 static Transform fromEigen4f(
const Eigen::Matrix4f & matrix);
136 static Transform fromEigen4d(
const Eigen::Matrix4d & matrix);
137 static Transform fromEigen3f(
const Eigen::Affine3f & matrix);
138 static Transform fromEigen3d(
const Eigen::Affine3d & matrix);
139 static Transform fromEigen3f(
const Eigen::Isometry3f & matrix);
140 static Transform fromEigen3d(
const Eigen::Isometry3d & matrix);
149 static Transform fromString(
const std::string &
string);
150 static bool canParseString(
const std::string &
string);
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
GLM_FUNC_DECL genType::row_type row(genType const &m, length_t const &index)
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
GLM_FUNC_DECL tmat2x2< T, P > operator*(tmat2x2< T, P > const &m, T const &s)
GLM_FUNC_DECL bool isNull(detail::tmat2x2< T, P > const &m, T const &epsilon)
GLM_FUNC_DECL detail::tmat4x4< T, P > interpolate(detail::tmat4x4< T, P > const &m1, detail::tmat4x4< T, P > const &m2, T const delta)
GLM_FUNC_DECL bool operator==(tvec1< T, P > const &v1, tvec1< T, P > const &v2)
GLM_FUNC_DECL bool operator!=(tvec1< T, P > const &v1, tvec1< T, P > const &v2)
GLM_FUNC_DECL detail::tquat< T, P > rotation(detail::tvec3< T, P > const &orig, detail::tvec3< T, P > const &dest)
GLM_FUNC_DECL bool isIdentity(matType< T, P > const &m, T const &epsilon)
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
RTABMAP_EXP std::ostream & operator<<(std::ostream &os, const Transform &s)
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)