MRPT  1.9.9
CQuaternion.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-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 #pragma once
11 
14 #include <mrpt/core/exceptions.h>
15 #include <mrpt/core/bits_math.h> // square()
16 
17 namespace mrpt::math
18 {
19 // For use with a constructor of CQuaternion
21 {
23 };
24 
25 /** A quaternion, which can represent a 3D rotation as pair \f$ (r,\mathbf{u})
26  *\f$, with a real part "r" and a 3D vector \f$ \mathbf{u} = (x,y,z) \f$, or
27  *alternatively, q = r + ix + jy + kz.
28  *
29  * The elements of the quaternion can be accessed by either:
30  * - r(), x(), y(), z(), or
31  * - the operator [] with indices running from 0 (=r) to 3 (=z).
32  *
33  * Users will usually employ the type `CQuaternionDouble` instead of this
34  *template.
35  *
36  * For more information about quaternions, see:
37  * - http://people.csail.mit.edu/bkph/articles/Quaternions.pdf
38  * - http://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation
39  *
40  * \ingroup mrpt_math_grp
41  * \sa mrpt::poses::CPose3D
42  */
43 template <class T>
44 class CQuaternion : public CArrayNumeric<T, 4>
45 {
47 
48  public:
49  /* @{ Constructors
50  */
51 
52  /** Can be used with UNINITIALIZED_QUATERNION as argument, does not
53  * initialize the 4 elements of the quaternion (use this constructor when
54  * speed is critical). */
56  /** Default constructor: construct a (1, (0,0,0) ) quaternion representing
57  * no rotation. */
58  inline CQuaternion()
59  {
60  (*this)[0] = 1;
61  (*this)[1] = 0;
62  (*this)[2] = 0;
63  (*this)[3] = 0;
64  }
65 
66  /** Construct a quaternion from its parameters 'r', 'x', 'y', 'z', with q =
67  * r + ix + jy + kz. */
68  inline CQuaternion(const T r, const T x, const T y, const T z)
69  {
70  (*this)[0] = r;
71  (*this)[1] = x;
72  (*this)[2] = y;
73  (*this)[3] = z;
74  ASSERTMSG_(
75  std::abs(normSqr() - 1.0) < 1e-3,
77  "Initialization data for quaternion is not normalized: %f %f "
78  "%f %f -> sqrNorm=%f",
79  r, x, y, z, normSqr()));
80  }
81 
82  /* @}
83  */
84 
85  /** Return r coordinate of the quaternion */
86  inline T r() const { return (*this)[0]; }
87  /** Return x coordinate of the quaternion */
88  inline T x() const { return (*this)[1]; }
89  /** Return y coordinate of the quaternion */
90  inline T y() const { return (*this)[2]; }
91  /** Return z coordinate of the quaternion */
92  inline T z() const { return (*this)[3]; }
93  /** Set r coordinate of the quaternion */
94  inline void r(const T r) { (*this)[0] = r; }
95  /** Set x coordinate of the quaternion */
96  inline void x(const T x) { (*this)[1] = x; }
97  /** Set y coordinate of the quaternion */
98  inline void y(const T y) { (*this)[2] = y; }
99  /** Set z coordinate of the quaternion */
100  inline void z(const T z) { (*this)[3] = z; }
101  /** Set this quaternion to the rotation described by a 3D (Rodrigues)
102  * rotation vector \f$ \mathbf{v} \f$:
103  * If \f$ \mathbf{v}=0 \f$, then the quaternion is \f$ \mathbf{q} = [1 ~
104  * 0 ~ 0 ~ 0]^\top \f$, otherwise:
105  * \f[ \mathbf{q} = \left[ \begin{array}{c}
106  * \cos(\frac{\theta}{2}) \\
107  * v_x \frac{\sin(\frac{\theta}{2})}{\theta} \\
108  * v_y \frac{\sin(\frac{\theta}{2})}{\theta} \\
109  * v_z \frac{\sin(\frac{\theta}{2})}{\theta}
110  * \end{array} \right] \f]
111  * where \f$ \theta = |\mathbf{v}| = \sqrt{v_x^2+v_y^2+v_z^2} \f$.
112  * \sa "Representing Attitude: Euler Angles, Unit Quaternions, and
113  * Rotation Vectors (2006)", James Diebel.
114  */
115  template <class ARRAYLIKE3>
116  void fromRodriguesVector(const ARRAYLIKE3& v)
117  {
118  if (v.size() != 3) THROW_EXCEPTION("Vector v must have a length=3");
119 
120  const T x = v[0];
121  const T y = v[1];
122  const T z = v[2];
123  const T angle = std::sqrt(x * x + y * y + z * z);
124  if (angle < 1e-7)
125  {
126  (*this)[0] = 1;
127  (*this)[1] = static_cast<T>(0.5) * x;
128  (*this)[2] = static_cast<T>(0.5) * y;
129  (*this)[3] = static_cast<T>(0.5) * z;
130  }
131  else
132  {
133  const T s = (::sin(angle / 2)) / angle;
134  const T c = ::cos(angle / 2);
135  (*this)[0] = c;
136  (*this)[1] = x * s;
137  (*this)[2] = y * s;
138  (*this)[3] = z * s;
139  }
140  }
141 
142  /** @name Lie Algebra methods
143  @{ */
144 
145  /** Logarithm of the 3x3 matrix defined by this pose, generating the
146  * corresponding vector in the SO(3) Lie Algebra,
147  * which coincides with the so-called "rotation vector" (I don't have
148  * space here for the proof ;-).
149  * \param[out] out_ln The target vector, which can be: std::vector<>, or
150  * mrpt::math::CVectorDouble or any row or column Eigen::Matrix<>.
151  * \sa exp, mrpt::poses::SE_traits */
152  template <class ARRAYLIKE3>
153  inline void ln(ARRAYLIKE3& out_ln) const
154  {
155  if (out_ln.size() != 3) out_ln.resize(3);
156  this->ln_noresize(out_ln);
157  }
158  /** overload that returns by value */
159  template <class ARRAYLIKE3>
160  inline ARRAYLIKE3 ln() const
161  {
162  ARRAYLIKE3 out_ln;
163  this->ln(out_ln);
164  return out_ln;
165  }
166  /** Like ln() but does not try to resize the output vector. */
167  template <class ARRAYLIKE3>
168  void ln_noresize(ARRAYLIKE3& out_ln) const
169  {
170  using mrpt::square;
171  const T xyz_norm = std::sqrt(square(x()) + square(y()) + square(z()));
172  const T K = (xyz_norm < 1e-7) ? 2 : 2 * ::acos(r()) / xyz_norm;
173  out_ln[0] = K * x();
174  out_ln[1] = K * y();
175  out_ln[2] = K * z();
176  }
177 
178  /** Exponential map from the SO(3) Lie Algebra to unit quaternions.
179  * \sa ln, mrpt::poses::SE_traits */
180  template <class ARRAYLIKE3>
181  inline static CQuaternion<T> exp(const ARRAYLIKE3& v)
182  {
184  q.fromRodriguesVector(v);
185  return q;
186  }
187  /** \overload */
188  template <class ARRAYLIKE3>
189  inline static void exp(const ARRAYLIKE3& v, CQuaternion<T>& out_quat)
190  {
191  out_quat.fromRodriguesVector(v);
192  }
193 
194  /** @} */ // end of Lie algebra
195 
196  /** Calculate the "cross" product (or "composed rotation") of two
197  * quaternion: this = q1 x q2
198  * After the operation, "this" will represent the composed rotations of
199  * q1 and q2 (q2 applied "after" q1).
200  */
201  inline void crossProduct(const CQuaternion& q1, const CQuaternion& q2)
202  {
203  // First: compute result, then save in this object. In this way we avoid
204  // problems when q1 or q2 == *this !!
205  const T new_r = q1.r() * q2.r() - q1.x() * q2.x() - q1.y() * q2.y() -
206  q1.z() * q2.z();
207  const T new_x = q1.r() * q2.x() + q2.r() * q1.x() + q1.y() * q2.z() -
208  q2.y() * q1.z();
209  const T new_y = q1.r() * q2.y() + q2.r() * q1.y() + q1.z() * q2.x() -
210  q2.z() * q1.x();
211  const T new_z = q1.r() * q2.z() + q2.r() * q1.z() + q1.x() * q2.y() -
212  q2.x() * q1.y();
213  this->r(new_r);
214  this->x(new_x);
215  this->y(new_y);
216  this->z(new_z);
217  this->normalize();
218  }
219 
220  /** Rotate a 3D point (lx,ly,lz) -> (gx,gy,gz) as described by this
221  * quaternion
222  */
223  void rotatePoint(
224  const double lx, const double ly, const double lz, double& gx,
225  double& gy, double& gz) const
226  {
227  const double t2 = r() * x();
228  const double t3 = r() * y();
229  const double t4 = r() * z();
230  const double t5 = -x() * x();
231  const double t6 = x() * y();
232  const double t7 = x() * z();
233  const double t8 = -y() * y();
234  const double t9 = y() * z();
235  const double t10 = -z() * z();
236  gx = 2 * ((t8 + t10) * lx + (t6 - t4) * ly + (t3 + t7) * lz) + lx;
237  gy = 2 * ((t4 + t6) * lx + (t5 + t10) * ly + (t9 - t2) * lz) + ly;
238  gz = 2 * ((t7 - t3) * lx + (t2 + t9) * ly + (t5 + t8) * lz) + lz;
239  }
240 
241  /** Rotate a 3D point (lx,ly,lz) -> (gx,gy,gz) as described by the inverse
242  * (conjugate) of this quaternion
243  */
244  void inverseRotatePoint(
245  const double lx, const double ly, const double lz, double& gx,
246  double& gy, double& gz) const
247  {
248  const double t2 = -r() * x();
249  const double t3 = -r() * y();
250  const double t4 = -r() * z();
251  const double t5 = -x() * x();
252  const double t6 = x() * y();
253  const double t7 = x() * z();
254  const double t8 = -y() * y();
255  const double t9 = y() * z();
256  const double t10 = -z() * z();
257  gx = 2 * ((t8 + t10) * lx + (t6 - t4) * ly + (t3 + t7) * lz) + lx;
258  gy = 2 * ((t4 + t6) * lx + (t5 + t10) * ly + (t9 - t2) * lz) + ly;
259  gz = 2 * ((t7 - t3) * lx + (t2 + t9) * ly + (t5 + t8) * lz) + lz;
260  }
261 
262  /** Return the squared norm of the quaternion */
263  inline double normSqr() const
264  {
265  using mrpt::square;
266  return square(r()) + square(x()) + square(y()) + square(z());
267  }
268 
269  /** Normalize this quaternion, so its norm becomes the unitity.
270  */
271  inline void normalize()
272  {
273  const T qq = 1.0 / std::sqrt(normSqr());
274  for (unsigned int i = 0; i < 4; i++) (*this)[i] *= qq;
275  }
276 
277  /** Calculate the 4x4 Jacobian of the normalization operation of this
278  * quaternion.
279  * The output matrix can be a dynamic or fixed size (4x4) matrix.
280  */
281  template <class MATRIXLIKE>
282  void normalizationJacobian(MATRIXLIKE& J) const
283  {
284  const T n = 1.0 / std::pow(normSqr(), T(1.5));
285  J.setSize(4, 4);
286  J.get_unsafe(0, 0) = x() * x() + y() * y() + z() * z();
287  J.get_unsafe(0, 1) = -r() * x();
288  J.get_unsafe(0, 2) = -r() * y();
289  J.get_unsafe(0, 3) = -r() * z();
290 
291  J.get_unsafe(1, 0) = -x() * r();
292  J.get_unsafe(1, 1) = r() * r() + y() * y() + z() * z();
293  J.get_unsafe(1, 2) = -x() * y();
294  J.get_unsafe(1, 3) = -x() * z();
295 
296  J.get_unsafe(2, 0) = -y() * r();
297  J.get_unsafe(2, 1) = -y() * x();
298  J.get_unsafe(2, 2) = r() * r() + x() * x() + z() * z();
299  J.get_unsafe(2, 3) = -y() * z();
300 
301  J.get_unsafe(3, 0) = -z() * r();
302  J.get_unsafe(3, 1) = -z() * x();
303  J.get_unsafe(3, 2) = -z() * y();
304  J.get_unsafe(3, 3) = r() * r() + x() * x() + y() * y();
305  J *= n;
306  }
307 
308  /** Compute the Jacobian of the rotation composition operation \f$ p =
309  * f(\cdot) = q_{this} \times r \f$, that is the 4x4 matrix \f$
310  * \frac{\partial f}{\partial q_{this} } \f$.
311  * The output matrix can be a dynamic or fixed size (4x4) matrix.
312  */
313  template <class MATRIXLIKE>
314  inline void rotationJacobian(MATRIXLIKE& J) const
315  {
316  J.setSize(4, 4);
317  J.get_unsafe(0, 0) = r();
318  J.get_unsafe(0, 1) = -x();
319  J.get_unsafe(0, 2) = -y();
320  J.get_unsafe(0, 3) = -z();
321  J.get_unsafe(1, 0) = x();
322  J.get_unsafe(1, 1) = r();
323  J.get_unsafe(1, 2) = -z();
324  J.get_unsafe(1, 3) = y();
325  J.get_unsafe(2, 0) = y();
326  J.get_unsafe(2, 1) = z();
327  J.get_unsafe(2, 2) = r();
328  J.get_unsafe(2, 3) = -x();
329  J.get_unsafe(3, 0) = z();
330  J.get_unsafe(3, 1) = -y();
331  J.get_unsafe(3, 2) = x();
332  J.get_unsafe(3, 3) = r();
333  }
334 
335  /** Calculate the 3x3 rotation matrix associated to this quaternion: \f[
336  * \mathbf{R} = \left(
337  * \begin{array}{ccc}
338  * q_r^2+q_x^2-q_y^2-q_z^2 & 2(q_x q_y - q_r q_z) & 2(q_z
339  * q_x+q_r q_y) \\
340  * 2(q_x q_y+q_r q_z) & q_r^2-q_x^2+q_y^2-q_z^2 & 2(q_y
341  * q_z-q_r q_x) \\
342  * 2(q_z q_x-q_r q_y) & 2(q_y q_z+q_r q_x) & q_r^2- q_x^2 - q_y^2 +
343  * q_z^2
344  * \end{array}
345  * \right)\f]
346  *
347  */
348  template <class MATRIXLIKE>
349  inline void rotationMatrix(MATRIXLIKE& M) const
350  {
351  M.setSize(3, 3);
353  }
354 
355  /** Fill out the top-left 3x3 block of the given matrix with the rotation
356  * matrix associated to this quaternion (does not resize the matrix, for
357  * that, see rotationMatrix). */
358  template <class MATRIXLIKE>
359  inline void rotationMatrixNoResize(MATRIXLIKE& M) const
360  {
361  M.get_unsafe(0, 0) = r() * r() + x() * x() - y() * y() - z() * z();
362  M.get_unsafe(0, 1) = 2 * (x() * y() - r() * z());
363  M.get_unsafe(0, 2) = 2 * (z() * x() + r() * y());
364  M.get_unsafe(1, 0) = 2 * (x() * y() + r() * z());
365  M.get_unsafe(1, 1) = r() * r() - x() * x() + y() * y() - z() * z();
366  M.get_unsafe(1, 2) = 2 * (y() * z() - r() * x());
367  M.get_unsafe(2, 0) = 2 * (z() * x() - r() * y());
368  M.get_unsafe(2, 1) = 2 * (y() * z() + r() * x());
369  M.get_unsafe(2, 2) = r() * r() - x() * x() - y() * y() + z() * z();
370  }
371 
372  /** Return the conjugate quaternion */
373  inline void conj(CQuaternion& q_out) const
374  {
375  q_out.r(r());
376  q_out.x(-x());
377  q_out.y(-y());
378  q_out.z(-z());
379  }
380 
381  /** Return the conjugate quaternion */
382  inline CQuaternion conj() const
383  {
384  CQuaternion q_aux;
385  conj(q_aux);
386  return q_aux;
387  }
388 
389  /** Return the yaw, pitch & roll angles associated to quaternion
390  * \sa For the equations, see The MRPT Book, or see
391  * http://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToEuler/Quaternions.pdf
392  * \sa rpy_and_jacobian
393  */
394  inline void rpy(T& roll, T& pitch, T& yaw) const
395  {
397  roll, pitch, yaw, static_cast<mrpt::math::CMatrixDouble*>(nullptr));
398  }
399 
400  /** Return the yaw, pitch & roll angles associated to quaternion, and
401  * (optionally) the 3x4 Jacobian of the transformation.
402  * Note that both the angles and the Jacobian have one set of normal
403  * equations, plus other special formulas for the degenerated cases of
404  * |pitch|=90 degrees.
405  * \sa For the equations, see The MRPT Book, or
406  * http://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToEuler/Quaternions.pdf
407  * \sa rpy
408  */
409  template <class MATRIXLIKE>
410  void rpy_and_jacobian(
411  T& roll, T& pitch, T& yaw, MATRIXLIKE* out_dr_dq = nullptr,
412  bool resize_out_dr_dq_to3x4 = true) const
413  {
414  using mrpt::square;
415  using std::sqrt;
416 
417  if (out_dr_dq && resize_out_dr_dq_to3x4) out_dr_dq->setSize(3, 4);
418  const T discr = r() * y() - x() * z();
419  if (fabs(discr) > 0.49999)
420  { // pitch = 90 deg
421  pitch = 0.5 * M_PI;
422  yaw = -2 * atan2(x(), r());
423  roll = 0;
424  if (out_dr_dq)
425  {
426  out_dr_dq->zeros();
427  out_dr_dq->get_unsafe(0, 0) = +2 / x();
428  out_dr_dq->get_unsafe(0, 2) = -2 * r() / (x() * x());
429  }
430  }
431  else if (discr < -0.49999)
432  { // pitch =-90 deg
433  pitch = -0.5 * M_PI;
434  yaw = 2 * atan2(x(), r());
435  roll = 0;
436  if (out_dr_dq)
437  {
438  out_dr_dq->zeros();
439  out_dr_dq->get_unsafe(0, 0) = -2 / x();
440  out_dr_dq->get_unsafe(0, 2) = +2 * r() / (x() * x());
441  }
442  }
443  else
444  { // Non-degenerate case:
445  yaw = ::atan2(
446  2 * (r() * z() + x() * y()), 1 - 2 * (y() * y() + z() * z()));
447  pitch = ::asin(2 * discr);
448  roll = ::atan2(
449  2 * (r() * x() + y() * z()), 1 - 2 * (x() * x() + y() * y()));
450  if (out_dr_dq)
451  {
452  // Auxiliary terms:
453  const double val1 = (2 * x() * x() + 2 * y() * y() - 1);
454  const double val12 = square(val1);
455  const double val2 = (2 * r() * x() + 2 * y() * z());
456  const double val22 = square(val2);
457  const double xy2 = 2 * x() * y();
458  const double rz2 = 2 * r() * z();
459  const double ry2 = 2 * r() * y();
460  const double val3 = (2 * y() * y() + 2 * z() * z() - 1);
461  const double val4 =
462  ((square(rz2 + xy2) / square(val3) + 1) * val3);
463  const double val5 = (4 * (rz2 + xy2)) / square(val3);
464  const double val6 =
465  1.0 / (square(rz2 + xy2) / square(val3) + 1);
466  const double val7 = 2.0 / sqrt(1 - square(ry2 - 2 * x() * z()));
467  const double val8 = (val22 / val12 + 1);
468  const double val9 = -2.0 / val8;
469  // row 1:
470  out_dr_dq->get_unsafe(0, 0) = -2 * z() / val4;
471  out_dr_dq->get_unsafe(0, 1) = -2 * y() / val4;
472  out_dr_dq->get_unsafe(0, 2) =
473  -(2 * x() / val3 - y() * val5) * val6;
474  out_dr_dq->get_unsafe(0, 3) =
475  -(2 * r() / val3 - z() * val5) * val6;
476  // row 2:
477  out_dr_dq->get_unsafe(1, 0) = y() * val7;
478  out_dr_dq->get_unsafe(1, 1) = -z() * val7;
479  out_dr_dq->get_unsafe(1, 2) = r() * val7;
480  out_dr_dq->get_unsafe(1, 3) = -x() * val7;
481  // row 3:
482  out_dr_dq->get_unsafe(2, 0) = val9 * x() / val1;
483  out_dr_dq->get_unsafe(2, 1) =
484  val9 * (r() / val1 - (2 * x() * val2) / val12);
485  out_dr_dq->get_unsafe(2, 2) =
486  val9 * (z() / val1 - (2 * y() * val2) / val12);
487  out_dr_dq->get_unsafe(2, 3) = val9 * y() / val1;
488  }
489  }
490  }
492  inline CQuaternion operator*(const T& factor)
493  {
494  CQuaternion q = *this;
495  q *= factor;
496  return q;
497  }
498 
499 }; // end class
500 
501 /** A quaternion of data type "double" */
503 /** A quaternion of data type "float" */
505 
506 }
507 
void rpy_and_jacobian(T &roll, T &pitch, T &yaw, MATRIXLIKE *out_dr_dq=nullptr, bool resize_out_dr_dq_to3x4=true) const
Return the yaw, pitch & roll angles associated to quaternion, and (optionally) the 3x4 Jacobian of th...
Definition: CQuaternion.h:409
void inverseRotatePoint(const double lx, const double ly, const double lz, double &gx, double &gy, double &gz) const
Rotate a 3D point (lx,ly,lz) -> (gx,gy,gz) as described by the inverse (conjugate) of this quaternion...
Definition: CQuaternion.h:243
static CQuaternion< T > exp(const ARRAYLIKE3 &v)
Exponential map from the SO(3) Lie Algebra to unit quaternions.
Definition: CQuaternion.h:180
void rotationMatrix(MATRIXLIKE &M) const
Calculate the 3x3 rotation matrix associated to this quaternion: .
Definition: CQuaternion.h:348
void normalize()
Normalize this quaternion, so its norm becomes the unitity.
Definition: CQuaternion.h:270
GLdouble GLdouble z
Definition: glext.h:3872
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:41
TConstructorFlags_Quaternions
Definition: CQuaternion.h:20
T y() const
Return y coordinate of the quaternion.
Definition: CQuaternion.h:89
GLdouble GLdouble GLdouble GLdouble q
Definition: glext.h:3721
GLenum GLsizei n
Definition: glext.h:5074
void rotationMatrixNoResize(MATRIXLIKE &M) const
Fill out the top-left 3x3 block of the given matrix with the rotation matrix associated to this quate...
Definition: CQuaternion.h:358
CArrayNumeric is an array for numeric types supporting several mathematical operations (actually...
Definition: CArrayNumeric.h:25
GLdouble s
Definition: glext.h:3676
T square(const T x)
Inline function for the square of a number.
double normSqr() const
Return the squared norm of the quaternion.
Definition: CQuaternion.h:262
This base provides a set of functions for maths stuff.
T r() const
Return r coordinate of the quaternion.
Definition: CQuaternion.h:85
CQuaternion operator*(const T &factor)
Definition: CQuaternion.h:491
void crossProduct(const CQuaternion &q1, const CQuaternion &q2)
Calculate the "cross" product (or "composed rotation") of two quaternion: this = q1 x q2 After the op...
Definition: CQuaternion.h:200
const GLubyte * c
Definition: glext.h:6313
void rotationJacobian(MATRIXLIKE &J) const
Compute the Jacobian of the rotation composition operation , that is the 4x4 matrix ...
Definition: CQuaternion.h:313
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
Definition: exceptions.h:101
void rotatePoint(const double lx, const double ly, const double lz, double &gx, double &gy, double &gz) const
Rotate a 3D point (lx,ly,lz) -> (gx,gy,gz) as described by this quaternion.
Definition: CQuaternion.h:222
void ln_noresize(ARRAYLIKE3 &out_ln) const
Like ln() but does not try to resize the output vector.
Definition: CQuaternion.h:167
ARRAYLIKE3 ln() const
overload that returns by value
Definition: CQuaternion.h:159
const GLdouble * v
Definition: glext.h:3678
T x() const
Return x coordinate of the quaternion.
Definition: CQuaternion.h:87
GLdouble GLdouble GLdouble r
Definition: glext.h:3705
void normalizationJacobian(MATRIXLIKE &J) const
Calculate the 4x4 Jacobian of the normalization operation of this quaternion.
Definition: CQuaternion.h:281
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
CQuaternion(const T r, const T x, const T y, const T z)
Construct a quaternion from its parameters &#39;r&#39;, &#39;x&#39;, &#39;y&#39;, &#39;z&#39;, with q = r + ix + jy + kz...
Definition: CQuaternion.h:68
GLenum GLint GLint y
Definition: glext.h:3538
GLenum GLint x
Definition: glext.h:3538
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...
Definition: CQuaternion.h:44
T z() const
Return z coordinate of the quaternion.
Definition: CQuaternion.h:91
void rpy(T &roll, T &pitch, T &yaw) const
Return the yaw, pitch & roll angles associated to quaternion.
Definition: CQuaternion.h:393
CQuaternion conj() const
Return the conjugate quaternion.
Definition: CQuaternion.h:381
CQuaternion()
Default constructor: construct a (1, (0,0,0) ) quaternion representing no rotation.
Definition: CQuaternion.h:58
CQuaternion(TConstructorFlags_Quaternions)
Can be used with UNINITIALIZED_QUATERNION as argument, does not initialize the 4 elements of the quat...
Definition: CQuaternion.h:55
void fromRodriguesVector(const ARRAYLIKE3 &v)
Set this quaternion to the rotation described by a 3D (Rodrigues) rotation vector : If ...
Definition: CQuaternion.h:115



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020