Specialization of SE for 3D poses.
Definition at line 30 of file SE_traits.h.
#include <mrpt/poses/SE_traits.h>
Public Types | |
enum | { VECTOR_SIZE = 6 } |
typedef mrpt::math::CArrayDouble< VECTOR_SIZE > | array_t |
typedef mrpt::math::CMatrixFixedNumeric< double, VECTOR_SIZE, VECTOR_SIZE > | matrix_VxV_t |
typedef CPose3D | pose_t |
typedef mrpt::math::TPose3D | lightweight_pose_t |
typedef mrpt::math::TPoint3D | point_t |
Static Public Member Functions | |
static void | exp (const array_t &x, CPose3D &P) |
Exponential map in SE(3), with XYZ different from the first three values of "x". More... | |
static void | pseudo_exp (const array_t &x, CPose3D &P) |
Pseudo-Exponential map in SE(3), with XYZ copied from the first three values of "x". More... | |
static void | ln (const CPose3D &P, array_t &x) |
Logarithm map in SE(3) More... | |
static void | pseudo_ln (const CPose3D &P, array_t &x) |
A pseudo-Logarithm map in SE(3), where the output = [X,Y,Z, Ln(ROT)], that is, the normal SO(3) logarithm is used for the rotation components, but the translation is left unmodified. More... | |
static void | jacobian_dP1DP2inv_depsilon (const CPose3D &P1DP2inv, matrix_VxV_t *df_de1, matrix_VxV_t *df_de2) |
Return one or both of the following 6x6 Jacobians, useful in graph-slam problems:
With | |
typedef mrpt::math::CArrayDouble<VECTOR_SIZE> mrpt::poses::SE_traits< 3 >::array_t |
Definition at line 33 of file SE_traits.h.
typedef mrpt::math::TPose3D mrpt::poses::SE_traits< 3 >::lightweight_pose_t |
Definition at line 36 of file SE_traits.h.
typedef mrpt::math::CMatrixFixedNumeric<double,VECTOR_SIZE,VECTOR_SIZE> mrpt::poses::SE_traits< 3 >::matrix_VxV_t |
Definition at line 34 of file SE_traits.h.
typedef mrpt::math::TPoint3D mrpt::poses::SE_traits< 3 >::point_t |
Definition at line 37 of file SE_traits.h.
typedef CPose3D mrpt::poses::SE_traits< 3 >::pose_t |
Definition at line 35 of file SE_traits.h.
anonymous enum |
Enumerator | |
---|---|
VECTOR_SIZE |
Definition at line 32 of file SE_traits.h.
|
inlinestatic |
Exponential map in SE(3), with XYZ different from the first three values of "x".
Definition at line 40 of file SE_traits.h.
References mrpt::poses::CPose3D::exp().
|
static |
Return one or both of the following 6x6 Jacobians, useful in graph-slam problems:
With and
being increments in the linearized manifold for P1 and P2.
|
inlinestatic |
Logarithm map in SE(3)
Definition at line 46 of file SE_traits.h.
References mrpt::poses::CPose3D::ln(), and exprtk::details::x().
|
inlinestatic |
Pseudo-Exponential map in SE(3), with XYZ copied from the first three values of "x".
Definition at line 43 of file SE_traits.h.
References mrpt::poses::CPose3D::exp().
|
static |
A pseudo-Logarithm map in SE(3), where the output = [X,Y,Z, Ln(ROT)], that is, the normal SO(3) logarithm is used for the rotation components, but the translation is left unmodified.
Page generated by Doxygen 1.8.13 for MRPT 1.5.3 at Mon Oct 30 10:27:08 UTC 2017 |