Specialization of SE for 2D poses.
Definition at line 65 of file SE_traits.h.
#include <mrpt/poses/SE_traits.h>
Public Types | |
| enum | { VECTOR_SIZE = 3 } | 
| typedef mrpt::math::CArrayDouble< VECTOR_SIZE > | array_t | 
| typedef mrpt::math::CMatrixFixedNumeric< double, VECTOR_SIZE, VECTOR_SIZE > | matrix_VxV_t | 
| typedef CPose2D | pose_t | 
| typedef mrpt::math::TPose2D | lightweight_pose_t | 
| typedef mrpt::math::TPoint2D | point_t | 
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:  
 
  With   | |
| typedef mrpt::math::CArrayDouble<VECTOR_SIZE> mrpt::poses::SE_traits< 2 >::array_t | 
Definition at line 68 of file SE_traits.h.
| typedef mrpt::math::TPose2D mrpt::poses::SE_traits< 2 >::lightweight_pose_t | 
Definition at line 71 of file SE_traits.h.
| typedef mrpt::math::CMatrixFixedNumeric<double,VECTOR_SIZE,VECTOR_SIZE> mrpt::poses::SE_traits< 2 >::matrix_VxV_t | 
Definition at line 69 of file SE_traits.h.
| typedef mrpt::math::TPoint2D mrpt::poses::SE_traits< 2 >::point_t | 
Definition at line 72 of file SE_traits.h.
| typedef CPose2D mrpt::poses::SE_traits< 2 >::pose_t | 
Definition at line 70 of file SE_traits.h.
| anonymous enum | 
| Enumerator | |
|---|---|
| VECTOR_SIZE | |
Definition at line 67 of file SE_traits.h.
      
  | 
  inlinestatic | 
Exponential map in SE(2)
Definition at line 75 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 81 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 78 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 86 of file SE_traits.h.
| Page generated by Doxygen 1.8.14 for MRPT 1.5.6 Git: 4c65e8431 Tue Apr 24 08:18:17 2018 +0200 at lun oct 28 01:35:26 CET 2019 |