Ignition Math

API Reference

6.4.0
Quaternion.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012 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_MATH_QUATERNION_HH_
18 #define IGNITION_MATH_QUATERNION_HH_
19 
20 #include <ignition/math/Helpers.hh>
21 #include <ignition/math/Angle.hh>
22 #include <ignition/math/Vector3.hh>
23 #include <ignition/math/Matrix3.hh>
24 #include <ignition/math/config.hh>
25 
26 namespace ignition
27 {
28  namespace math
29  {
30  // Inline bracket to help doxygen filtering.
31  inline namespace IGNITION_MATH_VERSION_NAMESPACE {
32  //
33  template <typename T> class Matrix3;
34 
37  template<typename T>
38  class Quaternion
39  {
41  public: static const Quaternion Identity;
42 
44  public: static const Quaternion Zero;
45 
47  public: Quaternion()
48  : qw(1), qx(0), qy(0), qz(0)
49  {
50  // quaternion not normalized, because that breaks
51  // Pose::CoordPositionAdd(...)
52  }
53 
59  public: Quaternion(const T &_w, const T &_x, const T &_y, const T &_z)
60  : qw(_w), qx(_x), qy(_y), qz(_z)
61  {}
62 
67  public: Quaternion(const T &_roll, const T &_pitch, const T &_yaw)
68  {
69  this->Euler(Vector3<T>(_roll, _pitch, _yaw));
70  }
71 
75  public: Quaternion(const Vector3<T> &_axis, const T &_angle)
76  {
77  this->Axis(_axis, _angle);
78  }
79 
82  public: explicit Quaternion(const Vector3<T> &_rpy)
83  {
84  this->Euler(_rpy);
85  }
86 
90  public: explicit Quaternion(const Matrix3<T> &_mat)
91  {
92  this->Matrix(_mat);
93  }
94 
97  public: Quaternion(const Quaternion<T> &_qt)
98  {
99  this->qw = _qt.qw;
100  this->qx = _qt.qx;
101  this->qy = _qt.qy;
102  this->qz = _qt.qz;
103  }
104 
106  public: ~Quaternion() {}
107 
110  public: Quaternion<T> &operator=(const Quaternion<T> &_qt)
111  {
112  this->qw = _qt.qw;
113  this->qx = _qt.qx;
114  this->qy = _qt.qy;
115  this->qz = _qt.qz;
116 
117  return *this;
118  }
119 
121  public: void Invert()
122  {
123  this->Normalize();
124  // this->qw = this->qw;
125  this->qx = -this->qx;
126  this->qy = -this->qy;
127  this->qz = -this->qz;
128  }
129 
132  public: inline Quaternion<T> Inverse() const
133  {
134  T s = 0;
135  Quaternion<T> q(this->qw, this->qx, this->qy, this->qz);
136 
137  // use s to test if quaternion is valid
138  s = q.qw * q.qw + q.qx * q.qx + q.qy * q.qy + q.qz * q.qz;
139 
140  if (equal<T>(s, static_cast<T>(0)))
141  {
142  q.qw = 1.0;
143  q.qx = 0.0;
144  q.qy = 0.0;
145  q.qz = 0.0;
146  }
147  else
148  {
149  // deal with non-normalized quaternion
150  // div by s so q * qinv = identity
151  q.qw = q.qw / s;
152  q.qx = -q.qx / s;
153  q.qy = -q.qy / s;
154  q.qz = -q.qz / s;
155  }
156  return q;
157  }
158 
161  public: Quaternion<T> Log() const
162  {
163  // If q = cos(A)+sin(A)*(x*i+y*j+z*k) where (x, y, z) is unit length,
164  // then log(q) = A*(x*i+y*j+z*k). If sin(A) is near zero, use log(q) =
165  // sin(A)*(x*i+y*j+z*k) since sin(A)/A has limit 1.
166 
167  Quaternion<T> result;
168  result.qw = 0.0;
169 
170  if (std::abs(this->qw) < 1.0)
171  {
172  T fAngle = acos(this->qw);
173  T fSin = sin(fAngle);
174  if (std::abs(fSin) >= 1e-3)
175  {
176  T fCoeff = fAngle/fSin;
177  result.qx = fCoeff*this->qx;
178  result.qy = fCoeff*this->qy;
179  result.qz = fCoeff*this->qz;
180  return result;
181  }
182  }
183 
184  result.qx = this->qx;
185  result.qy = this->qy;
186  result.qz = this->qz;
187 
188  return result;
189  }
190 
193  public: Quaternion<T> Exp() const
194  {
195  // If q = A*(x*i+y*j+z*k) where (x, y, z) is unit length, then
196  // exp(q) = cos(A)+sin(A)*(x*i+y*j+z*k). If sin(A) is near zero,
197  // use exp(q) = cos(A)+A*(x*i+y*j+z*k) since A/sin(A) has limit 1.
198 
199  T fAngle = sqrt(this->qx*this->qx+
200  this->qy*this->qy+this->qz*this->qz);
201  T fSin = sin(fAngle);
202 
203  Quaternion<T> result;
204  result.qw = cos(fAngle);
205 
206  if (std::abs(fSin) >= 1e-3)
207  {
208  T fCoeff = fSin/fAngle;
209  result.qx = fCoeff*this->qx;
210  result.qy = fCoeff*this->qy;
211  result.qz = fCoeff*this->qz;
212  }
213  else
214  {
215  result.qx = this->qx;
216  result.qy = this->qy;
217  result.qz = this->qz;
218  }
219 
220  return result;
221  }
222 
224  public: void Normalize()
225  {
226  T s = 0;
227 
228  s = T(sqrt(this->qw * this->qw + this->qx * this->qx +
229  this->qy * this->qy + this->qz * this->qz));
230 
231  if (equal<T>(s, static_cast<T>(0)))
232  {
233  this->qw = T(1.0);
234  this->qx = T(0.0);
235  this->qy = T(0.0);
236  this->qz = T(0.0);
237  }
238  else
239  {
240  this->qw /= s;
241  this->qx /= s;
242  this->qy /= s;
243  this->qz /= s;
244  }
245  }
246 
252  public: void Axis(T _ax, T _ay, T _az, T _aa)
253  {
254  T l;
255 
256  l = _ax * _ax + _ay * _ay + _az * _az;
257 
258  if (equal<T>(l, static_cast<T>(0)))
259  {
260  this->qw = 1;
261  this->qx = 0;
262  this->qy = 0;
263  this->qz = 0;
264  }
265  else
266  {
267  _aa *= 0.5;
268  l = sin(_aa) / sqrt(l);
269  this->qw = cos(_aa);
270  this->qx = _ax * l;
271  this->qy = _ay * l;
272  this->qz = _az * l;
273  }
274 
275  this->Normalize();
276  }
277 
281  public: void Axis(const Vector3<T> &_axis, T _a)
282  {
283  this->Axis(_axis.X(), _axis.Y(), _axis.Z(), _a);
284  }
285 
291  public: void Set(T _w, T _x, T _y, T _z)
292  {
293  this->qw = _w;
294  this->qx = _x;
295  this->qy = _y;
296  this->qz = _z;
297  }
298 
304  public: void Euler(const Vector3<T> &_vec)
305  {
306  this->Euler(_vec.X(), _vec.Y(), _vec.Z());
307  }
308 
313  public: void Euler(T _roll, T _pitch, T _yaw)
314  {
315  T phi, the, psi;
316 
317  phi = _roll / T(2.0);
318  the = _pitch / T(2.0);
319  psi = _yaw / T(2.0);
320 
321  this->qw = T(cos(phi) * cos(the) * cos(psi) +
322  sin(phi) * sin(the) * sin(psi));
323  this->qx = T(sin(phi) * cos(the) * cos(psi) -
324  cos(phi) * sin(the) * sin(psi));
325  this->qy = T(cos(phi) * sin(the) * cos(psi) +
326  sin(phi) * cos(the) * sin(psi));
327  this->qz = T(cos(phi) * cos(the) * sin(psi) -
328  sin(phi) * sin(the) * cos(psi));
329 
330  this->Normalize();
331  }
332 
335  public: Vector3<T> Euler() const
336  {
337  Vector3<T> vec;
338 
339  T tol = static_cast<T>(1e-15);
340 
341  Quaternion<T> copy = *this;
342  T squ;
343  T sqx;
344  T sqy;
345  T sqz;
346 
347  copy.Normalize();
348 
349  squ = copy.qw * copy.qw;
350  sqx = copy.qx * copy.qx;
351  sqy = copy.qy * copy.qy;
352  sqz = copy.qz * copy.qz;
353 
354  // Pitch
355  T sarg = -2 * (copy.qx*copy.qz - copy.qw * copy.qy);
356  if (sarg <= T(-1.0))
357  {
358  vec.Y(T(-0.5*IGN_PI));
359  }
360  else if (sarg >= T(1.0))
361  {
362  vec.Y(T(0.5*IGN_PI));
363  }
364  else
365  {
366  vec.Y(T(asin(sarg)));
367  }
368 
369  // If the pitch angle is PI/2 or -PI/2, we can only compute
370  // the sum roll + yaw. However, any combination that gives
371  // the right sum will produce the correct orientation, so we
372  // set yaw = 0 and compute roll.
373  // pitch angle is PI/2
374  if (std::abs(sarg - 1) < tol)
375  {
376  vec.Z(0);
377  vec.X(T(atan2(2 * (copy.qx*copy.qy - copy.qz*copy.qw),
378  squ - sqx + sqy - sqz)));
379  }
380  // pitch angle is -PI/2
381  else if (std::abs(sarg + 1) < tol)
382  {
383  vec.Z(0);
384  vec.X(T(atan2(-2 * (copy.qx*copy.qy - copy.qz*copy.qw),
385  squ - sqx + sqy - sqz)));
386  }
387  else
388  {
389  // Roll
390  vec.X(T(atan2(2 * (copy.qy*copy.qz + copy.qw*copy.qx),
391  squ - sqx - sqy + sqz)));
392 
393  // Yaw
394  vec.Z(T(atan2(2 * (copy.qx*copy.qy + copy.qw*copy.qz),
395  squ + sqx - sqy - sqz)));
396  }
397 
398  return vec;
399  }
400 
404  public: static Quaternion<T> EulerToQuaternion(const Vector3<T> &_vec)
405  {
406  Quaternion<T> result;
407  result.Euler(_vec);
408  return result;
409  }
410 
416  public: static Quaternion<T> EulerToQuaternion(T _x, T _y, T _z)
417  {
418  return EulerToQuaternion(Vector3<T>(_x, _y, _z));
419  }
420 
423  public: T Roll() const
424  {
425  return this->Euler().X();
426  }
427 
430  public: T Pitch() const
431  {
432  return this->Euler().Y();
433  }
434 
437  public: T Yaw() const
438  {
439  return this->Euler().Z();
440  }
441 
445  public: void ToAxis(Vector3<T> &_axis, T &_angle) const
446  {
447  T len = this->qx*this->qx + this->qy*this->qy + this->qz*this->qz;
448  if (equal<T>(len, static_cast<T>(0)))
449  {
450  _angle = 0.0;
451  _axis.Set(1, 0, 0);
452  }
453  else
454  {
455  _angle = 2.0 * acos(this->qw);
456  T invLen = 1.0 / sqrt(len);
457  _axis.Set(this->qx*invLen, this->qy*invLen, this->qz*invLen);
458  }
459  }
460 
468  void Matrix(const Matrix3<T> &_mat)
469  {
470  const T trace = _mat(0, 0) + _mat(1, 1) + _mat(2, 2);
471  if (trace > 0.0000001)
472  {
473  qw = sqrt(1 + trace) / 2;
474  const T s = 1.0 / (4 * qw);
475  qx = (_mat(2, 1) - _mat(1, 2)) * s;
476  qy = (_mat(0, 2) - _mat(2, 0)) * s;
477  qz = (_mat(1, 0) - _mat(0, 1)) * s;
478  }
479  else if (_mat(0, 0) > _mat(1, 1) && _mat(0, 0) > _mat(2, 2))
480  {
481  qx = sqrt(1.0 + _mat(0, 0) - _mat(1, 1) - _mat(2, 2)) / 2;
482  const T s = 1.0 / (4 * qx);
483  qw = (_mat(2, 1) - _mat(1, 2)) * s;
484  qy = (_mat(1, 0) + _mat(0, 1)) * s;
485  qz = (_mat(0, 2) + _mat(2, 0)) * s;
486  }
487  else if (_mat(1, 1) > _mat(2, 2))
488  {
489  qy = sqrt(1.0 - _mat(0, 0) + _mat(1, 1) - _mat(2, 2)) / 2;
490  const T s = 1.0 / (4 * qy);
491  qw = (_mat(0, 2) - _mat(2, 0)) * s;
492  qx = (_mat(0, 1) + _mat(1, 0)) * s;
493  qz = (_mat(1, 2) + _mat(2, 1)) * s;
494  }
495  else
496  {
497  qz = sqrt(1.0 - _mat(0, 0) - _mat(1, 1) + _mat(2, 2)) / 2;
498  const T s = 1.0 / (4 * qz);
499  qw = (_mat(1, 0) - _mat(0, 1)) * s;
500  qx = (_mat(0, 2) + _mat(2, 0)) * s;
501  qy = (_mat(1, 2) + _mat(2, 1)) * s;
502  }
503  }
504 
514  public: void From2Axes(const Vector3<T> &_v1, const Vector3<T> &_v2)
515  {
516  // generally, we utilize the fact that a quat (w, x, y, z) represents
517  // rotation of angle 2*w about axis (x, y, z)
518  //
519  // so we want to take get a vector half-way between no rotation and the
520  // double rotation, which is
521  // [ (1, (0, 0, 0)) + (_v1 dot _v2, _v1 x _v2) ] / 2
522  // if _v1 and _v2 are unit quaternions
523  //
524  // since we normalize the result anyway, we can omit the division,
525  // getting the result:
526  // [ (1, (0, 0, 0)) + (_v1 dot _v2, _v1 x _v2) ].Normalized()
527  //
528  // if _v1 and _v2 are not normalized, the magnitude (1 + _v1 dot _v2)
529  // is multiplied by k = norm(_v1)*norm(_v2)
530 
531  const T kCosTheta = _v1.Dot(_v2);
532  const T k = sqrt(_v1.SquaredLength() * _v2.SquaredLength());
533 
534  if (fabs(kCosTheta/k + 1) < 1e-6)
535  {
536  // the vectors are opposite
537  // any vector orthogonal to _v1
538  Vector3<T> other;
539  {
540  const Vector3<T> _v1Abs(_v1.Abs());
541  if (_v1Abs.X() < _v1Abs.Y())
542  {
543  if (_v1Abs.X() < _v1Abs.Z())
544  {
545  other.Set(1, 0, 0);
546  }
547  else
548  {
549  other.Set(0, 0, 1);
550  }
551  }
552  else
553  {
554  if (_v1Abs.Y() < _v1Abs.Z())
555  {
556  other.Set(0, 1, 0);
557  }
558  else
559  {
560  other.Set(0, 0, 1);
561  }
562  }
563  }
564 
565  const Vector3<T> axis(_v1.Cross(other).Normalize());
566 
567  qw = 0;
568  qx = axis.X();
569  qy = axis.Y();
570  qz = axis.Z();
571  }
572  else
573  {
574  // the vectors are in general position
575  const Vector3<T> axis(_v1.Cross(_v2));
576  qw = kCosTheta + k;
577  qx = axis.X();
578  qy = axis.Y();
579  qz = axis.Z();
580  this->Normalize();
581  }
582  }
583 
586  public: void Scale(T _scale)
587  {
588  Quaternion<T> b;
589  Vector3<T> axis;
590  T angle;
591 
592  // Convert to axis-and-angle
593  this->ToAxis(axis, angle);
594  angle *= _scale;
595 
596  this->Axis(axis.X(), axis.Y(), axis.Z(), angle);
597  }
598 
602  public: Quaternion<T> operator+(const Quaternion<T> &_qt) const
603  {
604  Quaternion<T> result(this->qw + _qt.qw, this->qx + _qt.qx,
605  this->qy + _qt.qy, this->qz + _qt.qz);
606  return result;
607  }
608 
613  {
614  *this = *this + _qt;
615 
616  return *this;
617  }
618 
622  public: Quaternion<T> operator-(const Quaternion<T> &_qt) const
623  {
624  Quaternion<T> result(this->qw - _qt.qw, this->qx - _qt.qx,
625  this->qy - _qt.qy, this->qz - _qt.qz);
626  return result;
627  }
628 
633  {
634  *this = *this - _qt;
635  return *this;
636  }
637 
641  public: inline Quaternion<T> operator*(const Quaternion<T> &_q) const
642  {
643  return Quaternion<T>(
644  this->qw*_q.qw-this->qx*_q.qx-this->qy*_q.qy-this->qz*_q.qz,
645  this->qw*_q.qx+this->qx*_q.qw+this->qy*_q.qz-this->qz*_q.qy,
646  this->qw*_q.qy-this->qx*_q.qz+this->qy*_q.qw+this->qz*_q.qx,
647  this->qw*_q.qz+this->qx*_q.qy-this->qy*_q.qx+this->qz*_q.qw);
648  }
649 
653  public: Quaternion<T> operator*(const T &_f) const
654  {
655  return Quaternion<T>(this->qw*_f, this->qx*_f,
656  this->qy*_f, this->qz*_f);
657  }
658 
663  {
664  *this = *this * _qt;
665  return *this;
666  }
667 
671  public: Vector3<T> operator*(const Vector3<T> &_v) const
672  {
673  Vector3<T> uv, uuv;
674  Vector3<T> qvec(this->qx, this->qy, this->qz);
675  uv = qvec.Cross(_v);
676  uuv = qvec.Cross(uv);
677  uv *= (2.0f * this->qw);
678  uuv *= 2.0f;
679 
680  return _v + uv + uuv;
681  }
682 
686  public: bool operator==(const Quaternion<T> &_qt) const
687  {
688  return equal(this->qx, _qt.qx, static_cast<T>(0.001)) &&
689  equal(this->qy, _qt.qy, static_cast<T>(0.001)) &&
690  equal(this->qz, _qt.qz, static_cast<T>(0.001)) &&
691  equal(this->qw, _qt.qw, static_cast<T>(0.001));
692  }
693 
697  public: bool operator!=(const Quaternion<T> &_qt) const
698  {
699  return !equal(this->qx, _qt.qx, static_cast<T>(0.001)) ||
700  !equal(this->qy, _qt.qy, static_cast<T>(0.001)) ||
701  !equal(this->qz, _qt.qz, static_cast<T>(0.001)) ||
702  !equal(this->qw, _qt.qw, static_cast<T>(0.001));
703  }
704 
707  public: Quaternion<T> operator-() const
708  {
709  return Quaternion<T>(-this->qw, -this->qx, -this->qy, -this->qz);
710  }
711 
715  public: inline Vector3<T> RotateVector(const Vector3<T> &_vec) const
716  {
717  Quaternion<T> tmp(static_cast<T>(0),
718  _vec.X(), _vec.Y(), _vec.Z());
719  tmp = (*this) * (tmp * this->Inverse());
720  return Vector3<T>(tmp.qx, tmp.qy, tmp.qz);
721  }
722 
726  public: Vector3<T> RotateVectorReverse(const Vector3<T> &_vec) const
727  {
728  Quaternion<T> tmp(0.0, _vec.X(), _vec.Y(), _vec.Z());
729 
730  tmp = this->Inverse() * (tmp * (*this));
731 
732  return Vector3<T>(tmp.qx, tmp.qy, tmp.qz);
733  }
734 
737  public: bool IsFinite() const
738  {
739  // std::isfinite works with floating point values, need to explicit
740  // cast to avoid ambiguity in vc++.
741  return std::isfinite(static_cast<double>(this->qw)) &&
742  std::isfinite(static_cast<double>(this->qx)) &&
743  std::isfinite(static_cast<double>(this->qy)) &&
744  std::isfinite(static_cast<double>(this->qz));
745  }
746 
748  public: inline void Correct()
749  {
750  // std::isfinite works with floating point values, need to explicit
751  // cast to avoid ambiguity in vc++.
752  if (!std::isfinite(static_cast<double>(this->qx)))
753  this->qx = 0;
754  if (!std::isfinite(static_cast<double>(this->qy)))
755  this->qy = 0;
756  if (!std::isfinite(static_cast<double>(this->qz)))
757  this->qz = 0;
758  if (!std::isfinite(static_cast<double>(this->qw)))
759  this->qw = 1;
760 
761  if (equal(this->qw, static_cast<T>(0)) &&
762  equal(this->qx, static_cast<T>(0)) &&
763  equal(this->qy, static_cast<T>(0)) &&
764  equal(this->qz, static_cast<T>(0)))
765  {
766  this->qw = 1;
767  }
768  }
769 
772  public: Vector3<T> XAxis() const
773  {
774  T fTy = 2.0f*this->qy;
775  T fTz = 2.0f*this->qz;
776 
777  T fTwy = fTy*this->qw;
778  T fTwz = fTz*this->qw;
779  T fTxy = fTy*this->qx;
780  T fTxz = fTz*this->qx;
781  T fTyy = fTy*this->qy;
782  T fTzz = fTz*this->qz;
783 
784  return Vector3<T>(1.0f-(fTyy+fTzz), fTxy+fTwz, fTxz-fTwy);
785  }
786 
789  public: Vector3<T> YAxis() const
790  {
791  T fTx = 2.0f*this->qx;
792  T fTy = 2.0f*this->qy;
793  T fTz = 2.0f*this->qz;
794  T fTwx = fTx*this->qw;
795  T fTwz = fTz*this->qw;
796  T fTxx = fTx*this->qx;
797  T fTxy = fTy*this->qx;
798  T fTyz = fTz*this->qy;
799  T fTzz = fTz*this->qz;
800 
801  return Vector3<T>(fTxy-fTwz, 1.0f-(fTxx+fTzz), fTyz+fTwx);
802  }
803 
806  public: Vector3<T> ZAxis() const
807  {
808  T fTx = 2.0f*this->qx;
809  T fTy = 2.0f*this->qy;
810  T fTz = 2.0f*this->qz;
811  T fTwx = fTx*this->qw;
812  T fTwy = fTy*this->qw;
813  T fTxx = fTx*this->qx;
814  T fTxz = fTz*this->qx;
815  T fTyy = fTy*this->qy;
816  T fTyz = fTz*this->qy;
817 
818  return Vector3<T>(fTxz+fTwy, fTyz-fTwx, 1.0f-(fTxx+fTyy));
819  }
820 
823  public: void Round(int _precision)
824  {
825  this->qx = precision(this->qx, _precision);
826  this->qy = precision(this->qy, _precision);
827  this->qz = precision(this->qz, _precision);
828  this->qw = precision(this->qw, _precision);
829  }
830 
834  public: T Dot(const Quaternion<T> &_q) const
835  {
836  return this->qw*_q.qw + this->qx * _q.qx +
837  this->qy*_q.qy + this->qz*_q.qz;
838  }
839 
850  public: static Quaternion<T> Squad(T _fT,
851  const Quaternion<T> &_rkP, const Quaternion<T> &_rkA,
852  const Quaternion<T> &_rkB, const Quaternion<T> &_rkQ,
853  bool _shortestPath = false)
854  {
855  T fSlerpT = 2.0f*_fT*(1.0f-_fT);
856  Quaternion<T> kSlerpP = Slerp(_fT, _rkP, _rkQ, _shortestPath);
857  Quaternion<T> kSlerpQ = Slerp(_fT, _rkA, _rkB);
858  return Slerp(fSlerpT, kSlerpP, kSlerpQ);
859  }
860 
869  public: static Quaternion<T> Slerp(T _fT,
870  const Quaternion<T> &_rkP, const Quaternion<T> &_rkQ,
871  bool _shortestPath = false)
872  {
873  T fCos = _rkP.Dot(_rkQ);
874  Quaternion<T> rkT;
875 
876  // Do we need to invert rotation?
877  if (fCos < 0.0f && _shortestPath)
878  {
879  fCos = -fCos;
880  rkT = -_rkQ;
881  }
882  else
883  {
884  rkT = _rkQ;
885  }
886 
887  if (std::abs(fCos) < 1 - 1e-03)
888  {
889  // Standard case (slerp)
890  T fSin = sqrt(1 - (fCos*fCos));
891  T fAngle = atan2(fSin, fCos);
892  // FIXME: should check if (std::abs(fSin) >= 1e-3)
893  T fInvSin = 1.0f / fSin;
894  T fCoeff0 = sin((1.0f - _fT) * fAngle) * fInvSin;
895  T fCoeff1 = sin(_fT * fAngle) * fInvSin;
896  return _rkP * fCoeff0 + rkT * fCoeff1;
897  }
898  else
899  {
900  // There are two situations:
901  // 1. "rkP" and "rkQ" are very close (fCos ~= +1),
902  // so we can do a linear interpolation safely.
903  // 2. "rkP" and "rkQ" are almost inverse of each
904  // other (fCos ~= -1), there
905  // are an infinite number of possibilities interpolation.
906  // but we haven't have method to fix this case, so just use
907  // linear interpolation here.
908  Quaternion<T> t = _rkP * (1.0f - _fT) + rkT * _fT;
909  // taking the complement requires renormalisation
910  t.Normalize();
911  return t;
912  }
913  }
914 
923  public: Quaternion<T> Integrate(const Vector3<T> &_angularVelocity,
924  const T _deltaT) const
925  {
926  Quaternion<T> deltaQ;
927  Vector3<T> theta = _angularVelocity * _deltaT * 0.5;
928  T thetaMagSq = theta.SquaredLength();
929  T s;
930  if (thetaMagSq * thetaMagSq / 24.0 < MIN_D)
931  {
932  deltaQ.W() = 1.0 - thetaMagSq / 2.0;
933  s = 1.0 - thetaMagSq / 6.0;
934  }
935  else
936  {
937  double thetaMag = sqrt(thetaMagSq);
938  deltaQ.W() = cos(thetaMag);
939  s = sin(thetaMag) / thetaMag;
940  }
941  deltaQ.X() = theta.X() * s;
942  deltaQ.Y() = theta.Y() * s;
943  deltaQ.Z() = theta.Z() * s;
944  return deltaQ * (*this);
945  }
946 
949  public: inline const T &W() const
950  {
951  return this->qw;
952  }
953 
956  public: inline const T &X() const
957  {
958  return this->qx;
959  }
960 
963  public: inline const T &Y() const
964  {
965  return this->qy;
966  }
967 
970  public: inline const T &Z() const
971  {
972  return this->qz;
973  }
974 
975 
978  public: inline T &W()
979  {
980  return this->qw;
981  }
982 
985  public: inline T &X()
986  {
987  return this->qx;
988  }
989 
992  public: inline T &Y()
993  {
994  return this->qy;
995  }
996 
999  public: inline T &Z()
1000  {
1001  return this->qz;
1002  }
1003 
1006  public: inline void X(T _v)
1007  {
1008  this->qx = _v;
1009  }
1010 
1013  public: inline void Y(T _v)
1014  {
1015  this->qy = _v;
1016  }
1017 
1020  public: inline void Z(T _v)
1021  {
1022  this->qz = _v;
1023  }
1024 
1027  public: inline void W(T _v)
1028  {
1029  this->qw = _v;
1030  }
1031 
1036  public: friend std::ostream &operator<<(std::ostream &_out,
1038  {
1039  Vector3<T> v(_q.Euler());
1040  _out << precision(v.X(), 6) << " " << precision(v.Y(), 6) << " "
1041  << precision(v.Z(), 6);
1042  return _out;
1043  }
1044 
1049  public: friend std::istream &operator>>(std::istream &_in,
1051  {
1052  Angle roll, pitch, yaw;
1053 
1054  // Skip white spaces
1055  _in.setf(std::ios_base::skipws);
1056  _in >> roll >> pitch >> yaw;
1057 
1058  _q.Euler(Vector3<T>(*roll, *pitch, *yaw));
1059 
1060  return _in;
1061  }
1062 
1064  private: T qw;
1065 
1067  private: T qx;
1068 
1070  private: T qy;
1071 
1073  private: T qz;
1074  };
1075 
1076  template<typename T> const Quaternion<T>
1077  Quaternion<T>::Identity(1, 0, 0, 0);
1078 
1079  template<typename T> const Quaternion<T>
1080  Quaternion<T>::Zero(0, 0, 0, 0);
1081 
1085  }
1086  }
1087 }
1088 #endif
An angle and related functions.
Definition: Angle.hh:51
void Round(int _precision)
Round all values to _precision decimal places.
Definition: Quaternion.hh:823
void ToAxis(Vector3< T > &_axis, T &_angle) const
Return rotation as axis and angle.
Definition: Quaternion.hh:445
Quaternion< T > operator*=(const Quaternion< T > &_qt)
Multiplication operator.
Definition: Quaternion.hh:662
Quaternion(const Quaternion< T > &_qt)
Copy constructor.
Definition: Quaternion.hh:97
T setf(T... args)
Quaternion< double > Quaterniond
Definition: Quaternion.hh:1082
friend std::ostream & operator<<(std::ostream &_out, const Quaternion< T > &_q)
Stream insertion operator.
Definition: Quaternion.hh:1036
Vector3< T > Euler() const
Return the rotation in Euler angles.
Definition: Quaternion.hh:335
Quaternion()
Default Constructor.
Definition: Quaternion.hh:47
Quaternion(const Matrix3< T > &_mat)
Construct from rotation matrix.
Definition: Quaternion.hh:90
const T & W() const
Get the w component.
Definition: Quaternion.hh:949
void Matrix(const Matrix3< T > &_mat)
Set from a rotation matrix.
Definition: Quaternion.hh:468
T & W()
Get a mutable w component.
Definition: Quaternion.hh:978
void From2Axes(const Vector3< T > &_v1, const Vector3< T > &_v2)
Set this quaternion to represent rotation from vector _v1 to vector _v2, so that _v2.Normalize() == this * _v1.Normalize() holds.
Definition: Quaternion.hh:514
void Set(T _x=0, T _y=0, T _z=0)
Set the contents of the vector.
Definition: Vector3.hh:179
Quaternion< T > operator-=(const Quaternion< T > &_qt)
Subtraction operator.
Definition: Quaternion.hh:632
Quaternion< float > Quaternionf
Definition: Quaternion.hh:1083
const T & Z() const
Get the z component.
Definition: Quaternion.hh:970
Quaternion< T > operator-(const Quaternion< T > &_qt) const
Subtraction operator.
Definition: Quaternion.hh:622
Vector3< T > XAxis() const
Return the X axis.
Definition: Quaternion.hh:772
T precision(const T &_a, const unsigned int &_precision)
get value at a specified precision
Definition: Helpers.hh:587
Vector3< T > RotateVectorReverse(const Vector3< T > &_vec) const
Do the reverse rotation of a vector by this quaternion.
Definition: Quaternion.hh:726
void Normalize()
Normalize the quaternion.
Definition: Quaternion.hh:224
void Correct()
Correct any nan values in this quaternion.
Definition: Quaternion.hh:748
friend std::istream & operator>>(std::istream &_in, Quaternion< T > &_q)
Stream extraction operator.
Definition: Quaternion.hh:1049
Quaternion< T > operator+(const Quaternion< T > &_qt) const
Addition operator.
Definition: Quaternion.hh:602
Quaternion< T > operator-() const
Unary minus operator.
Definition: Quaternion.hh:707
Quaternion< T > Log() const
Return the logarithm.
Definition: Quaternion.hh:161
const T & X() const
Get the x component.
Definition: Quaternion.hh:956
bool equal(const T &_a, const T &_b, const T &_epsilon=T(1e-6))
check if two values are equal, within a tolerance
Definition: Helpers.hh:553
Vector3< T > ZAxis() const
Return the Z axis.
Definition: Quaternion.hh:806
Vector3< T > RotateVector(const Vector3< T > &_vec) const
Rotate a vector using the quaternion.
Definition: Quaternion.hh:715
void Y(T _v)
Set the y component.
Definition: Quaternion.hh:1013
const T & Y() const
Get the y component.
Definition: Quaternion.hh:963
void Z(T _v)
Set the z component.
Definition: Quaternion.hh:1020
static const double MIN_D
Double min value. This value will be similar to 2.22507e-308.
Definition: Helpers.hh:257
bool IsFinite() const
See if a quaternion is finite (e.g., not nan)
Definition: Quaternion.hh:737
STL class.
Quaternion< T > & operator=(const Quaternion< T > &_qt)
Equal operator.
Definition: Quaternion.hh:110
Quaternion(const T &_w, const T &_x, const T &_y, const T &_z)
Constructor.
Definition: Quaternion.hh:59
T X() const
Get the x value.
Definition: Vector3.hh:648
void Set(T _w, T _x, T _y, T _z)
Set this quaternion from 4 floating numbers.
Definition: Quaternion.hh:291
static Quaternion< T > EulerToQuaternion(const Vector3< T > &_vec)
Convert euler angles to quatern.
Definition: Quaternion.hh:404
static Quaternion< T > EulerToQuaternion(T _x, T _y, T _z)
Convert euler angles to quatern.
Definition: Quaternion.hh:416
T Z() const
Get the z value.
Definition: Vector3.hh:662
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:850
void Axis(T _ax, T _ay, T _az, T _aa)
Set the quaternion from an axis and angle.
Definition: Quaternion.hh:252
T Y() const
Get the y value.
Definition: Vector3.hh:655
T Dot(const Quaternion< T > &_q) const
Dot product.
Definition: Quaternion.hh:834
Vector3 Abs() const
Get the absolute value of the vector.
Definition: Vector3.hh:223
Quaternion(const Vector3< T > &_axis, const T &_angle)
Constructor from axis angle.
Definition: Quaternion.hh:75
void X(T _v)
Set the x component.
Definition: Quaternion.hh:1006
void Euler(const Vector3< T > &_vec)
Set the quaternion from Euler angles. The order of operations is roll, pitch, yaw around a fixed body...
Definition: Quaternion.hh:304
Quaternion< T > operator*(const T &_f) const
Multiplication operator by a scalar.
Definition: Quaternion.hh:653
Quaternion< T > operator*(const Quaternion< T > &_q) const
Multiplication operator.
Definition: Quaternion.hh:641
A 3x3 matrix class.
Definition: Matrix3.hh:40
T Pitch() const
Get the Euler pitch angle in radians.
Definition: Quaternion.hh:430
T & Y()
Get a mutable y component.
Definition: Quaternion.hh:992
T Dot(const Vector3< T > &_v) const
Return the dot product of this vector and another vector.
Definition: Vector3.hh:199
T & X()
Get a mutable x component.
Definition: Quaternion.hh:985
Vector3 Cross(const Vector3< T > &_v) const
Return the cross product of this vector with another vector.
Definition: Vector3.hh:189
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:869
bool operator!=(const Quaternion< T > &_qt) const
Not equal to operator.
Definition: Quaternion.hh:697
static const Quaternion Identity
math::Quaternion(1, 0, 0, 0)
Definition: Quaternion.hh:41
T isfinite(T... args)
void Scale(T _scale)
Scale a Quaternion<T>ion.
Definition: Quaternion.hh:586
void W(T _v)
Set the w component.
Definition: Quaternion.hh:1027
T Roll() const
Get the Euler roll angle in radians.
Definition: Quaternion.hh:423
T SquaredLength() const
Return the square of the length (magnitude) of the vector.
Definition: Vector3.hh:124
void Invert()
Invert the quaternion.
Definition: Quaternion.hh:121
bool operator==(const Quaternion< T > &_qt) const
Equal to operator.
Definition: Quaternion.hh:686
~Quaternion()
Destructor.
Definition: Quaternion.hh:106
The Vector3 class represents the generic vector containing 3 elements. Since it&#39;s commonly used to ke...
Definition: Vector3.hh:40
Quaternion< int > Quaternioni
Definition: Quaternion.hh:1084
Vector3< T > YAxis() const
Return the Y axis.
Definition: Quaternion.hh:789
static const Quaternion Zero
math::Quaternion(0, 0, 0, 0)
Definition: Quaternion.hh:44
Quaternion(const Vector3< T > &_rpy)
Constructor.
Definition: Quaternion.hh:82
void Euler(T _roll, T _pitch, T _yaw)
Set the quaternion from Euler angles.
Definition: Quaternion.hh:313
T & Z()
Get a mutable z component.
Definition: Quaternion.hh:999
Quaternion< T > operator+=(const Quaternion< T > &_qt)
Addition operator.
Definition: Quaternion.hh:612
Quaternion(const T &_roll, const T &_pitch, const T &_yaw)
Constructor from Euler angles in radians.
Definition: Quaternion.hh:67
Definition: Angle.hh:42
Quaternion< T > Integrate(const Vector3< T > &_angularVelocity, const T _deltaT) const
Integrate quaternion for constant angular velocity vector along specified interval _deltaT...
Definition: Quaternion.hh:923
Quaternion< T > Exp() const
Return the exponent.
Definition: Quaternion.hh:193
A quaternion class.
Definition: Matrix3.hh:35
Quaternion< T > Inverse() const
Get the inverse of this quaternion.
Definition: Quaternion.hh:132
#define IGN_PI
Define IGN_PI, IGN_PI_2, and IGN_PI_4. This was put here for Windows support.
Definition: Helpers.hh:181
STL class.
Vector3< T > operator*(const Vector3< T > &_v) const
Vector3 multiplication operator.
Definition: Quaternion.hh:671
void Axis(const Vector3< T > &_axis, T _a)
Set the quaternion from an axis and angle.
Definition: Quaternion.hh:281
T Yaw() const
Get the Euler yaw angle in radians.
Definition: Quaternion.hh:437