MRPT  1.9.9
CQuaternion.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #pragma once
11 
12 #include <mrpt/core/bits_math.h> // square()
13 #include <mrpt/core/exceptions.h>
15 #include <mrpt/math/CVectorFixed.h>
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 CVectorFixed<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  MRPT_START
119  ASSERT_(v.size() == 3);
120  const T x = v[0], y = v[1], z = v[2];
121  const T theta_sq = x * x + y * y + z * z, theta = std::sqrt(theta_sq);
122  T r, i;
123  if (theta < 1e-6)
124  {
125  // Taylor series approximation:
126  const T theta_po4 = theta_sq * theta_sq;
127  i = T(0.5) - T(1.0 / 48.0) * theta_sq + T(1.0 / 3840.0) * theta_po4;
128  r = T(1.0) - T(0.5) * theta_sq + T(1.0 / 384.0) * theta_po4;
129  }
130  else
131  {
132  i = (std::sin(theta / 2)) / theta;
133  r = std::cos(theta / 2);
134  }
135  (*this)[0] = r;
136  (*this)[1] = x * i;
137  (*this)[2] = y * i;
138  (*this)[3] = z * i;
139  ASSERTMSG_(
140  normSqr() - 1.0 < 1e-6,
141  mrpt::format(
142  "fromRodriguesVector() failed, tangent_vector=[%g %g %g]", v[0],
143  v[1], v[2]));
144  MRPT_END
145  }
146 
147  /** @name Lie Algebra methods
148  @{ */
149 
150  /** Logarithm of the 3x3 matrix defined by this pose, generating the
151  * corresponding vector in the SO(3) Lie Algebra,
152  * which coincides with the so-called "rotation vector" (I don't have
153  * space here for the proof ;-).
154  * \param[out] out_ln The target vector, which can be: std::vector<>, or
155  * mrpt::math::CVectorDouble or any row or column Eigen::Matrix<>.
156  * \sa exp, mrpt::poses::SE_traits */
157  template <class ARRAYLIKE3>
158  inline void ln(ARRAYLIKE3& out_ln) const
159  {
160  if (out_ln.size() != 3) out_ln.resize(3);
161  this->ln_noresize(out_ln);
162  }
163  /** overload that returns by value */
164  template <class ARRAYLIKE3>
165  inline ARRAYLIKE3 ln() const
166  {
167  ARRAYLIKE3 out_ln;
168  this->ln(out_ln);
169  return out_ln;
170  }
171  /** Like ln() but does not try to resize the output vector. */
172  template <class ARRAYLIKE3>
173  void ln_noresize(ARRAYLIKE3& out_ln) const
174  {
175  using mrpt::square;
176  const T xyz_norm = std::sqrt(square(x()) + square(y()) + square(z()));
177  const T K = (xyz_norm < 1e-7) ? 2 : 2 * ::acos(r()) / xyz_norm;
178  out_ln[0] = K * x();
179  out_ln[1] = K * y();
180  out_ln[2] = K * z();
181  }
182 
183  /** Exponential map from the SO(3) Lie Algebra to unit quaternions.
184  * \sa ln, mrpt::poses::SE_traits */
185  template <class ARRAYLIKE3>
186  inline static CQuaternion<T> exp(const ARRAYLIKE3& v)
187  {
189  q.fromRodriguesVector(v);
190  return q;
191  }
192  /** \overload */
193  template <class ARRAYLIKE3>
194  inline static void exp(const ARRAYLIKE3& v, CQuaternion<T>& out_quat)
195  {
196  out_quat.fromRodriguesVector(v);
197  }
198 
199  /** @} */ // end of Lie algebra
200 
201  /** Calculate the "cross" product (or "composed rotation") of two
202  * quaternion: this = q1 x q2
203  * After the operation, "this" will represent the composed rotations of
204  * q1 and q2 (q2 applied "after" q1).
205  */
206  inline void crossProduct(const CQuaternion& q1, const CQuaternion& q2)
207  {
208  // First: compute result, then save in this object. In this way we avoid
209  // problems when q1 or q2 == *this !!
210  const T new_r = q1.r() * q2.r() - q1.x() * q2.x() - q1.y() * q2.y() -
211  q1.z() * q2.z();
212  const T new_x = q1.r() * q2.x() + q2.r() * q1.x() + q1.y() * q2.z() -
213  q2.y() * q1.z();
214  const T new_y = q1.r() * q2.y() + q2.r() * q1.y() + q1.z() * q2.x() -
215  q2.z() * q1.x();
216  const T new_z = q1.r() * q2.z() + q2.r() * q1.z() + q1.x() * q2.y() -
217  q2.x() * q1.y();
218  this->r(new_r);
219  this->x(new_x);
220  this->y(new_y);
221  this->z(new_z);
222  this->normalize();
223  }
224 
225  /** Rotate a 3D point (lx,ly,lz) -> (gx,gy,gz) as described by this
226  * quaternion
227  */
228  void rotatePoint(
229  const double lx, const double ly, const double lz, double& gx,
230  double& gy, double& gz) const
231  {
232  const double t2 = r() * x();
233  const double t3 = r() * y();
234  const double t4 = r() * z();
235  const double t5 = -x() * x();
236  const double t6 = x() * y();
237  const double t7 = x() * z();
238  const double t8 = -y() * y();
239  const double t9 = y() * z();
240  const double t10 = -z() * z();
241  gx = 2 * ((t8 + t10) * lx + (t6 - t4) * ly + (t3 + t7) * lz) + lx;
242  gy = 2 * ((t4 + t6) * lx + (t5 + t10) * ly + (t9 - t2) * lz) + ly;
243  gz = 2 * ((t7 - t3) * lx + (t2 + t9) * ly + (t5 + t8) * lz) + lz;
244  }
245 
246  /** Rotate a 3D point (lx,ly,lz) -> (gx,gy,gz) as described by the inverse
247  * (conjugate) of this quaternion
248  */
249  void inverseRotatePoint(
250  const double lx, const double ly, const double lz, double& gx,
251  double& gy, double& gz) const
252  {
253  const double t2 = -r() * x();
254  const double t3 = -r() * y();
255  const double t4 = -r() * z();
256  const double t5 = -x() * x();
257  const double t6 = x() * y();
258  const double t7 = x() * z();
259  const double t8 = -y() * y();
260  const double t9 = y() * z();
261  const double t10 = -z() * z();
262  gx = 2 * ((t8 + t10) * lx + (t6 - t4) * ly + (t3 + t7) * lz) + lx;
263  gy = 2 * ((t4 + t6) * lx + (t5 + t10) * ly + (t9 - t2) * lz) + ly;
264  gz = 2 * ((t7 - t3) * lx + (t2 + t9) * ly + (t5 + t8) * lz) + lz;
265  }
266 
267  /** Return the squared norm of the quaternion */
268  inline double normSqr() const
269  {
270  using mrpt::square;
271  return square(r()) + square(x()) + square(y()) + square(z());
272  }
273 
274  /** Normalize this quaternion, so its norm becomes the unitity.
275  */
276  inline void normalize()
277  {
278  const T qq = 1.0 / std::sqrt(normSqr());
279  for (unsigned int i = 0; i < 4; i++) (*this)[i] *= qq;
280  }
281 
282  /** Calculate the 4x4 Jacobian of the normalization operation of this
283  * quaternion.
284  * The output matrix can be a dynamic or fixed size (4x4) matrix.
285  */
286  template <class MATRIXLIKE>
287  void normalizationJacobian(MATRIXLIKE& J) const
288  {
289  const T n = 1.0 / std::pow(normSqr(), T(1.5));
290  J.setSize(4, 4);
291  J(0, 0) = x() * x() + y() * y() + z() * z();
292  J(0, 1) = -r() * x();
293  J(0, 2) = -r() * y();
294  J(0, 3) = -r() * z();
295 
296  J(1, 0) = -x() * r();
297  J(1, 1) = r() * r() + y() * y() + z() * z();
298  J(1, 2) = -x() * y();
299  J(1, 3) = -x() * z();
300 
301  J(2, 0) = -y() * r();
302  J(2, 1) = -y() * x();
303  J(2, 2) = r() * r() + x() * x() + z() * z();
304  J(2, 3) = -y() * z();
305 
306  J(3, 0) = -z() * r();
307  J(3, 1) = -z() * x();
308  J(3, 2) = -z() * y();
309  J(3, 3) = r() * r() + x() * x() + y() * y();
310  J *= n;
311  }
312 
313  /** Compute the Jacobian of the rotation composition operation \f$ p =
314  * f(\cdot) = q_{this} \times r \f$, that is the 4x4 matrix \f$
315  * \frac{\partial f}{\partial q_{this} } \f$.
316  * The output matrix can be a dynamic or fixed size (4x4) matrix.
317  */
318  template <class MATRIXLIKE>
319  inline void rotationJacobian(MATRIXLIKE& J) const
320  {
321  J.setSize(4, 4);
322  J(0, 0) = r();
323  J(0, 1) = -x();
324  J(0, 2) = -y();
325  J(0, 3) = -z();
326  J(1, 0) = x();
327  J(1, 1) = r();
328  J(1, 2) = -z();
329  J(1, 3) = y();
330  J(2, 0) = y();
331  J(2, 1) = z();
332  J(2, 2) = r();
333  J(2, 3) = -x();
334  J(3, 0) = z();
335  J(3, 1) = -y();
336  J(3, 2) = x();
337  J(3, 3) = r();
338  }
339 
340  /** Calculate the 3x3 rotation matrix associated to this quaternion: \f[
341  * \mathbf{R} = \left(
342  * \begin{array}{ccc}
343  * q_r^2+q_x^2-q_y^2-q_z^2 & 2(q_x q_y - q_r q_z) & 2(q_z
344  * q_x+q_r q_y) \\
345  * 2(q_x q_y+q_r q_z) & q_r^2-q_x^2+q_y^2-q_z^2 & 2(q_y
346  * q_z-q_r q_x) \\
347  * 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 +
348  * q_z^2
349  * \end{array}
350  * \right)\f]
351  *
352  */
353  template <class MATRIXLIKE>
354  inline void rotationMatrix(MATRIXLIKE& M) const
355  {
356  M.setSize(3, 3);
358  }
359 
360  /** Fill out the top-left 3x3 block of the given matrix with the rotation
361  * matrix associated to this quaternion (does not resize the matrix, for
362  * that, see rotationMatrix). */
363  template <class MATRIXLIKE>
364  inline void rotationMatrixNoResize(MATRIXLIKE& M) const
365  {
366  M(0, 0) = r() * r() + x() * x() - y() * y() - z() * z();
367  M(0, 1) = 2 * (x() * y() - r() * z());
368  M(0, 2) = 2 * (z() * x() + r() * y());
369  M(1, 0) = 2 * (x() * y() + r() * z());
370  M(1, 1) = r() * r() - x() * x() + y() * y() - z() * z();
371  M(1, 2) = 2 * (y() * z() - r() * x());
372  M(2, 0) = 2 * (z() * x() - r() * y());
373  M(2, 1) = 2 * (y() * z() + r() * x());
374  M(2, 2) = r() * r() - x() * x() - y() * y() + z() * z();
375  }
376 
377  /** Return the conjugate quaternion */
378  inline void conj(CQuaternion& q_out) const
379  {
380  q_out.r(r());
381  q_out.x(-x());
382  q_out.y(-y());
383  q_out.z(-z());
384  }
385 
386  /** Return the conjugate quaternion */
387  inline CQuaternion conj() const
388  {
389  CQuaternion q_aux;
390  conj(q_aux);
391  return q_aux;
392  }
393 
394  /** Return the yaw, pitch & roll angles associated to quaternion
395  * \sa For the equations, see The MRPT Book, or see
396  * http://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToEuler/Quaternions.pdf
397  * \sa rpy_and_jacobian
398  */
399  inline void rpy(T& roll, T& pitch, T& yaw) const
400  {
402  roll, pitch, yaw, static_cast<mrpt::math::CMatrixDouble*>(nullptr));
403  }
404 
405  /** Return the yaw, pitch & roll angles associated to quaternion, and
406  * (optionally) the 3x4 Jacobian of the transformation.
407  * Note that both the angles and the Jacobian have one set of normal
408  * equations, plus other special formulas for the degenerated cases of
409  * |pitch|=90 degrees.
410  * \sa For the equations, see The MRPT Book, or
411  * http://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToEuler/Quaternions.pdf
412  * \sa rpy
413  */
414  template <class MATRIXLIKE>
415  void rpy_and_jacobian(
416  T& roll, T& pitch, T& yaw, MATRIXLIKE* out_dr_dq = nullptr,
417  bool resize_out_dr_dq_to3x4 = true) const
418  {
419  using mrpt::square;
420  using std::sqrt;
421 
422  if (out_dr_dq && resize_out_dr_dq_to3x4) out_dr_dq->setSize(3, 4);
423  const T discr = r() * y() - x() * z();
424  if (fabs(discr) > 0.49999)
425  { // pitch = 90 deg
426  pitch = 0.5 * M_PI;
427  yaw = -2 * atan2(x(), r());
428  roll = 0;
429  if (out_dr_dq)
430  {
431  out_dr_dq->setZero();
432  (*out_dr_dq)(0, 0) = +2 / x();
433  (*out_dr_dq)(0, 2) = -2 * r() / (x() * x());
434  }
435  }
436  else if (discr < -0.49999)
437  { // pitch =-90 deg
438  pitch = -0.5 * M_PI;
439  yaw = 2 * atan2(x(), r());
440  roll = 0;
441  if (out_dr_dq)
442  {
443  out_dr_dq->setZero();
444  (*out_dr_dq)(0, 0) = -2 / x();
445  (*out_dr_dq)(0, 2) = +2 * r() / (x() * x());
446  }
447  }
448  else
449  { // Non-degenerate case:
450  yaw = ::atan2(
451  2 * (r() * z() + x() * y()), 1 - 2 * (y() * y() + z() * z()));
452  pitch = ::asin(2 * discr);
453  roll = ::atan2(
454  2 * (r() * x() + y() * z()), 1 - 2 * (x() * x() + y() * y()));
455  if (out_dr_dq)
456  {
457  // Auxiliary terms:
458  const double val1 = (2 * x() * x() + 2 * y() * y() - 1);
459  const double val12 = square(val1);
460  const double val2 = (2 * r() * x() + 2 * y() * z());
461  const double val22 = square(val2);
462  const double xy2 = 2 * x() * y();
463  const double rz2 = 2 * r() * z();
464  const double ry2 = 2 * r() * y();
465  const double val3 = (2 * y() * y() + 2 * z() * z() - 1);
466  const double val4 =
467  ((square(rz2 + xy2) / square(val3) + 1) * val3);
468  const double val5 = (4 * (rz2 + xy2)) / square(val3);
469  const double val6 =
470  1.0 / (square(rz2 + xy2) / square(val3) + 1);
471  const double val7 = 2.0 / sqrt(1 - square(ry2 - 2 * x() * z()));
472  const double val8 = (val22 / val12 + 1);
473  const double val9 = -2.0 / val8;
474  // row 1:
475  (*out_dr_dq)(0, 0) = -2 * z() / val4;
476  (*out_dr_dq)(0, 1) = -2 * y() / val4;
477  (*out_dr_dq)(0, 2) = -(2 * x() / val3 - y() * val5) * val6;
478  (*out_dr_dq)(0, 3) = -(2 * r() / val3 - z() * val5) * val6;
479  // row 2:
480  (*out_dr_dq)(1, 0) = y() * val7;
481  (*out_dr_dq)(1, 1) = -z() * val7;
482  (*out_dr_dq)(1, 2) = r() * val7;
483  (*out_dr_dq)(1, 3) = -x() * val7;
484  // row 3:
485  (*out_dr_dq)(2, 0) = val9 * x() / val1;
486  (*out_dr_dq)(2, 1) =
487  val9 * (r() / val1 - (2 * x() * val2) / val12);
488  (*out_dr_dq)(2, 2) =
489  val9 * (z() / val1 - (2 * y() * val2) / val12);
490  (*out_dr_dq)(2, 3) = val9 * y() / val1;
491  }
492  }
493  }
495  inline CQuaternion operator*(const T& factor)
496  {
497  CQuaternion q = *this;
498  q *= factor;
499  return q;
500  }
501 
502 }; // end class
503 
504 /** A quaternion of data type "double" */
506 /** A quaternion of data type "float" */
508 
509 } // namespace mrpt::math
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:414
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:248
static CQuaternion< T > exp(const ARRAYLIKE3 &v)
Exponential map from the SO(3) Lie Algebra to unit quaternions.
Definition: CQuaternion.h:185
void rotationMatrix(MATRIXLIKE &M) const
Calculate the 3x3 rotation matrix associated to this quaternion: .
Definition: CQuaternion.h:353
A compile-time fixed-size numeric matrix container.
Definition: CMatrixFixed.h:33
#define MRPT_START
Definition: exceptions.h:241
void normalize()
Normalize this quaternion, so its norm becomes the unitity.
Definition: CQuaternion.h:275
GLdouble GLdouble z
Definition: glext.h:3879
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:3727
GLenum GLsizei n
Definition: glext.h:5136
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:363
T square(const T x)
Inline function for the square of a number.
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
double normSqr() const
Return the squared norm of the quaternion.
Definition: CQuaternion.h:267
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:494
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:205
void rotationJacobian(MATRIXLIKE &J) const
Compute the Jacobian of the rotation composition operation , that is the 4x4 matrix ...
Definition: CQuaternion.h:318
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
Definition: exceptions.h:108
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:227
void ln_noresize(ARRAYLIKE3 &out_ln) const
Like ln() but does not try to resize the output vector.
Definition: CQuaternion.h:172
ARRAYLIKE3 ln() const
overload that returns by value
Definition: CQuaternion.h:164
const GLdouble * v
Definition: glext.h:3684
T x() const
Return x coordinate of the quaternion.
Definition: CQuaternion.h:87
GLdouble GLdouble GLdouble r
Definition: glext.h:3711
void normalizationJacobian(MATRIXLIKE &J) const
Calculate the 4x4 Jacobian of the normalization operation of this quaternion.
Definition: CQuaternion.h:286
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
#define MRPT_END
Definition: exceptions.h:245
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:3542
GLenum GLint x
Definition: glext.h:3542
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:398
CQuaternion conj() const
Return the conjugate quaternion.
Definition: CQuaternion.h:386
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: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019