49 matrix_VxV_t & J1 = *df_de1;
60 J1(0,4) = P1DP2inv.z(); J1(0,5) = -P1DP2inv.
y();
61 J1(1,3) = -P1DP2inv.z(); J1(1,5) = P1DP2inv.
x();
62 J1(2,3) = P1DP2inv.
y(); J1(2,4) =-P1DP2inv.
x();
80 J1.block(3,3,3,3) = (dLnRot_dRot * aux).eval();
89 matrix_VxV_t & J2 = *df_de2;
94 J2.set_unsafe(i,j, -
R.get_unsafe(i,j));
112 J2.block(3,3,3,3) = (dLnRot_dRot * aux).eval();
122 matrix_VxV_t *df_de1,
123 matrix_VxV_t *df_de2)
127 matrix_VxV_t & J1 = *df_de1;
133 J1.unit(VECTOR_SIZE,1.0);
134 J1(0,2) = -P1DP2inv.
y();
135 J1(1,2) = P1DP2inv.
x();
144 matrix_VxV_t & J2 = *df_de2;
146 const double ccos = cos(P1DP2inv.
phi());
147 const double csin = sin(P1DP2inv.
phi());
149 const double vals[] = {
double x() const
Common members of all points & poses classes.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
mrpt::math::CArrayDouble< 3 > ln_rotation() const
Take the logarithm of the 3x3 rotation matrix, generating the corresponding vector in the Lie Algebra...
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: With and being ...
This base provides a set of functions for maths stuff.
mrpt::math::CArrayDouble< 3 > m_coords
The translation vector [x,y,z] access directly or with x(), y(), z() setter/getter methods...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
static void ln_rot_jacob(const mrpt::math::CMatrixDouble33 &R, mrpt::math::CMatrixFixedNumeric< double, 3, 9 > &M)
Static function to compute the Jacobian of the SO(3) Logarithm function, evaluated at a given 3x3 rot...
const double & phi() const
Get the phi angle of the 2D pose (in radians)
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) logar...
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
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 and being ...