Main MRPT website > C++ reference for MRPT 1.9.9
SE_traits.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "poses-precomp.h" // Precompiled headers
11 
12 #include <mrpt/poses/SE_traits.h>
13 
14 using namespace mrpt;
15 using namespace mrpt::math;
16 
17 using namespace mrpt::poses;
18 
19 /** A pseudo-Logarithm map in SE(3), where the output = [X,Y,Z, Ln(ROT)], that
20  * is, the normal
21  * SO(3) logarithm is used for the rotation components, but the translation is
22  * left unmodified.
23  */
24 void SE_traits<3>::pseudo_ln(const CPose3D& P, array_t& x)
25 {
26  x[0] = P.m_coords[0];
27  x[1] = P.m_coords[1];
28  x[2] = P.m_coords[2];
29  CArrayDouble<3> ln_rot = P.ln_rotation();
30  x[3] = ln_rot[0];
31  x[4] = ln_rot[1];
32  x[5] = ln_rot[2];
33 }
34 
35 /** Return one or both of the following 6x6 Jacobians, useful in graph-slam
36  * problems...
37  */
39  const CPose3D& P1DP2inv, matrix_VxV_t* df_de1, matrix_VxV_t* df_de2)
40 {
41  const CMatrixDouble33& R =
42  P1DP2inv.getRotationMatrix(); // The rotation matrix.
43 
44  // Common part: d_Ln(R)_dR:
46  CPose3D::ln_rot_jacob(R, dLnRot_dRot);
47 
48  if (df_de1)
49  {
50  matrix_VxV_t& J1 = *df_de1;
51  // This Jacobian has the structure:
52  // [ I_3 | -[d_t]_x ]
53  // Jacob1 = [ ---------+------------------- ]
54  // [ 0_3x3 | dLnR_dR * (...) ]
55  //
56  J1.zeros();
57  J1(0, 0) = 1;
58  J1(1, 1) = 1;
59  J1(2, 2) = 1;
60 
61  J1(0, 4) = P1DP2inv.z();
62  J1(0, 5) = -P1DP2inv.y();
63  J1(1, 3) = -P1DP2inv.z();
64  J1(1, 5) = P1DP2inv.x();
65  J1(2, 3) = P1DP2inv.y();
66  J1(2, 4) = -P1DP2inv.x();
67 
68  alignas(MRPT_MAX_ALIGN_BYTES) const double aux_vals[] = {
69  0, R(2, 0), -R(1, 0), -R(2, 0), 0, R(0, 0), R(1, 0), -R(0, 0), 0,
70  // -----------------------
71  0, R(2, 1), -R(1, 1), -R(2, 1), 0, R(0, 1), R(1, 1), -R(0, 1), 0,
72  // -----------------------
73  0, R(2, 2), -R(1, 2), -R(2, 2), 0, R(0, 2), R(1, 2), -R(0, 2), 0};
74  const CMatrixFixedNumeric<double, 9, 3> aux(aux_vals);
75 
76  // right-bottom part = dLnRot_dRot * aux
77  J1.block(3, 3, 3, 3) = (dLnRot_dRot * aux).eval();
78  }
79  if (df_de2)
80  {
81  // This Jacobian has the structure:
82  // [ -R | 0_3x3 ]
83  // Jacob2 = [ ---------+------------------- ]
84  // [ 0_3x3 | dLnR_dR * (...) ]
85  //
86  matrix_VxV_t& J2 = *df_de2;
87  J2.zeros();
88 
89  for (int i = 0; i < 3; i++)
90  for (int j = 0; j < 3; j++)
91  J2.set_unsafe(i, j, -R.get_unsafe(i, j));
92 
93  alignas(MRPT_MAX_ALIGN_BYTES) const double aux_vals[] = {
94  0, R(0, 2), -R(0, 1), 0, R(1, 2), -R(1, 1), 0, R(2, 2), -R(2, 1),
95  // -----------------------
96  -R(0, 2), 0, R(0, 0), -R(1, 2), 0, R(1, 0), -R(2, 2), 0, R(2, 0),
97  // -----------------------
98  R(0, 1), -R(0, 0), 0, R(1, 1), -R(1, 0), 0, R(2, 1), -R(2, 0), 0};
99  const CMatrixFixedNumeric<double, 9, 3> aux(aux_vals);
100 
101  // right-bottom part = dLnRot_dRot * aux
102  J2.block(3, 3, 3, 3) = (dLnRot_dRot * aux).eval();
103  }
104 }
105 
106 /** Return one or both of the following 6x6 Jacobians, useful in graph-slam
107  * problems...
108  */
110  const CPose2D& P1DP2inv, matrix_VxV_t* df_de1, matrix_VxV_t* df_de2)
111 {
112  if (df_de1)
113  {
114  matrix_VxV_t& J1 = *df_de1;
115  // This Jacobian has the structure:
116  // [ I_2 | -[d_t]_x ]
117  // Jacob1 = [ ---------+--------------- ]
118  // [ 0 | 1 ]
119  //
120  J1.unit(VECTOR_SIZE, 1.0);
121  J1(0, 2) = -P1DP2inv.y();
122  J1(1, 2) = P1DP2inv.x();
123  }
124  if (df_de2)
125  {
126  // This Jacobian has the structure:
127  // [ -R | 0 ]
128  // Jacob2 = [ ---------+------- ]
129  // [ 0 | -1 ]
130  //
131  matrix_VxV_t& J2 = *df_de2;
132 
133  const double ccos = cos(P1DP2inv.phi());
134  const double csin = sin(P1DP2inv.phi());
135 
136  const double vals[] = {-ccos, csin, 0, -csin, -ccos, 0, 0, 0, -1};
138  }
139 }
poses-precomp.h
mrpt::poses::CPose2D::phi
const double & phi() const
Get the phi angle of the 2D pose (in radians)
Definition: CPose2D.h:82
mrpt::poses::CPose3D::getRotationMatrix
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
Definition: CPose3D.h:232
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CKalmanFilterCapable.h:30
R
const float R
Definition: CKinematicChain.cpp:138
mrpt::poses
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CHierarchicalMapMHPartition.h:25
mrpt::poses::SE_traits
A helper class for SE(2) and SE(3) geometry-related transformations, on-manifold optimization Jacobia...
Definition: SE_traits.h:29
mrpt::poses::CPoseOrPoint::y
double y() const
Definition: CPoseOrPoint.h:144
mrpt::poses::CPose2D
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle.
Definition: CPose2D.h:40
mrpt::poses::CPoseOrPoint::x
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:140
mrpt::poses::CPose3D
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
SE_traits.h
mrpt::math::CArrayNumeric
CArrayNumeric is an array for numeric types supporting several mathematical operations (actually,...
Definition: CArrayNumeric.h:25
mrpt::math::CMatrixFixedNumeric< double, 3, 3 >
mrpt::math::UNINITIALIZED_MATRIX
@ UNINITIALIZED_MATRIX
Definition: math_frwds.h:75
mrpt::math
This base provides a set of functions for maths stuff.
Definition: math/include/mrpt/math/bits_math.h:13
MRPT_MAX_ALIGN_BYTES
#define MRPT_MAX_ALIGN_BYTES
Definition: aligned_allocator.h:21
mrpt::poses::CPose3D::ln_rotation
mrpt::math::CArrayDouble< 3 > ln_rotation() const
Take the logarithm of the 3x3 rotation matrix, generating the corresponding vector in the Lie Algebra...
Definition: CPose3D.cpp:785
x
GLenum GLint x
Definition: glext.h:3538
mrpt::poses::CPose3D::m_coords
mrpt::math::CArrayDouble< 3 > m_coords
The translation vector [x,y,z] access directly or with x(), y(), z() setter/getter methods.
Definition: CPose3D.h:98



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