Main MRPT website > C++ reference for MRPT 1.9.9
List of all members | Public Types | Static Public Member Functions | Static Public Attributes
mrpt::poses::SE_traits< 2 > Struct Reference

Detailed Description

Specialization of SE for 2D poses.

See also
SE_traits

Definition at line 81 of file SE_traits.h.

#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
 

Member Typedef Documentation

◆ array_t

Definition at line 84 of file SE_traits.h.

◆ lightweight_pose_t

Definition at line 88 of file SE_traits.h.

◆ matrix_VxV_t

Definition at line 86 of file SE_traits.h.

◆ point_t

Definition at line 89 of file SE_traits.h.

◆ pose_t

Definition at line 87 of file SE_traits.h.

Member Function Documentation

◆ exp()

static void mrpt::poses::SE_traits< 2 >::exp ( const array_t x,
CPose2D P 
)
inlinestatic

◆ jacobian_dP1DP2inv_depsilon()

static void mrpt::poses::SE_traits< 2 >::jacobian_dP1DP2inv_depsilon ( const CPose2D P1DP2inv,
matrix_VxV_t df_de1,
matrix_VxV_t df_de2 
)
static

Return one or both of the following 3x3 Jacobians, useful in graph-slam problems:

\[ \frac{\partial pseudoLn(P_1 D P_2^{-1}) }{\partial \epsilon_1} \]

\[ \frac{\partial pseudoLn(P_1 D P_2^{-1}) }{\partial \epsilon_2} \]

With $ \epsilon_1 $ and $ \epsilon_2 $ being increments in the linearized manifold for P1 and P2.

◆ ln()

static void mrpt::poses::SE_traits< 2 >::ln ( const CPose2D P,
array_t x 
)
inlinestatic

◆ pseudo_exp()

static void mrpt::poses::SE_traits< 2 >::pseudo_exp ( const array_t x,
CPose2D P 
)
inlinestatic

Pseudo-Exponential map in SE(2), in this case identical to exp()

Definition at line 100 of file SE_traits.h.

◆ pseudo_ln()

static void mrpt::poses::SE_traits< 2 >::pseudo_ln ( const CPose2D P,
array_t x 
)
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.

Member Data Documentation

◆ VECTOR_SIZE

constexpr static size_t mrpt::poses::SE_traits< 2 >::VECTOR_SIZE = 3
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