#include <Transform.h>
Public Member Functions | |
Transform | clone () const |
const float * | data () const |
float * | data () |
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 | 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 |
RTABMAP_DEPRECATED (static Transform getClosestTransform(const std::map< double, Transform > &tfBuffer, const double &stamp, double *stampDiff),"Use Transform::getTransform() instead to get always accurate transforms.") | |
void | setIdentity () |
void | setNull () |
int | size () const |
float | theta () const |
Transform | to3DoF () const |
Eigen::Affine3d | toEigen3d () const |
Eigen::Affine3f | toEigen3f () const |
Eigen::Matrix4d | toEigen4d () const |
Eigen::Matrix4f | toEigen4f () const |
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 (const cv::Mat &transformationMatrix) | |
Transform (float x, float y, float z, float roll, float pitch, float yaw) | |
Transform (float x, float y, float z, float qx, float qy, float qz, float qw) | |
Transform (float x, float y, float theta) | |
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 |
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 | fromEigen3f (const Eigen::Affine3f &matrix) |
static Transform | fromEigen3f (const Eigen::Isometry3f &matrix) |
static Transform | fromEigen4d (const Eigen::Matrix4d &matrix) |
static Transform | fromEigen4f (const Eigen::Matrix4f &matrix) |
static Transform | fromString (const std::string &string) |
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_ |
Definition at line 41 of file Transform.h.
rtabmap::Transform::Transform | ( | ) |
Definition at line 41 of file Transform.cpp.
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.
rtabmap::Transform::Transform | ( | const cv::Mat & | transformationMatrix | ) |
Definition at line 57 of file Transform.cpp.
rtabmap::Transform::Transform | ( | float | x, |
float | y, | ||
float | z, | ||
float | roll, | ||
float | pitch, | ||
float | yaw | ||
) |
Definition at line 72 of file Transform.cpp.
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.
rtabmap::Transform::Transform | ( | float | x, |
float | y, | ||
float | theta | ||
) |
Definition at line 96 of file Transform.cpp.
|
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 480 of file Transform.cpp.
Transform rtabmap::Transform::clone | ( | ) | const |
Definition at line 102 of file Transform.cpp.
|
inline |
Definition at line 88 of file Transform.h.
|
inline |
Definition at line 89 of file Transform.h.
|
inline |
Definition at line 87 of file Transform.h.
|
static |
Definition at line 404 of file Transform.cpp.
|
static |
Definition at line 417 of file Transform.cpp.
|
static |
Definition at line 398 of file Transform.cpp.
|
static |
Definition at line 411 of file Transform.cpp.
|
static |
Definition at line 391 of file Transform.cpp.
|
static |
Definition at line 385 of file Transform.cpp.
|
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 431 of file Transform.cpp.
float rtabmap::Transform::getAngle | ( | float | x = 1.0f , |
float | y = 0.0f , |
||
float | z = 0.0f |
||
) | const |
Definition at line 245 of file Transform.cpp.
float rtabmap::Transform::getDistance | ( | const Transform & | t | ) | const |
Definition at line 262 of file Transform.cpp.
float rtabmap::Transform::getDistanceSquared | ( | const Transform & | t | ) | const |
Definition at line 267 of file Transform.cpp.
void rtabmap::Transform::getEulerAngles | ( | float & | roll, |
float & | pitch, | ||
float & | yaw | ||
) | const |
Definition at line 232 of file Transform.cpp.
|
static |
Definition at line 380 of file Transform.cpp.
float rtabmap::Transform::getNorm | ( | ) | const |
Definition at line 252 of file Transform.cpp.
float rtabmap::Transform::getNormSquared | ( | ) | const |
Definition at line 257 of file Transform.cpp.
Eigen::Quaterniond rtabmap::Transform::getQuaterniond | ( | ) | const |
Definition at line 375 of file Transform.cpp.
Eigen::Quaternionf rtabmap::Transform::getQuaternionf | ( | ) | const |
Definition at line 370 of file Transform.cpp.
|
static |
Definition at line 486 of file Transform.cpp.
void rtabmap::Transform::getTranslation | ( | float & | x, |
float & | y, | ||
float & | z | ||
) | const |
Definition at line 238 of file Transform.cpp.
void rtabmap::Transform::getTranslationAndEulerAngles | ( | float & | x, |
float & | y, | ||
float & | z, | ||
float & | roll, | ||
float & | pitch, | ||
float & | yaw | ||
) | const |
Definition at line 227 of file Transform.cpp.
Definition at line 272 of file Transform.cpp.
Transform rtabmap::Transform::inverse | ( | ) | const |
Definition at line 178 of file Transform.cpp.
bool rtabmap::Transform::isIdentity | ( | ) | const |
Definition at line 136 of file Transform.cpp.
bool rtabmap::Transform::isInvertible | ( | ) | const |
Definition at line 169 of file Transform.cpp.
bool rtabmap::Transform::isNull | ( | ) | const |
Definition at line 107 of file Transform.cpp.
void rtabmap::Transform::normalizeRotation | ( | ) |
Definition at line 285 of file Transform.cpp.
|
inline |
Definition at line 72 of file Transform.h.
|
inline |
Definition at line 73 of file Transform.h.
|
inline |
Definition at line 74 of file Transform.h.
|
inlinestatic |
Definition at line 144 of file Transform.h.
bool rtabmap::Transform::operator!= | ( | const Transform & | t | ) | const |
Definition at line 328 of file Transform.cpp.
|
inline |
Definition at line 78 of file Transform.h.
|
inline |
Definition at line 79 of file Transform.h.
Definition at line 309 of file Transform.cpp.
Definition at line 317 of file Transform.cpp.
bool rtabmap::Transform::operator== | ( | const Transform & | t | ) | const |
Definition at line 323 of file Transform.cpp.
|
inline |
Definition at line 76 of file Transform.h.
|
inline |
Definition at line 77 of file Transform.h.
std::string rtabmap::Transform::prettyPrint | ( | ) | const |
Definition at line 295 of file Transform.cpp.
|
inline |
Definition at line 62 of file Transform.h.
|
inline |
Definition at line 63 of file Transform.h.
|
inline |
Definition at line 64 of file Transform.h.
|
inline |
Definition at line 65 of file Transform.h.
|
inline |
Definition at line 66 of file Transform.h.
|
inline |
Definition at line 67 of file Transform.h.
|
inline |
Definition at line 68 of file Transform.h.
|
inline |
Definition at line 69 of file Transform.h.
|
inline |
Definition at line 70 of file Transform.h.
Transform rtabmap::Transform::rotation | ( | ) | const |
Definition at line 195 of file Transform.cpp.
cv::Mat rtabmap::Transform::rotationMatrix | ( | ) | const |
Definition at line 217 of file Transform.cpp.
rtabmap::Transform::RTABMAP_DEPRECATED | ( | static Transform | getClosestTransformconst std::map< double, Transform > &tfBuffer, const double &stamp, double *stampDiff, |
"Use Transform::getTransform() instead to get always accurate transforms." | |||
) |
|
inlinestatic |
Definition at line 148 of file Transform.h.
void rtabmap::Transform::setIdentity | ( | ) |
Definition at line 157 of file Transform.cpp.
void rtabmap::Transform::setNull | ( | ) |
Definition at line 152 of file Transform.cpp.
|
inline |
Definition at line 90 of file Transform.h.
float rtabmap::Transform::theta | ( | ) | const |
Definition at line 162 of file Transform.cpp.
Transform rtabmap::Transform::to3DoF | ( | ) | const |
Definition at line 210 of file Transform.cpp.
Eigen::Affine3d rtabmap::Transform::toEigen3d | ( | ) | const |
Definition at line 365 of file Transform.cpp.
Eigen::Affine3f rtabmap::Transform::toEigen3f | ( | ) | const |
Definition at line 360 of file Transform.cpp.
Eigen::Matrix4d rtabmap::Transform::toEigen4d | ( | ) | const |
Definition at line 350 of file Transform.cpp.
Eigen::Matrix4f rtabmap::Transform::toEigen4f | ( | ) | const |
Definition at line 341 of file Transform.cpp.
Transform rtabmap::Transform::translation | ( | ) | const |
Definition at line 203 of file Transform.cpp.
cv::Mat rtabmap::Transform::translationMatrix | ( | ) | const |
Definition at line 222 of file Transform.cpp.
|
inline |
Definition at line 92 of file Transform.h.
|
inline |
Definition at line 95 of file Transform.h.
|
inline |
Definition at line 93 of file Transform.h.
|
inline |
Definition at line 96 of file Transform.h.
|
inline |
Definition at line 94 of file Transform.h.
|
inline |
Definition at line 97 of file Transform.h.
|
private |
Definition at line 172 of file Transform.h.