Main MRPT website > C++ reference
MRPT logo
Public Types | Static Public Member Functions

mrpt::poses::SE_traits< 3 > Struct Template Reference


Detailed Description

template<>
struct mrpt::poses::SE_traits< 3 >

Specialization of SE for 3D poses.

See also:
SE_traits

Definition at line 46 of file SE_traits.h.

#include <mrpt/poses/SE_traits.h>

List of all members.

Public Types

enum  { VECTOR_SIZE = 6 }
typedef CArrayDouble< VECTOR_SIZE > array_t
typedef CMatrixFixedNumeric
< double, VECTOR_SIZE,
VECTOR_SIZE > 
matrix_VxV_t
typedef CPose3D pose_t

Static Public Member Functions

static void exp (const array_t &x, CPose3D &P)
 Exponential map in SE(3).
static void ln (const CPose3D &P, array_t &x)
 Logarithm map in SE(3).
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.
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:

\[ \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.


Member Typedef Documentation

typedef CArrayDouble<VECTOR_SIZE> mrpt::poses::SE_traits< 3 >::array_t

Definition at line 49 of file SE_traits.h.

typedef CMatrixFixedNumeric<double,VECTOR_SIZE,VECTOR_SIZE> mrpt::poses::SE_traits< 3 >::matrix_VxV_t

Definition at line 50 of file SE_traits.h.

Definition at line 51 of file SE_traits.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
VECTOR_SIZE 

Definition at line 48 of file SE_traits.h.


Member Function Documentation

static void mrpt::poses::SE_traits< 3 >::exp ( const array_t x,
CPose3D P 
) [inline, static]

Exponential map in SE(3).

Definition at line 54 of file SE_traits.h.

References exp().

static void mrpt::poses::SE_traits< 3 >::jacobian_dP1DP2inv_depsilon ( const CPose3D P1DP2inv,
matrix_VxV_t df_de1,
matrix_VxV_t df_de2 
) [static]

Return one or both of the following 6x6 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.

static void mrpt::poses::SE_traits< 3 >::ln ( const CPose3D P,
array_t x 
) [inline, static]

Logarithm map in SE(3).

Definition at line 57 of file SE_traits.h.

References mrpt::poses::CPose3D::ln().

static void mrpt::poses::SE_traits< 3 >::pseudo_ln ( const CPose3D P,
array_t x 
) [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.7.1 for MRPT 0.9.4 SVN: at Mon Jan 10 23:33:19 UTC 2011