Main MRPT website > C++ reference
MRPT logo
CPose3D.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2014, 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 #ifndef CPOSE3D_H
10 #define CPOSE3D_H
11 
12 #include <mrpt/poses/CPose.h>
14 #include <mrpt/math/CQuaternion.h>
15 
16 namespace mrpt
17 {
18 namespace poses
19 {
20  using namespace mrpt::math;
21 
24 
26 
27  /** A class used to store a 3D pose (a 3D translation + a rotation in 3D).
28  * The 6D transformation in SE(3) stored in this class is kept in two
29  * separate containers: a 3-array for the translation, and a 3x3 rotation matrix.
30  *
31  * This class allows parameterizing 6D poses as a 6-vector: [x y z yaw pitch roll] (read below
32  * for the angles convention). Note however,
33  * that the yaw/pitch/roll angles are only computed (on-demand and transparently)
34  * when the user requests them. Normally, rotations and transformations are always handled
35  * via the 3x3 rotation matrix.
36  *
37  * Yaw/Pitch/Roll angles are defined as successive rotations around *local* (dynamic) axes in the Z/Y/X order:
38  *
39  * <div align=center>
40  * <img src="CPose3D.gif">
41  * </div>
42  *
43  * It may be extremely confusing and annoying to find a different criterion also involving
44  * the names "yaw, pitch, roll" but regarding rotations around *global* (static) axes.
45  * Fortunately, it's very easy to see (by writing down the product of the three
46  * rotation matrices) that both conventions lead to exactly the same numbers.
47  * Only, that it's conventional to write the numbers in reverse order.
48  * That is, the same rotation can be described equivalently with any of these two
49  * parameterizations:
50  *
51  * - In local axes Z/Y/X convention: [yaw pitch roll] (This is the convention used in mrpt::poses::CPose3D)
52  * - In global axes X/Y/Z convention: [roll pitch yaw] (One of the Euler angles conventions)
53  *
54  * For further descriptions of point & pose classes, see mrpt::poses::CPoseOrPoint or refer
55  * to the <a href="http://www.mrpt.org/2D_3D_Geometry"> 2D/3D Geometry tutorial</a> online.
56  *
57  * To change the individual components of the pose, use CPose3D::setFromValues. This class assures that the internal
58  * 3x3 rotation matrix is always up-to-date with the "yaw pitch roll" members.
59  *
60  * Rotations in 3D can be also represented by quaternions. See mrpt::math::CQuaternion, and method CPose3D::getAsQuaternion.
61  *
62  * This class and CPose3DQuat are very similar, and they can be converted to the each other automatically via transformation constructors.
63  *
64  * There are Lie algebra methods: \a exp and \a ln (see the methods for documentation).
65  *
66  * \note Read also: "A tutorial on SE(3) transformation parameterizations and on-manifold optimization", Jose-Luis Blanco. http://mapir.isa.uma.es/~jlblanco/papers/jlblanco2010geometry3D_techrep.pdf
67  *
68  * \ingroup poses_grp
69  * \sa CPoseOrPoint,CPoint3D, mrpt::math::CQuaternion
70  */
71  class BASE_IMPEXP CPose3D : public CPose<CPose3D>, public mrpt::utils::CSerializable
72  {
73  // This must be added to any CSerializable derived class:
75 
76  public:
77  CArrayDouble<3> m_coords; //!< The translation vector [x,y,z] access directly or with x(), y(), z() setter/getter methods.
78  protected:
79  CMatrixDouble33 m_ROT; //!< The 3x3 rotation matrix, access with getRotationMatrix(), setRotationMatrix() (It's not safe to set this field as public)
80 
81  mutable bool m_ypr_uptodate; //!< Whether yaw/pitch/roll members are up-to-date since the last rotation matrix update.
82  mutable double m_yaw, m_pitch, m_roll; //!< These variables are updated every time that the object rotation matrix is modified (construction, loading from values, pose composition, etc )
83 
84  /** Rebuild the homog matrix from the angles. */
85  void rebuildRotationMatrix();
86 
87  /** Updates Yaw/pitch/roll members from the m_ROT */
88  inline void updateYawPitchRoll() const { if (!m_ypr_uptodate) { m_ypr_uptodate=true; getYawPitchRoll( m_yaw, m_pitch, m_roll ); } }
89 
90  public:
91  /** @name Constructors
92  @{ */
93 
94  /** Default constructor, with all the coordinates set to zero. */
95  CPose3D();
96 
97  /** Constructor with initilization of the pose; (remember that angles are always given in radians!) */
98  CPose3D(const double x,const double y,const double z,const double yaw=0, const double pitch=0, const double roll=0);
99 
100  /** Constructor from a 4x4 homogeneous matrix - the passed matrix can be actually of any size larger than or equal 3x4, since only those first values are used (the last row of a homogeneous 4x4 matrix are always fixed). */
101  explicit CPose3D(const math::CMatrixDouble &m);
102 
103  /** Constructor from a 4x4 homogeneous matrix: */
104  explicit CPose3D(const math::CMatrixDouble44 &m);
105 
106  /** Constructor from a 3x3 rotation matrix and a the translation given as a 3-vector, a 3-array, a CPoint3D or a TPoint3D */
107  template <class MATRIX33,class VECTOR3>
108  inline CPose3D(const MATRIX33 &rot, const VECTOR3& xyz) : m_ROT(UNINITIALIZED_MATRIX), m_ypr_uptodate(false)
109  {
111  for (int r=0;r<3;r++)
112  for (int c=0;c<3;c++)
113  m_ROT(r,c)=rot.get_unsafe(r,c);
114  for (int r=0;r<3;r++) m_coords[r]=xyz[r];
115  }
116  //! \overload
117  inline CPose3D(const CMatrixDouble33 &rot, const CArrayDouble<3>& xyz) : m_coords(xyz),m_ROT(rot), m_ypr_uptodate(false)
118  { }
119 
120  /** Constructor from a CPose2D object.
121  */
122  CPose3D(const CPose2D &);
123 
124  /** Constructor from a CPoint3D object.
125  */
126  CPose3D(const CPoint3D &);
127 
128  /** Constructor from lightweight object.
129  */
130  CPose3D(const mrpt::math::TPose3D &);
131 
132  /** Constructor from a quaternion (which only represents the 3D rotation part) and a 3D displacement. */
133  CPose3D(const mrpt::math::CQuaternionDouble &q, const double x, const double y, const double z );
134 
135  /** Constructor from a CPose3DQuat. */
136  CPose3D(const CPose3DQuat &);
137 
138  /** Constructor from a CPose3DRotVec. */
139  CPose3D(const CPose3DRotVec &p );
140 
141  /** Fast constructor that leaves all the data uninitialized - call with UNINITIALIZED_POSE as argument */
142  inline CPose3D(TConstructorFlags_Poses constructor_dummy_param) : m_ROT(UNINITIALIZED_MATRIX), m_ypr_uptodate(false) { }
143 
144  /** Constructor from an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz]
145  * where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose
146  * \sa setFrom12Vector, getAs12Vector
147  */
148  inline explicit CPose3D(const CArrayDouble<12> &vec12) : m_ROT( UNINITIALIZED_MATRIX ), m_ypr_uptodate(false) {
149  setFrom12Vector(vec12);
150  }
151 
152  /** @} */ // end Constructors
153 
154 
155 
156  /** @name Access 3x3 rotation and 4x4 homogeneous matrices
157  @{ */
158 
159  /** Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).
160  * \sa getInverseHomogeneousMatrix, getRotationMatrix
161  */
162  inline void getHomogeneousMatrix(CMatrixDouble44 & out_HM ) const
163  {
164  out_HM.insertMatrix(0,0,m_ROT);
165  for (int i=0;i<3;i++) out_HM(i,3)=m_coords[i];
166  out_HM(3,0)=out_HM(3,1)=out_HM(3,2)=0.; out_HM(3,3)=1.;
167  }
168 
169  inline CMatrixDouble44 getHomogeneousMatrixVal() const { CMatrixDouble44 M; getHomogeneousMatrix(M); return M;}
170 
171  /** Get the 3x3 rotation matrix \sa getHomogeneousMatrix */
172  inline void getRotationMatrix( mrpt::math::CMatrixDouble33 & ROT ) const { ROT = m_ROT; }
173  //! \overload
174  inline const mrpt::math::CMatrixDouble33 & getRotationMatrix() const { return m_ROT; }
175 
176  /** Sets the 3x3 rotation matrix \sa getRotationMatrix, getHomogeneousMatrix */
177  inline void setRotationMatrix( const mrpt::math::CMatrixDouble33 & ROT ) { m_ROT = ROT; m_ypr_uptodate = false; }
178 
179  /** @} */ // end rot and HM
180 
181 
182  /** @name Pose-pose and pose-point compositions and operators
183  @{ */
184 
185  /** The operator \f$ a \oplus b \f$ is the pose compounding operator. */
186  inline CPose3D operator + (const CPose3D& b) const
187  {
189  ret.composeFrom(*this,b);
190  return ret;
191  }
192 
193  /** The operator \f$ a \oplus b \f$ is the pose compounding operator. */
194  CPoint3D operator + (const CPoint3D& b) const;
195 
196  /** The operator \f$ a \oplus b \f$ is the pose compounding operator. */
197  CPoint3D operator + (const CPoint2D& b) const;
198 
199  /** Computes the spherical coordinates of a 3D point as seen from the 6D pose specified by this object. For the coordinate system see the top of this page. */
200  void sphericalCoordinates(
201  const TPoint3D &point,
202  double &out_range,
203  double &out_yaw,
204  double &out_pitch ) const;
205 
206  /** An alternative, slightly more efficient way of doing \f$ G = P \oplus L \f$ with G and L being 3D points and P this 6D pose.
207  * If pointers are provided, the corresponding Jacobians are returned.
208  * "out_jacobian_df_dse3" stands for the Jacobian with respect to the 6D locally Euclidean vector in the tangent space of SE(3).
209  * See <a href="http://www.mrpt.org/6D_poses:equivalences_compositions_and_uncertainty" >this report</a> for mathematical details.
210  * \param If set to true, the Jacobian "out_jacobian_df_dpose" uses a fastest linearized appoximation (valid only for small rotations!).
211  */
212  void composePoint(double lx,double ly,double lz, double &gx, double &gy, double &gz,
213  mrpt::math::CMatrixFixedNumeric<double,3,3> *out_jacobian_df_dpoint=NULL,
214  mrpt::math::CMatrixFixedNumeric<double,3,6> *out_jacobian_df_dpose=NULL,
215  mrpt::math::CMatrixFixedNumeric<double,3,6> *out_jacobian_df_dse3=NULL,
216  bool use_small_rot_approx = false) const;
217 
218  /** An alternative, slightly more efficient way of doing \f$ G = P \oplus L \f$ with G and L being 3D points and P this 6D pose.
219  * \note local_point is passed by value to allow global and local point to be the same variable
220  */
221  inline void composePoint(const TPoint3D local_point, TPoint3D &global_point) const {
222  composePoint(local_point.x,local_point.y,local_point.z, global_point.x,global_point.y,global_point.z );
223  }
224  /** This version of the method assumes that the resulting point has no Z component (use with caution!) */
225  inline void composePoint(const TPoint3D local_point, TPoint2D &global_point) const {
226  double dummy_z;
227  composePoint(local_point.x,local_point.y,local_point.z, global_point.x,global_point.y,dummy_z );
228  }
229 
230  /** An alternative, slightly more efficient way of doing \f$ G = P \oplus L \f$ with G and L being 3D points and P this 6D pose. */
231  inline void composePoint(double lx,double ly,double lz, float &gx, float &gy, float &gz ) const {
232  double ggx, ggy,ggz;
233  composePoint(lx,ly,lz,ggx,ggy,ggz);
234  gx = ggx; gy = ggy; gz = ggz;
235  }
236 
237  /** Computes the 3D point L such as \f$ L = G \ominus this \f$.
238  * If pointers are provided, the corresponding Jacobians are returned.
239  * "out_jacobian_df_dse3" stands for the Jacobian with respect to the 6D locally Euclidean vector in the tangent space of SE(3).
240  * See <a href="http://www.mrpt.org/6D_poses:equivalences_compositions_and_uncertainty" >this report</a> for mathematical details.
241  * \sa composePoint, composeFrom
242  */
243  void inverseComposePoint(const double gx,const double gy,const double gz,double &lx,double &ly,double &lz,
244  mrpt::math::CMatrixFixedNumeric<double,3,3> *out_jacobian_df_dpoint=NULL,
245  mrpt::math::CMatrixFixedNumeric<double,3,6> *out_jacobian_df_dpose=NULL,
246  mrpt::math::CMatrixFixedNumeric<double,3,6> *out_jacobian_df_dse3=NULL ) const;
247 
248  /** \overload */
250  inverseComposePoint(g.x,g.y,g.z, l.x,l.y,l.z);
251  }
252 
253  /** \overload for 2D points \exception If the z component of the result is greater than some epsilon */
254  inline void inverseComposePoint(const mrpt::math::TPoint2D &g, mrpt::math::TPoint2D &l, const double eps=1e-6) const {
255  double lz;
256  inverseComposePoint(g.x,g.y,0, l.x,l.y,lz);
257  ASSERT_BELOW_(std::abs(lz),eps)
258  }
259 
260  /** Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids the temporary object.
261  * \note A or B can be "this" without problems.
262  */
263  void composeFrom(const CPose3D& A, const CPose3D& B );
264 
265  /** Make \f$ this = this \oplus b \f$ (\a b can be "this" without problems) */
266  inline CPose3D& operator += (const CPose3D& b)
267  {
268  composeFrom(*this,b);
269  return *this;
270  }
271 
272  /** Makes \f$ this = A \ominus B \f$ this method is slightly more efficient than "this= A - B;" since it avoids the temporary object.
273  * \note A or B can be "this" without problems.
274  * \sa composeFrom, composePoint
275  */
276  void inverseComposeFrom(const CPose3D& A, const CPose3D& B );
277 
278  /** Compute \f$ RET = this \oplus b \f$ */
279  inline CPose3D operator - (const CPose3D& b) const
280  {
282  ret.inverseComposeFrom(*this,b);
283  return ret;
284  }
285 
286  /** Convert this pose into its inverse, saving the result in itself. \sa operator- */
287  void inverse();
288 
289  /** makes: this = p (+) this */
290  inline void changeCoordinatesReference( const CPose3D & p ) { composeFrom(p,CPose3D(*this)); }
291 
292  /** @} */ // compositions
293 
294 
295  /** @name Access and modify contents
296  @{ */
297 
298  /** Scalar sum of all 6 components: This is diferent from poses composition, which is implemented as "+" operators.
299  * \sa normalizeAngles
300  */
301  void addComponents(const CPose3D &p);
302 
303  /** Rebuild the internal matrix & update the yaw/pitch/roll angles within the ]-PI,PI] range (Must be called after using addComponents)
304  * \sa addComponents
305  */
306  void normalizeAngles();
307 
308  /** Scalar multiplication of x,y,z,yaw,pitch & roll (angles will be wrapped to the ]-pi,pi] interval). */
309  void operator *=(const double s);
310 
311  /** Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes the internal rotation matrix.
312  * \sa getYawPitchRoll, setYawPitchRoll
313  */
314  void setFromValues(
315  const double x0,
316  const double y0,
317  const double z0,
318  const double yaw=0,
319  const double pitch=0,
320  const double roll=0);
321 
322  /** Set the pose from a 3D position (meters) and a quaternion, stored as [x y z qr qx qy qz] in a 7-element vector.
323  * \sa setFromValues, getYawPitchRoll, setYawPitchRoll, CQuaternion, getAsQuaternion
324  */
325  template <typename VECTORLIKE>
326  inline void setFromXYZQ(
327  const VECTORLIKE &v,
328  const size_t index_offset = 0)
329  {
330  ASSERT_ABOVEEQ_(v.size(), 7+index_offset)
331  // The 3x3 rotation part:
332  mrpt::math::CQuaternion<typename VECTORLIKE::value_type> q( v[index_offset+3],v[index_offset+4],v[index_offset+5],v[index_offset+6] );
333  q.rotationMatrixNoResize(m_ROT);
334  m_ypr_uptodate=false;
335  m_coords[0] = v[index_offset+0];
336  m_coords[1] = v[index_offset+1];
337  m_coords[2] = v[index_offset+2];
338  }
339 
340  /** Set the 3 angles of the 3D pose (in radians) - This method recomputes the internal rotation coordinates matrix.
341  * \sa getYawPitchRoll, setFromValues
342  */
343  inline void setYawPitchRoll(
344  const double yaw_,
345  const double pitch_,
346  const double roll_)
347  {
348  setFromValues(x(),y(),z(),yaw_,pitch_,roll_);
349  }
350 
351  /** Set pose from an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz]
352  * where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose
353  * \sa getAs12Vector
354  */
355  template <class ARRAYORVECTOR>
356  inline void setFrom12Vector(const ARRAYORVECTOR &vec12)
357  {
358  m_ROT.set_unsafe(0,0, vec12[0]); m_ROT.set_unsafe(0,1, vec12[3]); m_ROT.set_unsafe(0,2, vec12[6]);
359  m_ROT.set_unsafe(1,0, vec12[1]); m_ROT.set_unsafe(1,1, vec12[4]); m_ROT.set_unsafe(1,2, vec12[7]);
360  m_ROT.set_unsafe(2,0, vec12[2]); m_ROT.set_unsafe(2,1, vec12[5]); m_ROT.set_unsafe(2,2, vec12[8]);
361  m_ypr_uptodate = false;
362  m_coords[0] = vec12[ 9];
363  m_coords[1] = vec12[10];
364  m_coords[2] = vec12[11];
365  }
366 
367  /** Get the pose representation as an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz]
368  * where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose
369  * \sa setFrom12Vector
370  */
371  template <class ARRAYORVECTOR>
372  inline void getAs12Vector(ARRAYORVECTOR &vec12) const
373  {
374  vec12[0] = m_ROT.get_unsafe(0,0); vec12[3] = m_ROT.get_unsafe(0,1); vec12[6] = m_ROT.get_unsafe(0,2);
375  vec12[1] = m_ROT.get_unsafe(1,0); vec12[4] = m_ROT.get_unsafe(1,1); vec12[7] = m_ROT.get_unsafe(1,2);
376  vec12[2] = m_ROT.get_unsafe(2,0); vec12[5] = m_ROT.get_unsafe(2,1); vec12[8] = m_ROT.get_unsafe(2,2);
377  vec12[ 9] = m_coords[0];
378  vec12[10] = m_coords[1];
379  vec12[11] = m_coords[2];
380  }
381 
382  /** Returns the three angles (yaw, pitch, roll), in radians, from the rotation matrix.
383  * \sa setFromValues, yaw, pitch, roll
384  */
385  void getYawPitchRoll( double &yaw, double &pitch, double &roll ) const;
386 
387  inline double yaw() const { updateYawPitchRoll(); return m_yaw; } //!< Get the YAW angle (in radians) \sa setFromValues
388  inline double pitch() const { updateYawPitchRoll(); return m_pitch; } //!< Get the PITCH angle (in radians) \sa setFromValues
389  inline double roll() const { updateYawPitchRoll(); return m_roll; } //!< Get the ROLL angle (in radians) \sa setFromValues
390 
391  /** Returns a 1x6 vector with [x y z yaw pitch roll] */
392  void getAsVector(vector_double &v) const;
393  /// \overload
394  void getAsVector(mrpt::math::CArrayDouble<6> &v) const;
395 
396  /** Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored)
397  * \f[ \mathbf{q} = \left( \begin{array}{c} \cos (\phi /2) \cos (\theta /2) \cos (\psi /2) + \sin (\phi /2) \sin (\theta /2) \sin (\psi /2) \\ \sin (\phi /2) \cos (\theta /2) \cos (\psi /2) - \cos (\phi /2) \sin (\theta /2) \sin (\psi /2) \\ \cos (\phi /2) \sin (\theta /2) \cos (\psi /2) + \sin (\phi /2) \cos (\theta /2) \sin (\psi /2) \\ \cos (\phi /2) \cos (\theta /2) \sin (\psi /2) - \sin (\phi /2) \sin (\theta /2) \cos (\psi /2) \\ \end{array}\right) \f]
398  * With : \f$ \phi = roll \f$, \f$ \theta = pitch \f$ and \f$ \psi = yaw \f$.
399  * \param out_dq_dr If provided, the 4x3 Jacobian of the transformation will be computed and stored here. It's the Jacobian of the transformation from (yaw pitch roll) to (qr qx qy qz).
400  */
401  void getAsQuaternion(
404  ) const;
405 
406  inline const double &operator[](unsigned int i) const
407  {
408  updateYawPitchRoll();
409  switch(i)
410  {
411  case 0:return m_coords[0];
412  case 1:return m_coords[1];
413  case 2:return m_coords[2];
414  case 3:return m_yaw;
415  case 4:return m_pitch;
416  case 5:return m_roll;
417  default:
418  throw std::runtime_error("CPose3D::operator[]: Index of bounds.");
419  }
420  }
421  // CPose3D CANNOT have a write [] operator, since it'd leave the object in an inconsistent state (outdated rotation matrix).
422  // Use setFromValues() instead.
423  // inline double &operator[](unsigned int i)
424 
425  /** Returns a human-readable textual representation of the object (eg: "[x y z yaw pitch roll]", angles in degrees.)
426  * \sa fromString
427  */
428  void asString(std::string &s) const { updateYawPitchRoll(); s = mrpt::format("[%f %f %f %f %f %f]",m_coords[0],m_coords[1],m_coords[2],RAD2DEG(m_yaw),RAD2DEG(m_pitch),RAD2DEG(m_roll)); }
429  inline std::string asString() const { std::string s; asString(s); return s; }
430 
431  /** Set the current object value from a string generated by 'asString' (eg: "[x y z yaw pitch roll]", angles in deg. )
432  * \sa asString
433  * \exception std::exception On invalid format
434  */
435  void fromString(const std::string &s) {
436  CMatrixDouble m;
437  if (!m.fromMatlabStringFormat(s)) THROW_EXCEPTION("Malformed expression in ::fromString");
438  ASSERTMSG_(mrpt::math::size(m,1)==1 && mrpt::math::size(m,2)==6, "Wrong size of vector in ::fromString");
439  this->setFromValues(m.get_unsafe(0,0),m.get_unsafe(0,1),m.get_unsafe(0,2),DEG2RAD(m.get_unsafe(0,3)),DEG2RAD(m.get_unsafe(0,4)),DEG2RAD(m.get_unsafe(0,5)));
440  }
441 
442  /** Return true if the 6D pose represents a Z axis almost exactly vertical (upwards or downwards), with a given tolerance (if set to 0 exact horizontality is tested). */
443  bool isHorizontal( const double tolerance=0) const;
444 
445  /** The euclidean distance between two poses taken as two 6-length vectors (angles in radians). */
446  double distanceEuclidean6D( const CPose3D &o ) const;
447 
448  /** @} */ // modif. components
449 
450 
451 
452  /** @name Lie Algebra methods
453  @{ */
454 
455  /** Exponentiate a Vector in the SE(3) Lie Algebra to generate a new CPose3D (static method).
456  * \param pseudo_exponential If set to true, XYZ are copied from the first three elements in the vector instead of using the proper Lie Algebra formulas (this is actually the common practice in robotics literature).
457  * \note Method from TooN (C) Tom Drummond (GNU GPL) */
458  static CPose3D exp(const mrpt::math::CArrayNumeric<double,6> & vect, bool pseudo_exponential = false);
459 
460  /** \overload */
461  static void exp(const mrpt::math::CArrayNumeric<double,6> & vect, CPose3D &out_pose, bool pseudo_exponential = false);
462 
463  /** Exponentiate a vector in the Lie algebra to generate a new SO(3) (a 3x3 rotation matrix).
464  * \note Method from TooN (C) Tom Drummond (GNU GPL) */
465  static CMatrixDouble33 exp_rotation(const mrpt::math::CArrayNumeric<double,3> & vect);
466 
467 
468  /** Take the logarithm of the 3x4 matrix defined by this pose, generating the corresponding vector in the SE(3) Lie Algebra.
469  * \note Method from TooN (C) Tom Drummond (GNU GPL)
470  * \sa ln_jacob
471  */
472  void ln(mrpt::math::CArrayDouble<6> &out_ln) const;
473 
474  /// \overload
475  inline mrpt::math::CArrayDouble<6> ln() const { mrpt::math::CArrayDouble<6> ret; ln(ret); return ret; }
476 
477  /** Jacobian of the logarithm of the 3x4 matrix defined by this pose.
478  * \note Method from TooN (C) Tom Drummond (GNU GPL)
479  * \sa ln
480  */
481  void ln_jacob(mrpt::math::CMatrixFixedNumeric<double,6,12> &J) const;
482 
483  /** Static function to compute the Jacobian of the SO(3) Logarithm function, evaluated at a given 3x3 rotation matrix R.
484  * \sa ln, ln_jacob
485  */
486  static void ln_rot_jacob(const CMatrixDouble33 &R, CMatrixFixedNumeric<double,3,9> &M);
487 
488  /** Take the logarithm of the 3x3 rotation matrix, generating the corresponding vector in the Lie Algebra.
489  * \note Method from TooN (C) Tom Drummond (GNU GPL) */
490  CArrayDouble<3> ln_rotation() const;
491 
492  /** @} */
493 
494  typedef CPose3D type_value; //!< Used to emulate CPosePDF types, for example, in mrpt::graphs::CNetworkOfPoses
495  enum { is_3D_val = 1 };
496  static inline bool is_3D() { return is_3D_val!=0; }
497  enum { rotation_dimensions = 3 };
498  enum { is_PDF_val = 0 };
499  static inline bool is_PDF() { return is_PDF_val!=0; }
500 
501  inline const type_value & getPoseMean() const { return *this; }
502  inline type_value & getPoseMean() { return *this; }
503 
504  /** @name STL-like methods and typedefs
505  @{ */
506  typedef double value_type; //!< The type of the elements
507  typedef double& reference;
508  typedef const double& const_reference;
509  typedef std::size_t size_type;
510  typedef std::ptrdiff_t difference_type;
511 
512 
513  // size is constant
514  enum { static_size = 6 };
515  static inline size_type size() { return static_size; }
516  static inline bool empty() { return false; }
517  static inline size_type max_size() { return static_size; }
518  static inline void resize(const size_t n) { if (n!=static_size) throw std::logic_error(format("Try to change the size of CPose3D to %u.",static_cast<unsigned>(n))); }
519  /** @} */
520 
521  }; // End of class def.
522 
523 
524  std::ostream BASE_IMPEXP & operator << (std::ostream& o, const CPose3D& p);
525 
526  /** Unary - operator: return the inverse pose "-p" (Note that is NOT the same than a pose with negative x y z yaw pitch roll) */
527  CPose3D BASE_IMPEXP operator -(const CPose3D &p);
528 
529  bool BASE_IMPEXP operator==(const CPose3D &p1,const CPose3D &p2);
530  bool BASE_IMPEXP operator!=(const CPose3D &p1,const CPose3D &p2);
531 
532 
533  // This is a member of CPose<>, but has to be defined here since in its header CPose3D is not declared yet.
534  /** The operator \f$ a \ominus b \f$ is the pose inverse compounding operator. */
535  template <class DERIVEDCLASS> CPose3D CPose<DERIVEDCLASS>::operator -(const CPose3D& b) const
536  {
538  b.getInverseHomogeneousMatrix( B_INV );
540  static_cast<const DERIVEDCLASS*>(this)->getHomogeneousMatrix(HM);
542  RES.multiply(B_INV,HM);
543  return CPose3D( RES );
544  }
545 
546 
547  } // End of namespace
548 } // End of namespace
549 
550 #endif
#define ASSERT_EQUAL_(__A, __B)
double y
Y coordinate.
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...
std::size_t size_type
Definition: CPose3D.h:509
double x
X coordinate.
const type_value & getPoseMean() const
Definition: CPose3D.h:501
CArrayDouble< 3 > m_coords
The translation vector [x,y,z] access directly or with x(), y(), z() setter/getter methods...
Definition: CPose3D.h:77
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 setFromXYZQ(const VECTORLIKE &v, const size_t index_offset=0)
Set the pose from a 3D position (meters) and a quaternion, stored as [x y z qr qx qy qz] in a 7-eleme...
Definition: CPose3D.h:326
#define DEFINE_SERIALIZABLE_PRE(class_name)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
bool m_ypr_uptodate
Whether yaw/pitch/roll members are up-to-date since the last rotation matrix update.
Definition: CPose3D.h:81
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
#define THROW_EXCEPTION(msg)
#define ASSERT_BELOW_(__A, __B)
void setYawPitchRoll(const double yaw_, const double pitch_, const double roll_)
Set the 3 angles of the 3D pose (in radians) - This method recomputes the internal rotation coordinat...
Definition: CPose3D.h:343
CArrayNumeric is an array for numeric types supporting several mathematical operations (actually...
Definition: CArray.h:305
size_t size(const MATRIXLIKE &m, int dim)
double pitch() const
Get the PITCH angle (in radians)
Definition: CPose3D.h:388
double yaw() const
Get the YAW angle (in radians)
Definition: CPose3D.h:387
void getInverseHomogeneousMatrix(math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 inverse homogeneous transformation matrix for this point or pose...
Definition: CPoseOrPoint.h:200
double z
Z coordinate.
void updateYawPitchRoll() const
Updates Yaw/pitch/roll members from the m_ROT.
Definition: CPose3D.h:88
void setRotationMatrix(const mrpt::math::CMatrixDouble33 &ROT)
Sets the 3x3 rotation matrix.
Definition: CPose3D.h:177
static bool is_PDF()
Definition: CPose3D.h:499
std::ptrdiff_t difference_type
Definition: CPose3D.h:510
const double & const_reference
Definition: CPose3D.h:508
double value_type
The type of the elements.
Definition: CPose3D.h:506
void fromString(const std::string &s)
Set the current object value from a string generated by &#39;asString&#39; (eg: "[x y z yaw pitch roll]"...
Definition: CPose3D.h:435
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
Definition: CArray.h:19
type_value & getPoseMean()
Definition: CPose3D.h:502
CMatrixDouble33 m_ROT
The 3x3 rotation matrix, access with getRotationMatrix(), setRotationMatrix() (It&#39;s not safe to set t...
Definition: CPose3D.h:79
class BASE_IMPEXP CSerializable
Definition: CStream.h:21
bool operator!=(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
Definition: CPoint.h:137
void composePoint(const TPoint3D local_point, TPoint2D &global_point) const
This version of the method assumes that the resulting point has no Z component (use with caution!) ...
Definition: CPose3D.h:225
std::vector< T1 > & operator+=(std::vector< T1 > &a, const std::vector< T2 > &b)
a+=b (element-wise sum)
Definition: ops_vectors.h:64
mrpt::math::TPoint2D BASE_IMPEXP operator+(const CPose2D &pose, const mrpt::math::TPoint2D &pnt)
Compose a 2D point from a new coordinate base given by a 2D pose.
static void resize(const size_t n)
Definition: CPose3D.h:518
void changeCoordinatesReference(const CPose3D &p)
makes: this = p (+) this
Definition: CPose3D.h:290
A base class for representing a pose in 2D or 3D.
Definition: CPose.h:25
CPose3D type_value
Used to emulate CPosePDF types, for example, in mrpt::graphs::CNetworkOfPoses.
Definition: CPose3D.h:494
Eigen::Matrix< dataType, 4, 4 > inverse(Eigen::Matrix< dataType, 4, 4 > &pose)
Definition: Miscellaneous.h:71
double x
X coordinate.
void inverseComposePoint(const mrpt::math::TPoint3D &g, mrpt::math::TPoint3D &l) const
Definition: CPose3D.h:249
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
Definition: CPose3DQuat.h:44
CPose3D(const CMatrixDouble33 &rot, const CArrayDouble< 3 > &xyz)
Definition: CPose3D.h:117
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
A class used to store a 2D point.
Definition: CPoint2D.h:35
T abs(T x)
Definition: nanoflann.hpp:214
A class used to store a 3D point.
Definition: CPoint3D.h:33
double roll() const
Get the ROLL angle (in radians)
Definition: CPose3D.h:389
void setFrom12Vector(const ARRAYORVECTOR &vec12)
Set pose from an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz] where r...
Definition: CPose3D.h:356
void composePoint(double lx, double ly, double lz, float &gx, float &gy, float &gz) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
Definition: CPose3D.h:231
void asString(std::string &s) const
Returns a human-readable textual representation of the object (eg: "[x y z yaw pitch roll]"...
Definition: CPose3D.h:428
void inverseComposePoint(const mrpt::math::TPoint2D &g, mrpt::math::TPoint2D &l, const double eps=1e-6) const
Definition: CPose3D.h:254
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
#define ASSERT_ABOVEEQ_(__A, __B)
void getHomogeneousMatrix(CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
Definition: CPose3D.h:162
CPose3D(TConstructorFlags_Poses constructor_dummy_param)
Fast constructor that leaves all the data uninitialized - call with UNINITIALIZED_POSE as argument...
Definition: CPose3D.h:142
bool operator==(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
Definition: CPoint.h:129
A class used to store a 2D pose.
Definition: CPose2D.h:35
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:71
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...
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
CPose3D(const MATRIX33 &rot, const VECTOR3 &xyz)
Constructor from a 3x3 rotation matrix and a the translation given as a 3-vector, a 3-array...
Definition: CPose3D.h:108
CMatrixDouble44 getHomogeneousMatrixVal() const
Definition: CPose3D.h:169
static bool is_3D()
Definition: CPose3D.h:496
const mrpt::math::CMatrixDouble33 & getRotationMatrix() const
Definition: CPose3D.h:174
double y
Y coordinate.
double & reference
Definition: CPose3D.h:507
mrpt::math::CArrayDouble< 6 > ln() const
Definition: CPose3D.h:475
A 3D pose, with a 3D translation and a rotation in 3D parameterized in rotation-vector form (equivale...
Definition: CPose3DRotVec.h:45
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...
Definition: CQuaternion.h:42
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
Definition: CPose3D.h:172
Lightweight 3D point.
Lightweight 2D point.
static bool empty()
Definition: CPose3D.h:516
void getAs12Vector(ARRAYORVECTOR &vec12) const
Get the pose representation as an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 ...
Definition: CPose3D.h:372
#define ASSERTMSG_(f, __ERROR_MSG)
CPose3D operator-(const CPose3D &b) const
The operator is the pose inverse compounding operator.
Definition: CPose3D.h:535
static size_type max_size()
Definition: CPose3D.h:517
std::vector< T1 > & operator*=(std::vector< T1 > &a, const std::vector< T2 > &b)
a*=b (element-wise multiplication)
Definition: ops_vectors.h:34
CPose3D(const CArrayDouble< 12 > &vec12)
Constructor from an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz] wher...
Definition: CPose3D.h:148
void composePoint(const TPoint3D local_point, TPoint3D &global_point) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
Definition: CPose3D.h:221
std::string asString() const
Definition: CPose3D.h:429
const double & operator[](unsigned int i) const
Definition: CPose3D.h:406
std::ostream & operator<<(std::ostream &o, const CPoint< DERIVEDCLASS > &p)
Dumps a point as a string [x,y] or [x,y,z].
Definition: CPoint.h:105
static size_type size()
Definition: CPose3D.h:515



Page generated by Doxygen 1.8.14 for MRPT 1.1.0 SVN: at lun oct 28 00:54:49 CET 2019 Hosted on:
SourceForge.net Logo