Public Member Functions | Static Public Member Functions | Private Attributes | List of all members
rtabmap::Transform Class Reference

#include <Transform.h>

Public Member Functions

Transform clone () const
 
floatdata ()
 
const floatdata () const
 
const cv::MatdataMatrix () 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
 
floatoperator() (int row, int col)
 
const floatoperator() (int row, int col) const
 
Transform operator* (const Transform &t) const
 
Transformoperator*= (const Transform &t)
 
bool operator== (const Transform &t) const
 
floatoperator[] (int index)
 
const floatoperator[] (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
 
floatx ()
 
const floatx () const
 
floaty ()
 
const floaty () const
 
floatz ()
 
const floatz () const
 

Static Public Member Functions

static bool canParseString (const std::string &string)
 
static Transform fromEigen3d (const Eigen::Affine3d &matrix)
 
static Transform fromEigen3d (const Eigen::Isometry3d &matrix)
 
static Transform fromEigen3d (const Eigen::Matrix< double, 3, 4 > &matrix)
 
static Transform fromEigen3f (const Eigen::Affine3f &matrix)
 
static Transform fromEigen3f (const Eigen::Isometry3f &matrix)
 
static Transform fromEigen3f (const Eigen::Matrix< float, 3, 4 > &matrix)
 
static Transform fromEigen4d (const Eigen::Matrix4d &matrix)
 
static Transform fromEigen4f (const Eigen::Matrix4f &matrix)
 
static Transform fromString (const std::string &string)
 
static RTABMAP_DEPRECATED Transform getClosestTransform (const std::map< double, Transform > &tfBuffer, const double &stamp, double *stampDiff)
 
static Transform getIdentity ()
 
static Transform getTransform (const std::map< double, Transform > &tfBuffer, const double &stamp)
 
static Transform opengl_T_rtabmap ()
 
static Transform rtabmap_T_opengl ()
 

Private Attributes

cv::Mat data_
 

Detailed Description

Definition at line 41 of file Transform.h.

Constructor & Destructor Documentation

◆ Transform() [1/6]

rtabmap::Transform::Transform ( )

Definition at line 41 of file Transform.cpp.

◆ 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 
)

Definition at line 46 of file Transform.cpp.

◆ Transform() [3/6]

rtabmap::Transform::Transform ( const cv::Mat transformationMatrix)

Definition at line 57 of file Transform.cpp.

◆ Transform() [4/6]

rtabmap::Transform::Transform ( float  x,
float  y,
float  z,
float  roll,
float  pitch,
float  yaw 
)

Definition at line 72 of file Transform.cpp.

◆ Transform() [5/6]

rtabmap::Transform::Transform ( float  x,
float  y,
float  z,
float  qx,
float  qy,
float  qz,
float  qw 
)

Definition at line 78 of file Transform.cpp.

◆ Transform() [6/6]

rtabmap::Transform::Transform ( float  x,
float  y,
float  theta 
)

Definition at line 96 of file Transform.cpp.

Member Function Documentation

◆ 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

Definition at line 102 of file Transform.cpp.

◆ data() [1/2]

float* rtabmap::Transform::data ( )
inline

Definition at line 89 of file Transform.h.

◆ data() [2/2]

const float* rtabmap::Transform::data ( ) const
inline

Definition at line 88 of file Transform.h.

◆ dataMatrix()

const cv::Mat& rtabmap::Transform::dataMatrix ( ) const
inline

Definition at line 87 of file Transform.h.

◆ fromEigen3d() [1/3]

Transform rtabmap::Transform::fromEigen3d ( const Eigen::Affine3d matrix)
static

Definition at line 435 of file Transform.cpp.

◆ fromEigen3d() [2/3]

Transform rtabmap::Transform::fromEigen3d ( const Eigen::Isometry3d matrix)
static

Definition at line 448 of file Transform.cpp.

◆ fromEigen3d() [3/3]

Transform rtabmap::Transform::fromEigen3d ( const Eigen::Matrix< double, 3, 4 > &  matrix)
static

Definition at line 461 of file Transform.cpp.

◆ fromEigen3f() [1/3]

Transform rtabmap::Transform::fromEigen3f ( const Eigen::Affine3f matrix)
static

Definition at line 429 of file Transform.cpp.

◆ fromEigen3f() [2/3]

Transform rtabmap::Transform::fromEigen3f ( const Eigen::Isometry3f matrix)
static

Definition at line 442 of file Transform.cpp.

◆ fromEigen3f() [3/3]

Transform rtabmap::Transform::fromEigen3f ( const Eigen::Matrix< float, 3, 4 > &  matrix)
static

Definition at line 455 of file Transform.cpp.

◆ fromEigen4d()

Transform rtabmap::Transform::fromEigen4d ( const Eigen::Matrix4d &  matrix)
static

