All Classes Namespaces Files Functions Variables Typedefs Friends Macros Pages
Quaternion.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2014 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef _IGNITION_QUATERNION_HH_
18 #define _IGNITION_QUATERNION_HH_
19 
20 #include <ignition/math/Helpers.hh>
21 #include <ignition/math/Angle.hh>
22 #include <ignition/math/Vector3.hh>
23 
24 namespace ignition
25 {
26  namespace math
27  {
30  template<typename T>
31  class Quaternion
32  {
34  public: static const Quaternion Identity;
35 
37  public: Quaternion()
38  : qw(1), qx(0), qy(0), qz(0)
39  {
40  // quaternion not normalized, because that breaks
41  // Pose::CoordPositionAdd(...)
42  }
43 
49  public: Quaternion(const T &_w, const T &_x, const T &_y, const T &_z)
50  : qw(_w), qx(_x), qy(_y), qz(_z)
51  {}
52 
57  public: Quaternion(const T &_roll, const T &_pitch, const T &_yaw)
58  {
59  this->Euler(Vector3<T>(_roll, _pitch, _yaw));
60  }
61 
65  public: Quaternion(const Vector3<T> &_axis, const T &_angle)
66  {
67  this->Axis(_axis, _angle);
68  }
69 
72  public: Quaternion(const Vector3<T> &_rpy)
73  {
74  this->Euler(_rpy);
75  }
76 
79  public: Quaternion(const Quaternion<T> &_qt)
80  {
81  this->qw = _qt.qw;
82  this->qx = _qt.qx;
83  this->qy = _qt.qy;
84  this->qz = _qt.qz;
85  }
86 
88  public: ~Quaternion() {}
89 
92  public: Quaternion<T> &operator=(const Quaternion<T> &_qt)
93  {
94  this->qw = _qt.qw;
95  this->qx = _qt.qx;
96  this->qy = _qt.qy;
97  this->qz = _qt.qz;
98 
99  return *this;
100  }
101 
103  public: void Invert()
104  {
105  this->Normalize();
106  // this->qw = this->qw;
107  this->qx = -this->qx;
108  this->qy = -this->qy;
109  this->qz = -this->qz;
110  }
111 
114  public: inline Quaternion<T> Inverse() const
115  {
116  T s = 0;
117  Quaternion<T> q(this->qw, this->qx, this->qy, this->qz);
118 
119  // use s to test if quaternion is valid
120  s = q.qw * q.qw + q.qx * q.qx + q.qy * q.qy + q.qz * q.qz;
121 
122  if (equal<T>(s, static_cast<T>(0)))
123  {
124  q.qw = 1.0;
125  q.qx = 0.0;
126  q.qy = 0.0;
127  q.qz = 0.0;
128  }
129  else
130  {
131  // deal with non-normalized quaternion
132  // div by s so q * qinv = identity
133  q.qw = q.qw / s;
134  q.qx = -q.qx / s;
135  q.qy = -q.qy / s;
136  q.qz = -q.qz / s;
137  }
138  return q;
139  }
140 
143  public: Quaternion<T> Log() const
144  {
145  // If q = cos(A)+sin(A)*(x*i+y*j+z*k) where (x, y, z) is unit length,
146  // then log(q) = A*(x*i+y*j+z*k). If sin(A) is near zero, use log(q) =
147  // sin(A)*(x*i+y*j+z*k) since sin(A)/A has limit 1.
148 
149  Quaternion<T> result;
150  result.qw = 0.0;
151 
152  if (std::abs(this->qw) < 1.0)
153  {
154  T fAngle = acos(this->qw);
155  T fSin = sin(fAngle);
156  if (std::abs(fSin) >= 1e-3)
157  {
158  T fCoeff = fAngle/fSin;
159  result.qx = fCoeff*this->qx;
160  result.qy = fCoeff*this->qy;
161  result.qz = fCoeff*this->qz;
162  return result;
163  }
164  }
165 
166  result.qx = this->qx;
167  result.qy = this->qy;
168  result.qz = this->qz;
169 
170  return result;
171  }
172 
175  public: Quaternion<T> Exp() const
176  {
177  // If q = A*(x*i+y*j+z*k) where (x, y, z) is unit length, then
178  // exp(q) = cos(A)+sin(A)*(x*i+y*j+z*k). If sin(A) is near zero,
179  // use exp(q) = cos(A)+A*(x*i+y*j+z*k) since A/sin(A) has limit 1.
180 
181  T fAngle = sqrt(this->qx*this->qx+
182  this->qy*this->qy+this->qz*this->qz);
183  T fSin = sin(fAngle);
184 
185  Quaternion<T> result;
186  result.qw = cos(fAngle);
187 
188  if (std::abs(fSin) >= 1e-3)
189  {
190  T fCoeff = fSin/fAngle;
191  result.qx = fCoeff*this->qx;
192  result.qy = fCoeff*this->qy;
193  result.qz = fCoeff*this->qz;
194  }
195  else
196  {
197  result.qx = this->qx;
198  result.qy = this->qy;
199  result.qz = this->qz;
200  }
201 
202  return result;
203  }
204 
206  public: void Normalize()
207  {
208  T s = 0;
209 
210  s = sqrt(this->qw * this->qw + this->qx * this->qx +
211  this->qy * this->qy + this->qz * this->qz);
212 
213  if (equal<T>(s, static_cast<T>(0)))
214  {
215  this->qw = 1.0;
216  this->qx = 0.0;
217  this->qy = 0.0;
218  this->qz = 0.0;
219  }
220  else
221  {
222  this->qw /= s;
223  this->qx /= s;
224  this->qy /= s;
225  this->qz /= s;
226  }
227  }
228 
234  public: void Axis(T _ax, T _ay, T _az, T _aa)
235  {
236  T l;
237 
238  l = _ax * _ax + _ay * _ay + _az * _az;
239 
240  if (equal<T>(l, static_cast<T>(0)))
241  {
242  this->qw = 1;
243  this->qx = 0;
244  this->qy = 0;
245  this->qz = 0;
246  }
247  else
248  {
249  _aa *= 0.5;
250  l = sin(_aa) / sqrt(l);
251  this->qw = cos(_aa);
252  this->qx = _ax * l;
253  this->qy = _ay * l;
254  this->qz = _az * l;
255  }
256 
257  this->Normalize();
258  }
259 
263  public: void Axis(const Vector3<T> &_axis, T _a)
264  {
265  this->Axis(_axis.X(), _axis.Y(), _axis.Z(), _a);
266  }
267 
273  public: void Set(T _w, T _x, T _y, T _z)
274  {
275  this->qw = _w;
276  this->qx = _x;
277  this->qy = _y;
278  this->qz = _z;
279  }
280 
284  public: void Euler(const Vector3<T> &_vec)
285  {
286  this->Euler(_vec.X(), _vec.Y(), _vec.Z());
287  }
288 
293  public: void Euler(T _roll, T _pitch, T _yaw)
294  {
295  T phi, the, psi;
296 
297  phi = _roll / 2.0;
298  the = _pitch / 2.0;
299  psi = _yaw / 2.0;
300 
301  this->qw = cos(phi) * cos(the) * cos(psi) +
302  sin(phi) * sin(the) * sin(psi);
303  this->qx = sin(phi) * cos(the) * cos(psi) -
304  cos(phi) * sin(the) * sin(psi);
305  this->qy = cos(phi) * sin(the) * cos(psi) +
306  sin(phi) * cos(the) * sin(psi);
307  this->qz = cos(phi) * cos(the) * sin(psi) -
308  sin(phi) * sin(the) * cos(psi);
309 
310  this->Normalize();
311  }
312 
315  public: Vector3<T> Euler() const
316  {
317  Vector3<T> vec;
318 
319  Quaternion<T> copy = *this;
320  T squ;
321  T sqx;
322  T sqy;
323  T sqz;
324 
325  copy.Normalize();
326 
327  squ = copy.qw * copy.qw;
328  sqx = copy.qx * copy.qx;
329  sqy = copy.qy * copy.qy;
330  sqz = copy.qz * copy.qz;
331 
332  // Roll
333  vec.X(atan2(2 * (copy.qy*copy.qz + copy.qw*copy.qx),
334  squ - sqx - sqy + sqz));
335 
336  // Pitch
337  T sarg = -2 * (copy.qx*copy.qz - copy.qw * copy.qy);
338  vec.Y(sarg <= -1.0 ? -0.5*IGN_PI :
339  (sarg >= 1.0 ? 0.5*IGN_PI : asin(sarg)));
340 
341  // Yaw
342  vec.Z(atan2(2 * (copy.qx*copy.qy + copy.qw*copy.qz),
343  squ + sqx - sqy - sqz));
344 
345  return vec;
346  }
347 
350  public: static Quaternion<T> EulerToQuaternion(const Vector3<T> &_vec)
351  {
352  Quaternion<T> result;
353  result.Euler(_vec);
354  return result;
355  }
356 
361  public: static Quaternion<T> EulerToQuaternion(T _x, T _y, T _z)
362  {
363  return EulerToQuaternion(Vector3<T>(_x, _y, _z));
364  }
365 
368  public: T Roll() const
369  {
370  return this->Euler().X();
371  }
372 
375  public: T Pitch() const
376  {
377  return this->Euler().Y();
378  }
379 
382  public: T Yaw() const
383  {
384  return this->Euler().Z();
385  }
386 
390  public: void ToAxis(Vector3<T> &_axis, T &_angle) const
391  {
392  T len = this->qx*this->qx + this->qy*this->qy + this->qz*this->qz;
393  if (equal<T>(len, static_cast<T>(0)))
394  {
395  _angle = 0.0;
396  _axis.Set(1, 0, 0);
397  }
398  else
399  {
400  _angle = 2.0 * acos(this->qw);
401  T invLen = 1.0 / sqrt(len);
402  _axis.Set(this->qx*invLen, this->qy*invLen, this->qz*invLen);
403  }
404  }
405 
408  public: void Scale(T _scale)
409  {
410  Quaternion<T> b;
411  Vector3<T> axis;
412  T angle;
413 
414  // Convert to axis-and-angle
415  this->ToAxis(axis, angle);
416  angle *= _scale;
417 
418  this->Axis(axis.X(), axis.Y(), axis.Z(), angle);
419  }
420 
424  public: Quaternion<T> operator+(const Quaternion<T> &_qt) const
425  {
426  Quaternion<T> result(this->qw + _qt.qw, this->qx + _qt.qx,
427  this->qy + _qt.qy, this->qz + _qt.qz);
428  return result;
429  }
430 
435  {
436  *this = *this + _qt;
437 
438  return *this;
439  }
440 
444  public: Quaternion<T> operator-(const Quaternion<T> &_qt) const
445  {
446  Quaternion<T> result(this->qw - _qt.qw, this->qx - _qt.qx,
447  this->qy - _qt.qy, this->qz - _qt.qz);
448  return result;
449  }
450 
455  {
456  *this = *this - _qt;
457  return *this;
458  }
459 
463  public: inline Quaternion<T> operator*(const Quaternion<T> &_q) const
464  {
465  return Quaternion<T>(
466  this->qw*_q.qw-this->qx*_q.qx-this->qy*_q.qy-this->qz*_q.qz,
467  this->qw*_q.qx+this->qx*_q.qw+this->qy*_q.qz-this->qz*_q.qy,
468  this->qw*_q.qy-this->qx*_q.qz+this->qy*_q.qw+this->qz*_q.qx,
469  this->qw*_q.qz+this->qx*_q.qy-this->qy*_q.qx+this->qz*_q.qw);
470  }
471 
475  public: Quaternion<T> operator*(const T &_f) const
476  {
477  return Quaternion<T>(this->qw*_f, this->qx*_f,
478  this->qy*_f, this->qz*_f);
479  }
480 
485  {
486  *this = *this * qt;
487  return *this;
488  }
489 
492  public: Vector3<T> operator*(const Vector3<T> &_v) const
493  {
494  Vector3<T> uv, uuv;
495  Vector3<T> qvec(this->qx, this->qy, this->qz);
496  uv = qvec.Cross(_v);
497  uuv = qvec.Cross(uv);
498  uv *= (2.0f * this->qw);
499  uuv *= 2.0f;
500 
501  return _v + uv + uuv;
502  }
503 
507  public: bool operator==(const Quaternion<T> &_qt) const
508  {
509  return equal(this->qx, _qt.qx, static_cast<T>(0.001)) &&
510  equal(this->qy, _qt.qy, static_cast<T>(0.001)) &&
511  equal(this->qz, _qt.qz, static_cast<T>(0.001)) &&
512  equal(this->qw, _qt.qw, static_cast<T>(0.001));
513  }
514 
518  public: bool operator!=(const Quaternion<T> &_qt) const
519  {
520  return !equal(this->qx, _qt.qx, static_cast<T>(0.001)) ||
521  !equal(this->qy, _qt.qy, static_cast<T>(0.001)) ||
522  !equal(this->qz, _qt.qz, static_cast<T>(0.001)) ||
523  !equal(this->qw, _qt.qw, static_cast<T>(0.001));
524  }
525 
528  public: Quaternion<T> operator-() const
529  {
530  return Quaternion<T>(-this->qw, -this->qx, -this->qy, -this->qz);
531  }
532 
536  public: inline Vector3<T> RotateVector(const Vector3<T> &_vec) const
537  {
538  Quaternion<T> tmp(static_cast<T>(0),
539  _vec.X(), _vec.Y(), _vec.Z());
540  tmp = (*this) * (tmp * this->Inverse());
541  return Vector3<T>(tmp.qx, tmp.qy, tmp.qz);
542  }
543 
548  {
549  Quaternion<T> tmp(0.0, _vec.X(), _vec.Y(), _vec.Z());
550 
551  tmp = this->Inverse() * (tmp * (*this));
552 
553  return Vector3<T>(tmp.qx, tmp.qy, tmp.qz);
554  }
555 
558  public: bool IsFinite() const
559  {
560  // std::isfinite works with floating point values, need to explicit
561  // cast to avoid ambiguity in vc++.
562  return std::isfinite(static_cast<double>(this->qw)) &&
563  std::isfinite(static_cast<double>(this->qx)) &&
564  std::isfinite(static_cast<double>(this->qy)) &&
565  std::isfinite(static_cast<double>(this->qz));
566  }
567 
569  public: inline void Correct()
570  {
571  // std::isfinite works with floating point values, need to explicit
572  // cast to avoid ambiguity in vc++.
573  if (!std::isfinite(static_cast<double>(this->qx)))
574  this->qx = 0;
575  if (!std::isfinite(static_cast<double>(this->qy)))
576  this->qy = 0;
577  if (!std::isfinite(static_cast<double>(this->qz)))
578  this->qz = 0;
579  if (!std::isfinite(static_cast<double>(this->qw)))
580  this->qw = 1;
581 
582  if (equal(this->qw, static_cast<T>(0)) &&
583  equal(this->qx, static_cast<T>(0)) &&
584  equal(this->qy, static_cast<T>(0)) &&
585  equal(this->qz, static_cast<T>(0)))
586  {
587  this->qw = 1;
588  }
589  }
590 
593  public: Vector3<T> XAxis() const
594  {
595  T fTy = 2.0f*this->qy;
596  T fTz = 2.0f*this->qz;
597 
598  T fTwy = fTy*this->qw;
599  T fTwz = fTz*this->qw;
600  T fTxy = fTy*this->qx;
601  T fTxz = fTz*this->qx;
602  T fTyy = fTy*this->qy;
603  T fTzz = fTz*this->qz;
604 
605  return Vector3<T>(1.0f-(fTyy+fTzz), fTxy+fTwz, fTxz-fTwy);
606  }
607 
610  public: Vector3<T> YAxis() const
611  {
612  T fTx = 2.0f*this->qx;
613  T fTy = 2.0f*this->qy;
614  T fTz = 2.0f*this->qz;
615  T fTwx = fTx*this->qw;
616  T fTwz = fTz*this->qw;
617  T fTxx = fTx*this->qx;
618  T fTxy = fTy*this->qx;
619  T fTyz = fTz*this->qy;
620  T fTzz = fTz*this->qz;
621 
622  return Vector3<T>(fTxy-fTwz, 1.0f-(fTxx+fTzz), fTyz+fTwx);
623  }
624 
627  public: Vector3<T> ZAxis() const
628  {
629  T fTx = 2.0f*this->qx;
630  T fTy = 2.0f*this->qy;
631  T fTz = 2.0f*this->qz;
632  T fTwx = fTx*this->qw;
633  T fTwy = fTy*this->qw;
634  T fTxx = fTx*this->qx;
635  T fTxz = fTz*this->qx;
636  T fTyy = fTy*this->qy;
637  T fTyz = fTz*this->qy;
638 
639  return Vector3<T>(fTxz+fTwy, fTyz-fTwx, 1.0f-(fTxx+fTyy));
640  }
641 
644  public: void Round(int _precision)
645  {
646  this->qx = precision(this->qx, _precision);
647  this->qy = precision(this->qy, _precision);
648  this->qz = precision(this->qz, _precision);
649  this->qw = precision(this->qw, _precision);
650  }
651 
655  public: T Dot(const Quaternion<T> &_q) const
656  {
657  return this->qw*_q.qw + this->qx * _q.qx +
658  this->qy*_q.qy + this->qz*_q.qz;
659  }
660 
670  public: static Quaternion<T> Squad(T _fT,
671  const Quaternion<T> &_rkP, const Quaternion<T> &_rkA,
672  const Quaternion<T> &_rkB, const Quaternion<T> &_rkQ,
673  bool _shortestPath = false)
674  {
675  T fSlerpT = 2.0f*_fT*(1.0f-_fT);
676  Quaternion<T> kSlerpP = Slerp(_fT, _rkP, _rkQ, _shortestPath);
677  Quaternion<T> kSlerpQ = Slerp(_fT, _rkA, _rkB);
678  return Slerp(fSlerpT, kSlerpP, kSlerpQ);
679  }
680 
688  public: static Quaternion<T> Slerp(T _fT,
689  const Quaternion<T> &_rkP, const Quaternion<T> &_rkQ,
690  bool _shortestPath = false)
691  {
692  T fCos = _rkP.Dot(_rkQ);
693  Quaternion<T> rkT;
694 
695  // Do we need to invert rotation?
696  if (fCos < 0.0f && _shortestPath)
697  {
698  fCos = -fCos;
699  rkT = -_rkQ;
700  }
701  else
702  {
703  rkT = _rkQ;
704  }
705 
706  if (std::abs(fCos) < 1 - 1e-03)
707  {
708  // Standard case (slerp)
709  T fSin = sqrt(1 - (fCos*fCos));
710  T fAngle = atan2(fSin, fCos);
711  // FIXME: should check if (std::abs(fSin) >= 1e-3)
712  T fInvSin = 1.0f / fSin;
713  T fCoeff0 = sin((1.0f - _fT) * fAngle) * fInvSin;
714  T fCoeff1 = sin(_fT * fAngle) * fInvSin;
715  return _rkP * fCoeff0 + rkT * fCoeff1;
716  }
717  else
718  {
719  // There are two situations:
720  // 1. "rkP" and "rkQ" are very close (fCos ~= +1),
721  // so we can do a linear interpolation safely.
722  // 2. "rkP" and "rkQ" are almost inverse of each
723  // other (fCos ~= -1), there
724  // are an infinite number of possibilities interpolation.
725  // but we haven't have method to fix this case, so just use
726  // linear interpolation here.
727  Quaternion<T> t = _rkP * (1.0f - _fT) + rkT * _fT;
728  // taking the complement requires renormalisation
729  t.Normalize();
730  return t;
731  }
732  }
733 
736  public: inline const T &W() const
737  {
738  return this->qw;
739  }
740 
743  public: inline const T &X() const
744  {
745  return this->qx;
746  }
747 
750  public: inline const T &Y() const
751  {
752  return this->qy;
753  }
754 
757  public: inline const T &Z() const
758  {
759  return this->qz;
760  }
761 
762 
765  public: inline T &W()
766  {
767  return this->qw;
768  }
769 
772  public: inline T &X()
773  {
774  return this->qx;
775  }
776 
779  public: inline T &Y()
780  {
781  return this->qy;
782  }
783 
786  public: inline T &Z()
787  {
788  return this->qz;
789  }
790 
793  public: inline void X(T _v)
794  {
795  this->qx = _v;
796  }
797 
800  public: inline void Y(T _v)
801  {
802  this->qy = _v;
803  }
804 
807  public: inline void Z(T _v)
808  {
809  this->qz = _v;
810  }
811 
814  public: inline void W(T _v)
815  {
816  this->qw = _v;
817  }
818 
823  public: friend std::ostream &operator<<(std::ostream &_out,
825  {
826  Vector3<T> v(_q.Euler());
827  _out << precision(v.X(), 6) << " " << precision(v.Y(), 6) << " "
828  << precision(v.Z(), 6);
829  return _out;
830  }
831 
836  public: friend std::istream &operator>>(std::istream &_in,
838  {
839  Angle roll, pitch, yaw;
840 
841  // Skip white spaces
842  _in.setf(std::ios_base::skipws);
843  _in >> roll >> pitch >> yaw;
844 
845  _q.Euler(Vector3<T>(*roll, *pitch, *yaw));
846 
847  return _in;
848  }
849 
851  private: T qw;
852 
854  private: T qx;
855 
857  private: T qy;
858 
860  private: T qz;
861  };
862 
863  template<typename T> const Quaternion<T>
864  Quaternion<T>::Identity(1, 0, 0, 0);
865 
869  }
870 }
871 #endif
An angle and related functions.
Definition: Angle.hh:44
Quaternion< double > Quaterniond
Definition: Quaternion.hh:866
void Round(int _precision)
Round all values to _precision decimal places.
Definition: Quaternion.hh:644
void Y(T _v)
Set the y component.
Definition: Quaternion.hh:800
Quaternion(const Vector3< T > &_axis, const T &_angle)
Constructor from axis angle.
Definition: Quaternion.hh:65
void Set(T _x=0, T _y=0, T _z=0)
Set the contents of the vector.
Definition: Vector3.hh:171
~Quaternion()
Destructor.
Definition: Quaternion.hh:88
void X(T _v)
Set the x component.
Definition: Quaternion.hh:793
void Euler(T _roll, T _pitch, T _yaw)
Set the quaternion from Euler angles.
Definition: Quaternion.hh:293
Quaternion(const Vector3< T > &_rpy)
Constructor.
Definition: Quaternion.hh:72
T precision(const T &_a, const unsigned int &_precision)
get value at a specified precision
Definition: Helpers.hh:188
Vector3< T > operator*(const Vector3< T > &_v) const
Vector3 multiplication operator.
Definition: Quaternion.hh:492
bool operator==(const Quaternion< T > &_qt) const
Equal to operator.
Definition: Quaternion.hh:507
void Z(T _v)
Set the z component.
Definition: Quaternion.hh:807
Quaternion< T > Inverse() const
Get the inverse of this quaternion.
Definition: Quaternion.hh:114
void Invert()
Invert the quaternion.
Definition: Quaternion.hh:103
Quaternion< T > operator-(const Quaternion< T > &_qt) const
Substraction operator.
Definition: Quaternion.hh:444
T & X()
Get a mutable x component.
Definition: Quaternion.hh:772
T Roll() const
Get the Euler roll angle in radians.
Definition: Quaternion.hh:368
Quaternion< float > Quaternionf
Definition: Quaternion.hh:867
friend std::istream & operator>>(std::istream &_in, ignition::math::Quaternion< T > &_q)
Stream extraction operator.
Definition: Quaternion.hh:836
static Quaternion< T > Squad(T _fT, const Quaternion< T > &_rkP, const Quaternion< T > &_rkA, const Quaternion< T > &_rkB, const Quaternion< T > &_rkQ, bool _shortestPath=false)
Spherical quadratic interpolation given the ends and an interpolation parameter between 0 and 1...
Definition: Quaternion.hh:670
const T & Y() const
Get the y component.
Definition: Quaternion.hh:750
T & Y()
Get a mutable y component.
Definition: Quaternion.hh:779
Vector3< T > Euler() const
Return the rotation in Euler angles.
Definition: Quaternion.hh:315
T Pitch() const
Get the Euler pitch angle in radians.
Definition: Quaternion.hh:375
T X() const
Get the x value.
Definition: Vector3.hh:545
Quaternion< T > operator*(const T &_f) const
Multiplication operator.
Definition: Quaternion.hh:475
const T & Z() const
Get the z component.
Definition: Quaternion.hh:757
Quaternion< T > operator+=(const Quaternion< T > &_qt)
Addition operator.
Definition: Quaternion.hh:434
void Correct()
Correct any nan.
Definition: Quaternion.hh:569
Vector3 Cross(const Vector3< T > &_v) const
Return the cross product of this vector with another vector.
Definition: Vector3.hh:181
Quaternion(const Quaternion< T > &_qt)
Copy constructor.
Definition: Quaternion.hh:79
Vector3< T > YAxis() const
Return the Y axis.
Definition: Quaternion.hh:610
static Quaternion< T > EulerToQuaternion(const Vector3< T > &_vec)
Convert euler angles to quatern.
Definition: Quaternion.hh:350
T Dot(const Quaternion< T > &_q) const
Dot product.
Definition: Quaternion.hh:655
Quaternion< T > & operator=(const Quaternion< T > &_qt)
Equal operator.
Definition: Quaternion.hh:92
T Y() const
Get the y value.
Definition: Vector3.hh:552
void Axis(const Vector3< T > &_axis, T _a)
Set the quaternion from an axis and angle.
Definition: Quaternion.hh:263
void Axis(T _ax, T _ay, T _az, T _aa)
Set the quaternion from an axis and angle.
Definition: Quaternion.hh:234
Quaternion(const T &_w, const T &_x, const T &_y, const T &_z)
Constructor.
Definition: Quaternion.hh:49
Vector3< T > RotateVectorReverse(Vector3< T > _vec) const
Do the reverse rotation of a vector by this quaternion.
Definition: Quaternion.hh:547
static const Quaternion Identity
math::Quaternion(1, 0, 0, 1)
Definition: Quaternion.hh:34
friend std::ostream & operator<<(std::ostream &_out, const ignition::math::Quaternion< T > &_q)
Stream insertion operator.
Definition: Quaternion.hh:823
Vector3< T > XAxis() const
Return the X axis.
Definition: Quaternion.hh:593
Quaternion< T > operator*(const Quaternion< T > &_q) const
Multiplication operator.
Definition: Quaternion.hh:463
T & W()
Get a mutable w component.
Definition: Quaternion.hh:765
T Z() const
Get the z value.
Definition: Vector3.hh:559
void Scale(T _scale)
Scale a Quaternion<T>ion.
Definition: Quaternion.hh:408
static Quaternion< T > Slerp(T _fT, const Quaternion< T > &_rkP, const Quaternion< T > &_rkQ, bool _shortestPath=false)
Spherical linear interpolation between 2 quaternions, given the ends and an interpolation parameter b...
Definition: Quaternion.hh:688
void ToAxis(Vector3< T > &_axis, T &_angle) const
Return rotation as axis and angle.
Definition: Quaternion.hh:390
Quaternion< T > operator-() const
Unary minus operator.
Definition: Quaternion.hh:528
Quaternion< T > operator+(const Quaternion< T > &_qt) const
Addition operator.
Definition: Quaternion.hh:424
T & Z()
Get a mutable z component.
Definition: Quaternion.hh:786
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:37
bool IsFinite() const
See if a quatern is finite (e.g., not nan)
Definition: Quaternion.hh:558
bool operator!=(const Quaternion< T > &_qt) const
Not equal to operator.
Definition: Quaternion.hh:518
void W(T _v)
Set the w component.
Definition: Quaternion.hh:814
Quaternion< T > operator*=(const Quaternion< T > &qt)
Multiplication operator.
Definition: Quaternion.hh:484
Quaternion< int > Quaternioni
Definition: Quaternion.hh:868
void Euler(const Vector3< T > &_vec)
Set the quaternion from Euler angles.
Definition: Quaternion.hh:284
T Yaw() const
Get the Euler yaw angle in radians.
Definition: Quaternion.hh:382
Quaternion()
Default Constructor.
Definition: Quaternion.hh:37
const T & W() const
Get the w component.
Definition: Quaternion.hh:736
bool equal(const T &_a, const T &_b, const T &_epsilon=1e-6)
check if two values are equal, within a tolerance
Definition: Helpers.hh:177
void Normalize()
Normalize the quaternion.
Definition: Quaternion.hh:206
A quaternion class.
Definition: Quaternion.hh:31
Quaternion< T > Exp() const
Return the exponent.
Definition: Quaternion.hh:175
Quaternion< T > operator-=(const Quaternion< T > &_qt)
Substraction operator.
Definition: Quaternion.hh:454
#define IGN_PI
Define IGN_PI, IGN_PI_2, and IGN_PI_4.
Definition: Helpers.hh:59
Vector3< T > RotateVector(const Vector3< T > &_vec) const
Rotate a vector using the quaternion.
Definition: Quaternion.hh:536
Quaternion(const T &_roll, const T &_pitch, const T &_yaw)
Constructor from Euler angles in radians.
Definition: Quaternion.hh:57
Quaternion< T > Log() const
Return the logarithm.
Definition: Quaternion.hh:143
Vector3< T > ZAxis() const
Return the Z axis.
Definition: Quaternion.hh:627
static Quaternion< T > EulerToQuaternion(T _x, T _y, T _z)
Convert euler angles to quatern.
Definition: Quaternion.hh:361
void Set(T _w, T _x, T _y, T _z)
Set this quaternion from 4 floating numbers.
Definition: Quaternion.hh:273
const T & X() const
Get the x component.
Definition: Quaternion.hh:743