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



Page generated by Doxygen 1.8.9.1 for MRPT 1.3.0 SVN: at Sun Sep 13 03:55:12 UTC 2015