#include <Transform.h>
|
| Transform | clone () const |
| |
| float * | data () |
| |
| const float * | data () const |
| |
| const cv::Mat & | dataMatrix () const |
| |
| float | getAngle (float x=1.0f, float y=0.0f, float z=0.0f) const |
| |
| float | getDistance (const Transform &t) const |
| |
| float | getDistanceSquared (const Transform &t) const |
| |
| void | getEulerAngles (float &roll, float &pitch, float &yaw) const |
| |
| float | getNorm () const |
| |
| float | getNormSquared () const |
| |
| Eigen::Quaterniond | getQuaterniond () const |
| |
| Eigen::Quaternionf | getQuaternionf () const |
| |
| void | getTranslation (float &x, float &y, float &z) const |
| |
| void | getTranslationAndEulerAngles (float &x, float &y, float &z, float &roll, float &pitch, float &yaw) const |
| |
| Transform | interpolate (float t, const Transform &other) const |
| |
| Transform | inverse () const |
| |
| bool | is3DoF () const |
| |
| bool | is4DoF () const |
| |
| bool | isIdentity () const |
| |
| bool | isInvertible () const |
| |
| bool | isNull () const |
| |
| void | normalizeRotation () |
| |
| float | o14 () const |
| |
| float | o24 () const |
| |
| float | o34 () const |
| |
| bool | operator!= (const Transform &t) const |
| |
| float & | operator() (int row, int col) |
| |
| const float & | operator() (int row, int col) const |
| |
| Transform | operator* (const Transform &t) const |
| |
| Transform & | operator*= (const Transform &t) |
| |
| bool | operator== (const Transform &t) const |
| |
| float & | operator[] (int index) |
| |
| const float & | operator[] (int index) const |
| |
| std::string | prettyPrint () const |
| |
| float | r11 () const |
| |
| float | r12 () const |
| |
| float | r13 () const |
| |
| float | r21 () const |
| |
| float | r22 () const |
| |
| float | r23 () const |
| |
| float | r31 () const |
| |
| float | r32 () const |
| |
| float | r33 () const |
| |
| Transform | rotation () const |
| |
| cv::Mat | rotationMatrix () const |
| |
| void | setIdentity () |
| |
| void | setNull () |
| |
| int | size () const |
| |
| float | theta () const |
| |
| Transform | to3DoF () const |
| |
| Transform | to4DoF () const |
| |
| Eigen::Affine3d | toEigen3d () const |
| |
| Eigen::Affine3f | toEigen3f () const |
| |
| Eigen::Matrix4d | toEigen4d () const |
| |
| Eigen::Matrix4f | toEigen4f () const |
| |
| | Transform () |
| |
| | Transform (const cv::Mat &transformationMatrix) |
| |
| | Transform (float r11, float r12, float r13, float o14, float r21, float r22, float r23, float o24, float r31, float r32, float r33, float o34) |
| |
| | Transform (float x, float y, float theta) |
| |
| | Transform (float x, float y, float z, float qx, float qy, float qz, float qw) |
| |
| | Transform (float x, float y, float z, float roll, float pitch, float yaw) |
| |
| Transform | translation () const |
| |
| cv::Mat | translationMatrix () const |
| |
| float & | x () |
| |
| const float & | x () const |
| |
| float & | y () |
| |
| const float & | y () const |
| |
| float & | z () |
| |
| const float & | z () const |
| |
Definition at line 41 of file Transform.h.
◆ Transform() [1/6]
| rtabmap::Transform::Transform |
( |
| ) |
|
◆ Transform() [2/6]
| rtabmap::Transform::Transform |
( |
float |
r11, |
|
|
float |
r12, |
|
|
float |
r13, |
|
|
float |
o14, |
|
|
float |
r21, |
|
|
float |
r22, |
|
|
float |
r23, |
|
|
float |
o24, |
|
|
float |
r31, |
|
|
float |
r32, |
|
|
float |
r33, |
|
|
float |
o34 |
|
) |
| |
◆ Transform() [3/6]
| rtabmap::Transform::Transform |
( |
const cv::Mat & |
transformationMatrix | ) |
|
◆ Transform() [4/6]
◆ Transform() [5/6]
◆ Transform() [6/6]
◆ canParseString()
| bool rtabmap::Transform::canParseString |
( |
const std::string & |
string | ) |
|
|
static |
Format (3 values): x y z Format (6 values): x y z roll pitch yaw Format (7 values): x y z qx qy qz qw Format (9 values, 3x3 rotation): r11 r12 r13 r21 r22 r23 r31 r32 r33 Format (12 values, 3x4 transform): r11 r12 r13 tx r21 r22 r23 ty r31 r32 r33 tz
Definition at line 524 of file Transform.cpp.
◆ clone()
| Transform rtabmap::Transform::clone |
( |
| ) |
const |
◆ data() [1/2]
| float* rtabmap::Transform::data |
( |
| ) |
|
|
inline |
◆ data() [2/2]
| const float* rtabmap::Transform::data |
( |
| ) |
const |
|
inline |
◆ dataMatrix()
| const cv::Mat& rtabmap::Transform::dataMatrix |
( |
| ) |
const |
|
inline |
◆ fromEigen3d() [1/3]
◆ fromEigen3d() [2/3]
◆ fromEigen3d() [3/3]
◆ fromEigen3f() [1/3]
◆ fromEigen3f() [2/3]
◆ fromEigen3f() [3/3]
◆ fromEigen4d()
| Transform rtabmap::Transform::fromEigen4d |
( |
const Eigen::Matrix4d & |
matrix | ) |
|
|
static |
◆ fromEigen4f()
| Transform rtabmap::Transform::fromEigen4f |
( |
const Eigen::Matrix4f & |
matrix | ) |
|
|
static |
◆ fromString()
Format (3 values): x y z Format (6 values): x y z roll pitch yaw Format (7 values): x y z qx qy qz qw Format (9 values, 3x3 rotation): r11 r12 r13 r21 r22 r23 r31 r32 r33 Format (12 values, 3x4 transform): r11 r12 r13 tx r21 r22 r23 ty r31 r32 r33 tz
Definition at line 475 of file Transform.cpp.
◆ getAngle()
◆ getClosestTransform()
| Transform rtabmap::Transform::getClosestTransform |
( |
const std::map< double, Transform > & |
tfBuffer, |
|
|
const double & |
stamp, |
|
|
double * |
stampDiff |
|
) |
| |
|
static |
◆ getDistance()
◆ getDistanceSquared()
| float rtabmap::Transform::getDistanceSquared |
( |
const Transform & |
t | ) |
const |
◆ getEulerAngles()
| void rtabmap::Transform::getEulerAngles |
( |
float & |
roll, |
|
|
float & |
pitch, |
|
|
float & |
yaw |
|
) |
| const |
◆ getIdentity()
| Transform rtabmap::Transform::getIdentity |
( |
| ) |
|
|
static |
◆ getNorm()
| float rtabmap::Transform::getNorm |
( |
| ) |
const |
◆ getNormSquared()
| float rtabmap::Transform::getNormSquared |
( |
| ) |
const |
◆ getQuaterniond()
◆ getQuaternionf()
◆ getTransform()
| Transform rtabmap::Transform::getTransform |
( |
const std::map< double, Transform > & |
tfBuffer, |
|
|
const double & |
stamp |
|
) |
| |
|
static |
◆ getTranslation()
| void rtabmap::Transform::getTranslation |
( |
float & |
x, |
|
|
float & |
y, |
|
|
float & |
z |
|
) |
| const |
◆ getTranslationAndEulerAngles()
◆ interpolate()
◆ inverse()
| Transform rtabmap::Transform::inverse |
( |
| ) |
const |
◆ is3DoF()
| bool rtabmap::Transform::is3DoF |
( |
| ) |
const |
◆ is4DoF()
| bool rtabmap::Transform::is4DoF |
( |
| ) |
const |
◆ isIdentity()
| bool rtabmap::Transform::isIdentity |
( |
| ) |
const |
◆ isInvertible()
| bool rtabmap::Transform::isInvertible |
( |
| ) |
const |
◆ isNull()
| bool rtabmap::Transform::isNull |
( |
| ) |
const |
◆ normalizeRotation()
| void rtabmap::Transform::normalizeRotation |
( |
| ) |
|
◆ o14()
| float rtabmap::Transform::o14 |
( |
| ) |
const |
|
inline |
◆ o24()
| float rtabmap::Transform::o24 |
( |
| ) |
const |
|
inline |
◆ o34()
| float rtabmap::Transform::o34 |
( |
| ) |
const |
|
inline |
◆ opengl_T_rtabmap()
| static Transform rtabmap::Transform::opengl_T_rtabmap |
( |
| ) |
|
|
inlinestatic |
◆ operator!=()
◆ operator()() [1/2]
| float& rtabmap::Transform::operator() |
( |
int |
row, |
|
|
int |
col |
|
) |
| |
|
inline |
◆ operator()() [2/2]
| const float& rtabmap::Transform::operator() |
( |
int |
row, |
|
|
int |
col |
|
) |
| const |
|
inline |
◆ operator*()
◆ operator*=()
◆ operator==()
| bool rtabmap::Transform::operator== |
( |
const Transform & |
t | ) |
const |
◆ operator[]() [1/2]
| float& rtabmap::Transform::operator[] |
( |
int |
index | ) |
|
|
inline |
◆ operator[]() [2/2]
| const float& rtabmap::Transform::operator[] |
( |
int |
index | ) |
const |
|
inline |
◆ prettyPrint()
◆ r11()
| float rtabmap::Transform::r11 |
( |
| ) |
const |
|
inline |
◆ r12()
| float rtabmap::Transform::r12 |
( |
| ) |
const |
|
inline |
◆ r13()
| float rtabmap::Transform::r13 |
( |
| ) |
const |
|
inline |
◆ r21()
| float rtabmap::Transform::r21 |
( |
| ) |
const |
|
inline |
◆ r22()
| float rtabmap::Transform::r22 |
( |
| ) |
const |
|
inline |
◆ r23()
| float rtabmap::Transform::r23 |
( |
| ) |
const |
|
inline |
◆ r31()
| float rtabmap::Transform::r31 |
( |
| ) |
const |
|
inline |
◆ r32()
| float rtabmap::Transform::r32 |
( |
| ) |
const |
|
inline |
◆ r33()
| float rtabmap::Transform::r33 |
( |
| ) |
const |
|
inline |
◆ rotation()
| Transform rtabmap::Transform::rotation |
( |
| ) |
const |
◆ rotationMatrix()
| cv::Mat rtabmap::Transform::rotationMatrix |
( |
| ) |
const |
◆ rtabmap_T_opengl()
| static Transform rtabmap::Transform::rtabmap_T_opengl |
( |
| ) |
|
|
inlinestatic |
◆ setIdentity()
| void rtabmap::Transform::setIdentity |
( |
| ) |
|
◆ setNull()
| void rtabmap::Transform::setNull |
( |
| ) |
|
◆ size()
| int rtabmap::Transform::size |
( |
| ) |
const |
|
inline |
◆ theta()
| float rtabmap::Transform::theta |
( |
| ) |
const |
◆ to3DoF()
| Transform rtabmap::Transform::to3DoF |
( |
| ) |
const |
◆ to4DoF()
| Transform rtabmap::Transform::to4DoF |
( |
| ) |
const |
◆ toEigen3d()
◆ toEigen3f()
◆ toEigen4d()
| Eigen::Matrix4d rtabmap::Transform::toEigen4d |
( |
| ) |
const |
◆ toEigen4f()
| Eigen::Matrix4f rtabmap::Transform::toEigen4f |
( |
| ) |
const |
◆ translation()
| Transform rtabmap::Transform::translation |
( |
| ) |
const |
◆ translationMatrix()
| cv::Mat rtabmap::Transform::translationMatrix |
( |
| ) |
const |
◆ x() [1/2]
| float& rtabmap::Transform::x |
( |
| ) |
|
|
inline |
◆ x() [2/2]
| const float& rtabmap::Transform::x |
( |
| ) |
const |
|
inline |
◆ y() [1/2]
| float& rtabmap::Transform::y |
( |
| ) |
|
|
inline |
◆ y() [2/2]
| const float& rtabmap::Transform::y |
( |
| ) |
const |
|
inline |
◆ z() [1/2]
| float& rtabmap::Transform::z |
( |
| ) |
|
|
inline |
◆ z() [2/2]
| const float& rtabmap::Transform::z |
( |
| ) |
const |
|
inline |
◆ data_
The documentation for this class was generated from the following files: