MRPT
1.9.9
|
Traits for SE(3), rigid-body transformations in R^3 space.
See indidual members for documentation, or [1] for a general overview.
#include <mrpt/poses/Lie/SE.h>
Public Types | |
using | tangent_vector = mrpt::math::CVectorFixedDouble< DOFs > |
using | manifold_vector = mrpt::math::CVectorFixedDouble< MANIFOLD_DIM > |
using | type = CPose3D |
using | light_type = mrpt::math::TPose3D |
using | tang2mat_jacob = mrpt::math::CMatrixDouble12_6 |
Type for Jacobian: tangent space -> SO(n) matrix. More... | |
using | mat2tang_jacob = mrpt::math::CMatrixDouble6_12 |
Type for Jacobian: SO(n) matrix -> tangent space. More... | |
using | matrix_TxT = mrpt::math::CMatrixDouble66 |
Type for Jacobians between so(n) vectors on the tangent space. More... | |
using | matrix_MxM = mrpt::math::CMatrixFixed< double, 12, 12 > |
Type for Jacobians between SO(n) 3x4 (sub)matrices in the manifold. More... | |
Static Public Member Functions | |
static type | exp (const tangent_vector &x) |
Retraction to SE(3), a pseudo-exponential map and its Jacobian. More... | |
static tangent_vector | log (const type &P) |
SE(3) pseudo-logarithm map . More... | |
static manifold_vector | asManifoldVector (const type &pose) |
Returns a vector with all manifold matrix elements in column-major order. More... | |
static type | fromManifoldVector (const manifold_vector &v) |
The inverse operation of asManifoldVector() More... | |
static tang2mat_jacob | jacob_dexpe_de (const tangent_vector &x) |
Jacobian for the pseudo-exponential exp(). More... | |
static mat2tang_jacob | jacob_dlogv_dv (const type &P) |
Jacobian for the pseudo-logarithm log() See 10.3.11 in [1]. More... | |
static tang2mat_jacob | jacob_dexpeD_de (const CPose3D &D) |
Jacobian d (e^eps * D) / d eps , with eps=increment in Lie Algebra. More... | |
static tang2mat_jacob | jacob_dDexpe_de (const CPose3D &D) |
Jacobian d (D * e^eps) / d eps , with eps=increment in Lie Algebra. More... | |
static tang2mat_jacob | jacob_dAexpeD_de (const CPose3D &A, const CPose3D &D) |
Jacobian d (A * e^eps * D) / d eps , with eps=increment in Lie Algebra. More... | |
static matrix_MxM | jacob_dAB_dA (const type &A, const type &B) |
Jacobian of the pose composition A*B for SE(3) 3x4 (sub)matrices, with respect to A. More... | |
static matrix_MxM | jacob_dAB_dB (const type &A, const type &B) |
Jacobian of the pose composition A*B for SE(3) 3x4 (sub)matrices, with respect to B. More... | |
static void | jacob_dDinvP1invP2_de1e2 (const type &Dinv, const type &P1, const type &P2, mrpt::optional_ref< matrix_TxT > df_de1=std::nullopt, mrpt::optional_ref< matrix_TxT > df_de2=std::nullopt) |
Return one or both of the following 6x6 Jacobians, useful in graph-slam problems:
With and increments in the linearized manifold for P1 and P2. More... | |
Static Public Attributes | |
static constexpr size_t | DOFs = 6 |
Number of actual degrees of freedom for this transformation. More... | |
static constexpr size_t | MANIFOLD_DIM = 3 * 4 |
Dimensionality of the matrix manifold (3x4=12 upper part of the 4x4) More... | |
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019 |