36 #include <Eigen/Geometry> 37 #include <opencv2/core/core.hpp> 48 Transform(
float r11,
float r12,
float r13,
float o14,
49 float r21,
float r22,
float r23,
float o24,
50 float r31,
float r32,
float r33,
float o34);
52 Transform(
const cv::Mat & transformationMatrix);
56 Transform(
float x,
float y,
float z,
float qx,
float qy,
float qz,
float qw);
88 const float *
data()
const {
return (
const float *)data_.data;}
89 float *
data() {
return (
float *)data_.data;}
90 int size()
const {
return 12;}
94 float &
z() {
return data()[11];}
95 const float &
x()
const {
return data()[3];}
96 const float &
y()
const {
return data()[7];}
97 const float &
z()
const {
return data()[11];}
101 bool isInvertible()
const;
110 cv::Mat rotationMatrix()
const;
111 cv::Mat translationMatrix()
const;
113 void getTranslationAndEulerAngles(
float & x,
float & y,
float & z,
float & roll,
float & pitch,
float & yaw)
const;
114 void getEulerAngles(
float & roll,
float & pitch,
float & yaw)
const;
115 void getTranslation(
float & x,
float & y,
float & z)
const;
116 float getAngle(
float x=1.0
f,
float y=0.0
f,
float z=0.0
f)
const;
117 float getNorm()
const;
118 float getNormSquared()
const;
119 float getDistance(
const Transform & t)
const;
120 float getDistanceSquared(
const Transform & t)
const;
122 void normalizeRotation();
123 std::string prettyPrint()
const;
130 Eigen::Matrix4f toEigen4f()
const;
131 Eigen::Matrix4d toEigen4d()
const;
132 Eigen::Affine3f toEigen3f()
const;
133 Eigen::Affine3d toEigen3d()
const;
135 Eigen::Quaternionf getQuaternionf()
const;
136 Eigen::Quaterniond getQuaterniond()
const;
140 static Transform fromEigen4f(
const Eigen::Matrix4f & matrix);
141 static Transform fromEigen4d(
const Eigen::Matrix4d & matrix);
142 static Transform fromEigen3f(
const Eigen::Affine3f & matrix);
143 static Transform fromEigen3d(
const Eigen::Affine3d & matrix);
144 static Transform fromEigen3f(
const Eigen::Isometry3f & matrix);
145 static Transform fromEigen3d(
const Eigen::Isometry3d & matrix);
146 static Transform fromEigen3f(
const Eigen::Matrix<float, 3, 4> & matrix);
147 static Transform fromEigen3d(
const Eigen::Matrix<double, 3, 4> & matrix);
150 0.0
f, -1.0
f, 0.0
f, 0.0
f,
151 0.0
f, 0.0
f, 1.0
f, 0.0
f,
152 -1.0
f, 0.0
f, 0.0
f, 0.0
f);}
154 0.0
f, 0.0
f,-1.0
f, 0.0
f,
155 -1.0
f, 0.0
f, 0.0
f, 0.0
f,
156 0.0
f, 1.0
f, 0.0
f, 0.0
f);}
165 static Transform fromString(
const std::string &
string);
166 static bool canParseString(
const std::string &
string);
169 const std::map<double, Transform> & tfBuffer,
170 const double & stamp);
172 const std::map<double, Transform> & tfBuffer,
173 const double & stamp,
174 double * stampDiff),
"Use Transform::getTransform() instead to get always accurate transforms.");
186 transform_(transform),
190 const double &
stamp()
const {
return stamp_;}
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)
RTABMAP_DEPRECATED(typedef SensorData Image, "rtabmap::Image class is renamed to rtabmap::SensorData, use the last one instead.")
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)
RTABMAP_EXP std::ostream & operator<<(std::ostream &os, const CameraModel &model)
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)