Definition at line 422 of file Transform.cpp.

◆ fromEigen4f()

Transform rtabmap::Transform::fromEigen4f ( const Eigen::Matrix4f &  matrix)
static

Definition at line 416 of file Transform.cpp.

◆ fromString()

Transform rtabmap::Transform::fromString ( 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 475 of file Transform.cpp.

◆ getAngle()

float rtabmap::Transform::getAngle ( float  x = 1.0f,
float  y = 0.0f,
float  z = 0.0f 
) const

Definition at line 276 of file Transform.cpp.

◆ getClosestTransform()

Transform rtabmap::Transform::getClosestTransform ( const std::map< double, Transform > &  tfBuffer,
const double &  stamp,
double *  stampDiff 
)
static

Definition at line 566 of file Transform.cpp.

◆ getDistance()

float rtabmap::Transform::getDistance ( const Transform t) const

Definition at line 293 of file Transform.cpp.

◆ getDistanceSquared()

float rtabmap::Transform::getDistanceSquared ( const Transform t) const

Definition at line 298 of file Transform.cpp.

◆ getEulerAngles()

void rtabmap::Transform::getEulerAngles ( float roll,
float pitch,
float yaw 
) const

Definition at line 263 of file Transform.cpp.

◆ getIdentity()

Transform rtabmap::Transform::getIdentity ( )
static

Definition at line 411 of file Transform.cpp.

◆ getNorm()

float rtabmap::Transform::getNorm ( ) const

Definition at line 283 of file Transform.cpp.

◆ getNormSquared()

float rtabmap::Transform::getNormSquared ( ) const

Definition at line 288 of file Transform.cpp.

◆ getQuaterniond()

Eigen::Quaterniond rtabmap::Transform::getQuaterniond ( ) const

Definition at line 406 of file Transform.cpp.

◆ getQuaternionf()

Eigen::Quaternionf rtabmap::Transform::getQuaternionf ( ) const

Definition at line 401 of file Transform.cpp.

◆ getTransform()

Transform rtabmap::Transform::getTransform ( const std::map< double, Transform > &  tfBuffer,
const double &  stamp 
)
static

Definition at line 530 of file Transform.cpp.

◆ getTranslation()

void rtabmap::Transform::getTranslation ( float x,
float y,
float z 
) const

Definition at line 269 of file Transform.cpp.

◆ getTranslationAndEulerAngles()

void rtabmap::Transform::getTranslationAndEulerAngles ( float x,
float y,
float z,
float roll,
float pitch,
float yaw 
) const

Definition at line 258 of file Transform.cpp.

◆ interpolate()

Transform rtabmap::Transform::interpolate ( float  t,
const Transform other 
) const

Definition at line 303 of file Transform.cpp.

◆ inverse()

Transform rtabmap::Transform::inverse ( ) const

Definition at line 178 of file Transform.cpp.

◆ is3DoF()

bool rtabmap::Transform::is3DoF ( ) const

Definition at line 234 of file Transform.cpp.

◆ is4DoF()

bool rtabmap::Transform::is4DoF ( ) const

Definition at line 239 of file Transform.cpp.

◆ isIdentity()

bool rtabmap::Transform::isIdentity ( ) const

Definition at line 136 of file Transform.cpp.

◆ isInvertible()

bool rtabmap::Transform::isInvertible ( ) const

Definition at line 169 of file Transform.cpp.

◆ isNull()

bool rtabmap::Transform::isNull ( ) const

Definition at line 107 of file Transform.cpp.

◆ normalizeRotation()

void rtabmap::Transform::normalizeRotation ( )

Definition at line 316 of file Transform.cpp.

◆ o14()

float rtabmap::Transform::o14 ( ) const
inline

Definition at line 72 of file Transform.h.

◆ o24()

float rtabmap::Transform::o24 ( ) const
inline

Definition at line 73 of file Transform.h.

◆ o34()

float rtabmap::Transform::o34 ( ) const
inline

Definition at line 74 of file Transform.h.

◆ opengl_T_rtabmap()

static Transform rtabmap::Transform::opengl_T_rtabmap ( )
inlinestatic

Definition at line 149 of file Transform.h.

◆ operator!=()

bool rtabmap::Transform::operator!= ( const Transform t) const

Definition at line 359 of file Transform.cpp.

◆ operator()() [1/2]

float& rtabmap::Transform::operator() ( int  row,
int  col 
)
inline

Definition at line 78 of file Transform.h.

◆ operator()() [2/2]

const float& rtabmap::Transform::operator() ( int  row,
int  col 
) const
inline

Definition at line 79 of file Transform.h.

◆ operator*()

Transform rtabmap::Transform::operator* ( const Transform t) const

Definition at line 340 of file Transform.cpp.

◆ operator*=()

Transform & rtabmap::Transform::operator*= ( const Transform t)

Definition at line 348 of file Transform.cpp.

◆ operator==()

bool rtabmap::Transform::operator== ( const Transform t) const

Definition at line 354 of file Transform.cpp.

◆ operator[]() [1/2]

float& rtabmap::Transform::operator[] ( int  index)
inline

Definition at line 76 of file Transform.h.

◆ operator[]() [2/2]

const float& rtabmap::Transform::operator[] ( int  index) const
inline

Definition at line 77 of file Transform.h.

◆ prettyPrint()

std::string rtabmap::Transform::prettyPrint ( ) const

Definition at line 326 of file Transform.cpp.

◆ r11()

float rtabmap::Transform::r11 ( ) const
inline

Definition at line 62 of file Transform.h.

◆ r12()

float rtabmap::Transform::r12 ( ) const
inline

Definition at line 63 of file Transform.h.

◆ r13()

float rtabmap::Transform::r13 ( ) const
inline

Definition at line 64 of file Transform.h.

◆ r21()

float rtabmap::Transform::r21 ( ) const
inline

Definition at line 65 of file Transform.h.

◆ r22()

float rtabmap::Transform::r22 ( ) const
inline

Definition at line 66 of file Transform.h.

◆ r23()

float rtabmap::Transform::r23 ( ) const
inline

Definition at line 67 of file Transform.h.

◆ r31()

float rtabmap::Transform::r31 ( ) const
inline

Definition at line 68 of file Transform.h.

◆ r32()

float rtabmap::Transform::r32 ( ) const
inline

Definition at line 69 of file Transform.h.

◆ r33()

float rtabmap::Transform::r33 ( ) const
inline

Definition at line 70 of file Transform.h.

◆ rotation()

Transform rtabmap::Transform::rotation ( ) const

Definition at line 195 of file Transform.cpp.

◆ rotationMatrix()

cv::Mat rtabmap::Transform::rotationMatrix ( ) const

Definition at line 248 of file Transform.cpp.

◆ rtabmap_T_opengl()

static Transform rtabmap::Transform::rtabmap_T_opengl ( )
inlinestatic

Definition at line 153 of file Transform.h.

◆ setIdentity()

void rtabmap::Transform::setIdentity ( )

Definition at line 157 of file Transform.cpp.

◆ setNull()

void rtabmap::Transform::setNull ( )

Definition at line 152 of file Transform.cpp.

◆ size()

int rtabmap::Transform::size ( ) const
inline

Definition at line 90 of file Transform.h.

◆ theta()

float rtabmap::Transform::theta ( ) const

Definition at line 162 of file Transform.cpp.

◆ to3DoF()

Transform rtabmap::Transform::to3DoF ( ) const

Definition at line 210 of file Transform.cpp.

◆ to4DoF()

Transform rtabmap::Transform::to4DoF ( ) const

Definition at line 222 of file Transform.cpp.

◆ toEigen3d()

Eigen::Affine3d rtabmap::Transform::toEigen3d ( ) const

Definition at line 396 of file Transform.cpp.

◆ toEigen3f()

Eigen::Affine3f rtabmap::Transform::toEigen3f ( ) const

Definition at line 391 of file Transform.cpp.

◆ toEigen4d()

Eigen::Matrix4d rtabmap::Transform::toEigen4d ( ) const

Definition at line 381 of file Transform.cpp.

◆ toEigen4f()

Eigen::Matrix4f rtabmap::Transform::toEigen4f ( ) const

Definition at line 372 of file Transform.cpp.

◆ translation()

Transform rtabmap::Transform::translation ( ) const

Definition at line 203 of file Transform.cpp.

◆ translationMatrix()

cv::Mat rtabmap::Transform::translationMatrix ( ) const

Definition at line 253 of file Transform.cpp.

◆ x() [1/2]

float& rtabmap::Transform::x ( )
inline

Definition at line 92 of file Transform.h.

◆ x() [2/2]

const float& rtabmap::Transform::x ( ) const
inline

Definition at line 95 of file Transform.h.

◆ y() [1/2]

float& rtabmap::Transform::y ( )
inline

Definition at line 93 of file Transform.h.

◆ y() [2/2]

const float& rtabmap::Transform::y ( ) const
inline

Definition at line 96 of file Transform.h.

◆ z() [1/2]

float& rtabmap::Transform::z ( )
inline

Definition at line 94 of file Transform.h.

◆ z() [2/2]

const float& rtabmap::Transform::z ( ) const
inline

Definition at line 97 of file Transform.h.

Member Data Documentation

◆ data_

cv::Mat rtabmap::Transform::data_
private

Definition at line 178 of file Transform.h.


The documentation for this class was generated from the following files:


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:28