12 #include <mrpt/config.h> 41 #include <mrpt/otherlibs/sophus/so3.hpp> 42 #include <mrpt/otherlibs/sophus/se3.hpp> 56 : m_ypr_uptodate(true), m_yaw(0),m_pitch(0),m_roll(0)
71 : m_ypr_uptodate(false)
77 : m_ypr_uptodate(false)
83 : m_ypr_uptodate(false), m_yaw(),m_pitch(),m_roll()
104 for (
int r=0;
r<3;
r++)
105 for (
int c=0;
c<3;
c++)
107 for (
int r=0;
r<3;
r++)
128 p.quat().rotationMatrixNoResize(
m_ROT);
157 for (
int i = 0; i < 3; i++) out <<
m_coords[i];
158 for (
int r = 0;
r < 3;
r++)
159 for (
int c = 0;
c < 3;
c++) out <<
m_ROT(
r,
c);
178 m_ROT = HM2.block(0,0,3,3).cast<
double>();
191 m_ROT = HM.block(0,0,3,3);
202 in >>
p[0]>>
p[1]>>
p[2]>>
p[3]>>
p[4]>>
p[5]>>
p[6];
209 p.quat().rotationMatrixNoResize(
m_ROT);
213 for (
int i = 0; i < 3; i++) in >>
m_coords[i];
214 for (
int r = 0;
r < 3;
r++)
228 const std::streamsize old_pre = o.precision();
229 const std::ios_base::fmtflags old_flags = o.flags();
230 o <<
"(x,y,z,yaw,pitch,roll)=(" << std::fixed << std::setprecision(4) <<
p.m_coords[0] <<
"," <<
p.m_coords[1] <<
"," <<
p.m_coords[2] <<
"," 231 << std::setprecision(2) <<
RAD2DEG(
p.yaw()) <<
"deg," <<
RAD2DEG(
p.pitch()) <<
"deg," <<
RAD2DEG(
p.roll()) <<
"deg)";
233 o.precision(old_pre);
246 const char* fields[] = {
"R",
"t"};
247 mexplus::MxArray pose_struct( mexplus::MxArray::Struct(
sizeof(fields)/
sizeof(fields[0]),fields) );
250 return pose_struct.release();
293 ::sincos(
m_yaw,&sy,&cy);
299 const double cy = cos(
m_yaw);
300 const double sy = sin(
m_yaw);
301 const double cp = cos(
m_pitch);
302 const double sp = sin(
m_pitch);
303 const double cr = cos(
m_roll);
304 const double sr = sin(
m_roll);
308 cy*cp, cy*sp*sr-sy*cr, cy*sp*cr+sy*sr,
309 sy*cp, sy*sp*sr+cy*cr, sy*sp*cr-cy*sr,
343 if ( (fabs(
m_ROT(2,1))+fabs(
m_ROT(2,2)))<10*std::numeric_limits<double>::epsilon() )
381 double &out_pitch )
const 388 out_range =
local.norm();
397 out_pitch = -asin(
local.z / out_range );
443 bool use_small_rot_approx )
const 446 if (out_jacobian_df_dpoint)
447 *out_jacobian_df_dpoint =
m_ROT;
450 if (out_jacobian_df_dpose)
452 if (use_small_rot_approx)
458 0, 0, 1, 0, -lx, ly };
467 ::sincos(
m_yaw,&sy,&cy);
473 const double cy = cos(
m_yaw);
474 const double sy = sin(
m_yaw);
475 const double cp = cos(
m_pitch);
476 const double sp = sin(
m_pitch);
477 const double cr = cos(
m_roll);
478 const double sr = sin(
m_roll);
483 -lx*sy*cp+ly*(-sy*sp*sr-cy*cr)+lz*(-sy*sp*cr+cy*sr),
484 -lx*cy*sp+ly*(cy*cp*sr )+lz*(cy*cp*cr ),
485 ly*(cy*sp*cr+sy*sr)+lz*(-cy*sp*sr+sy*cr),
487 lx*cy*cp+ly*(cy*sp*sr-sy*cr)+lz*(cy*sp*cr+sy*sr),
488 -lx*sy*sp+ly*(sy*cp*sr) +lz*(sy*cp*cr ),
489 ly*(sy*sp*cr-cy*sr)+lz*(-sy*sp*sr-cy*cr),
492 -lx*cp-ly*sp*sr-lz*sp*cr,
504 if (out_jacobian_df_dse3)
509 0, 0, 1, gy,-gx, 0 };
516 #if MRPT_HAS_SSE2 && defined(MRPT_USE_SSE2) 561 b.getInverseHomogeneousMatrix( B_INV );
614 for (
int r=0;
r<3;
r++)
619 for (
int r=0;
r<3;
r++)
672 for (
int i=0;i<3;i++)
694 if (out_jacobian_df_dpoint)
695 *out_jacobian_df_dpoint = R_inv;
698 if (out_jacobian_df_dpose)
705 ::sincos(
m_yaw,&sy,&cy);
711 const double cy = cos(
m_yaw);
712 const double sy = sin(
m_yaw);
713 const double cp = cos(
m_pitch);
714 const double sp = sin(
m_pitch);
715 const double cr = cos(
m_roll);
716 const double sr = sin(
m_roll);
719 const double m11_dy = -sy*cp;
const double m12_dy = cy*cp;
const double m13_dy = 0;
720 const double m11_dp = -cy*sp;
const double m12_dp = -sy*sp;
const double m13_dp = -cp;
721 const double m11_dr = 0;
const double m12_dr = 0;
const double m13_dr = 0;
723 const double m21_dy = (-sy*sp*sr-cy*cr);
const double m22_dy = (cy*sp*sr-sy*cr);
const double m23_dy = 0;
724 const double m21_dp = (cy*cp*sr );
const double m22_dp = (sy*cp*sr );
const double m23_dp = -sp*sr;
725 const double m21_dr = (cy*sp*cr+sy*sr);
const double m22_dr = (sy*sp*cr-cy*sr);
const double m23_dr = cp*cr;
727 const double m31_dy = (-sy*sp*cr+cy*sr);
const double m32_dy = (cy*sp*cr+sy*sr);
const double m33_dy = 0;
728 const double m31_dp = (cy*cp*cr );
const double m32_dp = (sy*cp*cr );
const double m33_dp = -sp*cr;
729 const double m31_dr = (-cy*sp*sr+sy*cr);
const double m32_dr = (-sy*sp*sr-cy*cr);
const double m33_dr = -cp*sr;
737 Ax*m11_dy + Ay*m12_dy + Az*m13_dy ,
738 Ax*m11_dp + Ay*m12_dp + Az*m13_dp,
739 Ax*m11_dr + Ay*m12_dr + Az*m13_dr,
742 Ax*m21_dy + Ay*m22_dy + Az*m23_dy,
743 Ax*m21_dp + Ay*m22_dp + Az*m23_dp,
744 Ax*m21_dr + Ay*m22_dr + Az*m23_dr,
747 Ax*m31_dy + Ay*m32_dy + Az*m33_dy,
748 Ax*m31_dp + Ay*m32_dp + Az*m33_dp,
749 Ax*m31_dr + Ay*m32_dr + Az*m33_dr,
754 lx = t_inv[0] + R_inv(0,0) * gx + R_inv(0,1) * gy + R_inv(0,2) * gz;
755 ly = t_inv[1] + R_inv(1,0) * gx + R_inv(1,1) * gy + R_inv(1,2) * gz;
756 lz = t_inv[2] + R_inv(2,0) * gx + R_inv(2,1) * gy + R_inv(2,2) * gz;
759 if (out_jacobian_df_dse3)
763 0, -1, 0, lz, 0, -lx,
764 0, 0, -1, -ly, lx, 0 };
778 if (pseudo_exponential)
780 auto R = Sophus::SO3<double>::exp( mu.block<3,1>(3,0) );
788 auto R = Sophus::SE3<double>::exp(mu);
795 Sophus::SO3<double>
R(this->
m_ROT);
801 auto R = Sophus::SO3<double>::exp(
w);
816 template <
class VEC3,
class MAT33>
824 template <
typename VEC3,
typename MAT3x3,
typename MAT3x9>
831 a[0], -B(0,2), B(0,1), B(0,2),
a[0], -B(0,0),-B(0,1), B(0,0),
a[0],
832 a[1], -B(1,2), B(1,1), B(1,2),
a[1], -B(1,0),-B(1,1), B(1,0),
a[1],
833 a[2], -B(2,2), B(2,1), B(2,2),
a[2], -B(2,0),-B(2,1), B(2,0),
a[2]
835 RES.loadFromArray(vals);
866 const double d = 0.5*(
R(0,0)+
R(1,1)+
R(2,2)-1);
875 const double theta = acos(d);
876 const double theta2 =
square(theta);
877 const double oned2 = (1-
square(d));
878 const double sq = std::sqrt(oned2);
879 const double cot = 1./tan(0.5*theta);
880 const double csc2 =
square(1./sin(0.5*theta));
888 skewR.multiply_Ab(
t,skewR_t);
890 skewR_t*= -(d*theta-sq)/(8*pow(sq,3));
894 skewR2.multiply_AB(skewR,skewR);
897 skewR2.multiply_Ab(
t,skewR2_t);
898 skewR2_t*= (((theta*sq-d*theta2)*(0.5*theta*cot-1))-theta*sq*((0.25*theta*cot)+0.125*theta2*csc2-1))/(4*theta2*
square(oned2));
902 B *=-0.5*theta/(2*sq);
926 J.insertMatrix(3,0, M);
931 J.insertMatrix(0,0, M);
941 const double d = 0.5*(
R(0,0)+
R(1,1)+
R(2,2)-1);
948 Omega2.multiply_AAt(Omega);
960 const double theta = acos(d);
961 omega *=theta/(2*std::sqrt(1-d*d));
966 Omega2.multiply_AAt(Omega);
968 Omega2 *= (1-theta/(2*std::tan(theta*0.5)))/
square(theta);
974 J.insertMatrix(0,9, V_inv);
979 const double d = 0.5*(
R(0,0)+
R(1,1)+
R(2,2)-1);
989 const double theta = acos(d);
990 const double d2 =
square(d);
991 const double sq = std::sqrt(1-d2);
993 a *= (d*theta-sq)/(4*(sq*sq*sq));
994 B.unit(3, -theta/(2*sq) );
1002 jacob.block<9,3>(0,0).setZero();
1003 jacob.block<3,3>(9,0).setIdentity();
1004 for (
int i=0;i<3;i++) {
1005 Eigen::Block< Eigen::Matrix<double,12,6>,3,3,
false> trg_blc = jacob.block<3,3>(3*i,3);
1009 Eigen::Block< Eigen::Matrix<double,12,6>,3,3,
false> trg_blc = jacob.block<3,3>(9,3);
1017 jacob.block<9,3>(0,0).setZero();
1019 Eigen::Matrix<double,3,3> aux;
1020 for (
int i=0;i<3;i++) {
1022 jacob.block<3,3>(3*i,3) = A.
m_ROT * aux;
1025 jacob.block<3,3>(9,3) = A.
m_ROT * aux;
1030 for (
int i=0;i<3;i++)
1031 for (
int j=0;j<3;j++)
1032 m_ROT(i,j) = std::numeric_limits<double>::quiet_NaN();
1034 for (
int i=0;i<3;i++)
1035 m_coords[i] = std::numeric_limits<double>::quiet_NaN();
void readFromStream(mrpt::utils::CStream &in, int version)
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly...
double x() const
Common members of all points & poses classes.
void inverseComposeFrom(const CPose3D &A, const CPose3D &B)
Makes this method is slightly more efficient than "this= A - B;" since it avoids the temporary objec...
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
static mrpt::math::CMatrixDouble33 exp_rotation(const mrpt::math::CArrayNumeric< double, 3 > &vect)
Exponentiate a vector in the Lie algebra to generate a new SO(3) (a 3x3 rotation matrix).
mxArray * convertToMatlab(const Eigen::EigenBase< Derived > &mat)
Convert vectors, arrays and matrices into Matlab vectors/matrices.
The virtual base class which provides a unified interface for all persistent objects in MRPT...
void skew_symmetric3(const VECTOR &v, MATRIX &M)
Computes the 3x3 skew symmetric matrix from a 3-vector or 3-array: .
mrpt::math::CMatrixDouble33 m_ROT
The 3x3 rotation matrix, access with getRotationMatrix(), setRotationMatrix() (It's not safe to set t...
bool isHorizontal(const double tolerance=0) const
Return true if the 6D pose represents a Z axis almost exactly vertical (upwards or downwards)...
double roll
Roll coordinate (rotation angle over X coordinate).
bool m_ypr_uptodate
Whether yaw/pitch/roll members are up-to-date since the last rotation matrix update.
GLdouble GLdouble GLdouble GLdouble q
mrpt::math::CArrayDouble< 3 > ln_rotation() const
Take the logarithm of the 3x3 rotation matrix, generating the corresponding vector in the Lie Algebra...
This file implements several operations that operate element-wise on individual or pairs of container...
CArrayNumeric is an array for numeric types supporting several mathematical operations (actually...
double m_roll
These variables are updated every time that the object rotation matrix is modified (construction...
void getAsQuaternion(mrpt::math::CQuaternion< double > &q, mrpt::math::CMatrixFixedNumeric< double, 4, 3 > *out_dq_dr=NULL) const
Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored) ...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
CMatrixFixedNumeric< double, 4, 4 > CMatrixDouble44
double pitch() const
Get the PITCH angle (in radians)
double yaw() const
Get the YAW angle (in radians)
CPose3D operator+(const CPose3D &b) const
The operator is the pose compounding operator.
void rebuildRotationMatrix()
Rebuild the homog matrix from the angles.
double z
X,Y,Z coordinates.
double yaw
Yaw coordinate (rotation angle over Z axis).
IMPLEMENTS_SERIALIZABLE(CLogFileRecord_FullEval, CHolonomicLogFileRecord, mrpt::nav) IMPLEMENTS_SERIALIZABLE(CHolonomicFullEval
void updateYawPitchRoll() const
Updates Yaw/pitch/roll members from the m_ROT.
void inverse()
Convert this pose into its inverse, saving the result in itself.
GLubyte GLubyte GLubyte GLubyte w
void setRotationMatrix(const mrpt::math::CMatrixDouble33 &ROT)
Sets the 3x3 rotation matrix.
T square(const T x)
Inline function for the square of a number.
double distanceEuclidean6D(const CPose3D &o) const
The euclidean distance between two poses taken as two 6-length vectors (angles in radians)...
#define ASSERTDEBMSG_(f, __ERROR_MSG)
static void jacob_dexpeD_de(const CPose3D &D, Eigen::Matrix< double, 12, 6 > &jacob)
The Jacobian d (e^eps * D) / d eps , with eps=increment in Lie Algebra.
void skew_symmetric3_neg(const VECTOR &v, MATRIX &M)
Computes the negative version of a 3x3 skew symmetric matrix from a 3-vector or 3-array: ...
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=NULL, bool use_small_rot_approx=false) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
void dVinvt_dR(const CPose3D &P, CMatrixFixedNumeric< double, 3, 9 > &J)
mrpt::math::CArrayDouble< 3 > m_coords
The translation vector [x,y,z] access directly or with x(), y(), z() setter/getter methods...
void composeFrom(const CPose3D &A, const CPose3D &B)
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids th...
void setToNaN() MRPT_OVERRIDE
Set all data fields to quiet NaN.
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
bool operator!=(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
CPose2D BASE_IMPEXP operator-(const CPose2D &p)
Unary - operator: return the inverse pose "-p" (Note that is NOT the same than a pose with negative x...
void addComponents(const CPose3D &p)
Scalar sum of all 6 components: This is diferent from poses composition, which is implemented as "+" ...
void sphericalCoordinates(const mrpt::math::TPoint3D &point, double &out_range, double &out_yaw, double &out_pitch) const
Computes the spherical coordinates of a 3D point as seen from the 6D pose specified by this object...
void M3x9(const VEC3 &a, const MAT3x3 &B, MAT3x9 &RES)
#define IMPLEMENTS_MEXPLUS_FROM(complete_type)
CMatrixFixedNumeric< double, 3, 3 > CMatrixDouble33
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
void deltaR(const MAT33 &R, VEC3 &v)
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
A class used to store a 2D point.
A class used to store a 3D point.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double roll() const
Get the ROLL angle (in radians)
double pitch
Pitch coordinate (rotation angle over Y axis).
void loadFromArray(const T *vals)
void operator*=(const double s)
Scalar multiplication of x,y,z,yaw,pitch & roll (angles will be wrapped to the ]-pi,pi] interval).
void getYawPitchRoll(double &yaw, double &pitch, double &roll) const
Returns the three angles (yaw, pitch, roll), in radians, from the rotation matrix.
void ln_jacob(mrpt::math::CMatrixFixedNumeric< double, 6, 12 > &J) const
Jacobian of the logarithm of the 3x4 matrix defined by this pose.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
CMatrixDouble33 ddeltaRt_dR(const CPose3D &P)
void inverseComposePoint(const double gx, const double gy, const double gz, double &lx, double &ly, double &lz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=NULL) const
Computes the 3D point L such as .
#define ASSERT_ABOVEEQ_(__A, __B)
GLdouble GLdouble GLdouble r
size_t size(const MATRIXLIKE &m, const int dim)
bool operator==(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
virtual mxArray * writeToMatlab() const
Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class.
void homogeneousMatrixInverse(const MATRIXLIKE1 &M, MATRIXLIKE2 &out_inverse_M)
Efficiently compute the inverse of a 4x4 homogeneous matrix by only transposing the rotation 3x3 part...
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...
This file implements matrix/vector text and binary serialization.
mrpt::math::CArrayDouble< 3 > m_rotvec
The rotation vector [vx,vy,vz].
CPose3D()
Default constructor, with all the coordinates set to zero.
void setFromValues(const double x0, const double y0, const double z0, const double yaw=0, const double pitch=0, const double roll=0)
Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes...
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
A partial specialization of CArrayNumeric for double numbers.
void normalizeAngles()
Rebuild the internal matrix & update the yaw/pitch/roll angles within the ]-PI,PI] range (Must be cal...
mrpt::math::CArrayDouble< 6 > ln() const
A 3D pose, with a 3D translation and a rotation in 3D parameterized in rotation-vector form (equivale...
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
void getAsVector(mrpt::math::CVectorDouble &v) const
Returns a 1x6 vector with [x y z yaw pitch roll].
This class is a "CSerializable" wrapper for "CMatrixFloat".
GLubyte GLubyte GLubyte a
static CPose3D exp(const mrpt::math::CArrayNumeric< double, 6 > &vect, bool pseudo_exponential=false)
Exponentiate a Vector in the SE(3) Lie Algebra to generate a new CPose3D (static method).
void writeToStream(mrpt::utils::CStream &out, int *getVersion) const
Introduces a pure virtual method responsible for writing to a CStream.
void getAsQuaternion(mrpt::math::CQuaternionDouble &q, mrpt::math::CMatrixFixedNumeric< double, 4, 3 > *out_dq_dr=NULL) const
Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored) ...
static void jacob_dAexpeD_de(const CPose3D &A, const CPose3D &D, Eigen::Matrix< double, 12, 6 > &jacob)
The Jacobian d (A * e^eps * D) / d eps , with eps=increment in Lie Algebra.
struct mxArray_tag mxArray
Forward declaration for mxArray (avoid #including as much as possible to speed up compiling) ...
std::ostream & operator<<(std::ostream &o, const CPoint< DERIVEDCLASS > &p)
Dumps a point as a string [x,y] or [x,y,z].