#include <mrpt/poses/SE_traits.h>
Public Types | |
using | array_t = mrpt::math::CArrayDouble< VECTOR_SIZE > |
using | matrix_VxV_t = mrpt::math::CMatrixFixedNumeric< double, VECTOR_SIZE, VECTOR_SIZE > |
using | pose_t = CPose2D |
using | lightweight_pose_t = mrpt::math::TPose2D |
using | point_t = mrpt::math::TPoint2D |
Static Public Member Functions | |
static void | exp (const array_t &x, CPose2D &P) |
Exponential map in SE(2) More... | |
static void | pseudo_exp (const array_t &x, CPose2D &P) |
Pseudo-Exponential map in SE(2), in this case identical to exp() More... | |
static void | ln (const CPose2D &P, array_t &x) |
Logarithm map in SE(2) More... | |
static void | pseudo_ln (const CPose2D &P, array_t &x) |
A pseudo-Logarithm map in SE(2), where the output = [X,Y, Ln(ROT)], that is, the normal SO(2) logarithm is used for the rotation components, but the translation is left unmodified. More... | |
static void | jacobian_dP1DP2inv_depsilon (const CPose2D &P1DP2inv, matrix_VxV_t *df_de1, matrix_VxV_t *df_de2) |
Return one or both of the following 3x3 Jacobians, useful in graph-slam problems: More... | |
Static Public Attributes | |
constexpr static size_t | VECTOR_SIZE = 3 |
using mrpt::poses::SE_traits< 2 >::array_t = mrpt::math::CArrayDouble<VECTOR_SIZE> |
Definition at line 84 of file SE_traits.h.
using mrpt::poses::SE_traits< 2 >::lightweight_pose_t = mrpt::math::TPose2D |
Definition at line 88 of file SE_traits.h.
using mrpt::poses::SE_traits< 2 >::matrix_VxV_t = mrpt::math::CMatrixFixedNumeric<double, VECTOR_SIZE, VECTOR_SIZE> |
Definition at line 86 of file SE_traits.h.
using mrpt::poses::SE_traits< 2 >::point_t = mrpt::math::TPoint2D |
Definition at line 89 of file SE_traits.h.
using mrpt::poses::SE_traits< 2 >::pose_t = CPose2D |
Definition at line 87 of file SE_traits.h.
|
inlinestatic |
Exponential map in SE(2)
Definition at line 92 of file SE_traits.h.
References mrpt::poses::CPose2D::phi(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y().
|
static |
Return one or both of the following 3x3 Jacobians, useful in graph-slam problems:
With and being increments in the linearized manifold for P1 and P2.
|
inlinestatic |
Logarithm map in SE(2)
Definition at line 102 of file SE_traits.h.
References mrpt::poses::CPose2D::phi(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y().
|
inlinestatic |
Pseudo-Exponential map in SE(2), in this case identical to exp()
Definition at line 100 of file SE_traits.h.
|
inlinestatic |
A pseudo-Logarithm map in SE(2), where the output = [X,Y, Ln(ROT)], that is, the normal SO(2) logarithm is used for the rotation components, but the translation is left unmodified.
Definition at line 114 of file SE_traits.h.
|
staticconstexpr |
Definition at line 83 of file SE_traits.h.
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST |