17 #ifndef IGNITION_MATH_QUATERNION_HH_ 18 #define IGNITION_MATH_QUATERNION_HH_ 29 template <
typename T>
class Matrix3;
44 : qw(1), qx(0), qy(0), qz(0)
55 public:
Quaternion(
const T &_w,
const T &_x,
const T &_y,
const T &_z)
56 : qw(_w), qx(_x), qy(_y), qz(_z)
63 public:
Quaternion(
const T &_roll,
const T &_pitch,
const T &_yaw)
73 this->
Axis(_axis, _angle);
121 this->qx = -this->qx;
122 this->qy = -this->qy;
123 this->qz = -this->qz;
134 s = q.qw * q.qw + q.qx * q.qx + q.qy * q.qy + q.qz * q.qz;
136 if (equal<T>(s, static_cast<T>(0)))
166 if (std::abs(this->qw) < 1.0)
168 T fAngle = acos(this->qw);
169 T fSin = sin(fAngle);
170 if (std::abs(fSin) >= 1e-3)
172 T fCoeff = fAngle/fSin;
173 result.qx = fCoeff*this->qx;
174 result.qy = fCoeff*this->qy;
175 result.qz = fCoeff*this->qz;
180 result.qx = this->qx;
181 result.qy = this->qy;
182 result.qz = this->qz;
195 T fAngle = sqrt(this->qx*this->qx+
196 this->qy*this->qy+this->qz*this->qz);
197 T fSin = sin(fAngle);
200 result.qw = cos(fAngle);
202 if (std::abs(fSin) >= 1e-3)
204 T fCoeff = fSin/fAngle;
205 result.qx = fCoeff*this->qx;
206 result.qy = fCoeff*this->qy;
207 result.qz = fCoeff*this->qz;
211 result.qx = this->qx;
212 result.qy = this->qy;
213 result.qz = this->qz;
224 s = T(sqrt(this->qw * this->qw + this->qx * this->qx +
225 this->qy * this->qy + this->qz * this->qz));
227 if (equal<T>(s, static_cast<T>(0)))
248 public:
void Axis(T _ax, T _ay, T _az, T _aa)
252 l = _ax * _ax + _ay * _ay + _az * _az;
254 if (equal<T>(l, static_cast<T>(0)))
264 l = sin(_aa) / sqrt(l);
279 this->
Axis(_axis.
X(), _axis.
Y(), _axis.
Z(), _a);
287 public:
void Set(T _w, T _x, T _y, T _z)
302 this->
Euler(_vec.
X(), _vec.
Y(), _vec.
Z());
309 public:
void Euler(T _roll, T _pitch, T _yaw)
313 phi = _roll / T(2.0);
314 the = _pitch / T(2.0);
317 this->qw = T(cos(phi) * cos(the) * cos(psi) +
318 sin(phi) * sin(the) * sin(psi));
319 this->qx = T(sin(phi) * cos(the) * cos(psi) -
320 cos(phi) * sin(the) * sin(psi));
321 this->qy = T(cos(phi) * sin(the) * cos(psi) +
322 sin(phi) * cos(the) * sin(psi));
323 this->qz = T(cos(phi) * cos(the) * sin(psi) -
324 sin(phi) * sin(the) * cos(psi));
335 T tol =
static_cast<T
>(1e-15);
345 squ = copy.qw * copy.qw;
346 sqx = copy.qx * copy.qx;
347 sqy = copy.qy * copy.qy;
348 sqz = copy.qz * copy.qz;
351 T sarg = -2 * (copy.qx*copy.qz - copy.qw * copy.qy);
352 vec.
Y(sarg <= T(-1.0) ? T(-0.5*
IGN_PI) :
353 (sarg >= T(1.0) ? T(0.5*
IGN_PI) : T(asin(sarg))));
360 if (std::abs(sarg - 1) < tol)
363 vec.
X(T(atan2(2 * (copy.qx*copy.qy - copy.qz*copy.qw),
364 squ - sqx + sqy - sqz)));
367 else if (std::abs(sarg + 1) < tol)
370 vec.
X(T(atan2(-2 * (copy.qx*copy.qy - copy.qz*copy.qw),
371 squ - sqx + sqy - sqz)));
376 vec.
X(T(atan2(2 * (copy.qy*copy.qz + copy.qw*copy.qx),
377 squ - sqx - sqy + sqz)));
380 vec.
Z(T(atan2(2 * (copy.qx*copy.qy + copy.qw*copy.qz),
381 squ + sqx - sqy - sqz)));
411 return this->
Euler().X();
418 return this->
Euler().Y();
425 return this->
Euler().Z();
433 T len = this->qx*this->qx + this->qy*this->qy + this->qz*this->qz;
434 if (equal<T>(len, static_cast<T>(0)))
441 _angle = 2.0 * acos(this->qw);
442 T invLen = 1.0 / sqrt(len);
443 _axis.
Set(this->qx*invLen, this->qy*invLen, this->qz*invLen);
456 const T trace = _mat(0, 0) + _mat(1, 1) + _mat(2, 2);
457 if (trace > 0.0000001)
459 qw = sqrt(1 + trace) / 2;
460 const T s = 1.0 / (4 * qw);
461 qx = (_mat(2, 1) - _mat(1, 2)) * s;
462 qy = (_mat(0, 2) - _mat(2, 0)) * s;
463 qz = (_mat(1, 0) - _mat(0, 1)) * s;
465 else if (_mat(0, 0) > _mat(1, 1) && _mat(0, 0) > _mat(2, 2))
467 qx = sqrt(1.0 + _mat(0, 0) - _mat(1, 1) - _mat(2, 2)) / 2;
468 const T s = 1.0 / (4 * qx);
469 qw = (_mat(2, 1) - _mat(1, 2)) * s;
470 qy = (_mat(1, 0) + _mat(0, 1)) * s;
471 qz = (_mat(0, 2) + _mat(2, 0)) * s;
473 else if (_mat(1, 1) > _mat(2, 2))
475 qy = sqrt(1.0 - _mat(0, 0) + _mat(1, 1) - _mat(2, 2)) / 2;
476 const T s = 1.0 / (4 * qy);
477 qw = (_mat(0, 2) - _mat(2, 0)) * s;
478 qx = (_mat(0, 1) + _mat(1, 0)) * s;
479 qz = (_mat(1, 2) + _mat(2, 1)) * s;
483 qz = sqrt(1.0 - _mat(0, 0) - _mat(1, 1) + _mat(2, 2)) / 2;
484 const T s = 1.0 / (4 * qz);
485 qw = (_mat(1, 0) - _mat(0, 1)) * s;
486 qx = (_mat(0, 2) + _mat(2, 0)) * s;
487 qy = (_mat(1, 2) + _mat(2, 1)) * s;
517 const T kCosTheta = _v1.
Dot(_v2);
520 if (fabs(kCosTheta/k + 1) < 1e-6)
527 if (_v1Abs.X() < _v1Abs.Y())
529 if (_v1Abs.X() < _v1Abs.Z())
540 if (_v1Abs.Y() < _v1Abs.Z())
579 this->
ToAxis(axis, angle);
582 this->
Axis(axis.
X(), axis.
Y(), axis.
Z(), angle);
591 this->qy + _qt.qy, this->qz + _qt.qz);
611 this->qy - _qt.qy, this->qz - _qt.qz);
630 this->qw*_q.qw-this->qx*_q.qx-this->qy*_q.qy-this->qz*_q.qz,
631 this->qw*_q.qx+this->qx*_q.qw+this->qy*_q.qz-this->qz*_q.qy,
632 this->qw*_q.qy-this->qx*_q.qz+this->qy*_q.qw+this->qz*_q.qx,
633 this->qw*_q.qz+this->qx*_q.qy-this->qy*_q.qx+this->qz*_q.qw);
642 this->qy*_f, this->qz*_f);
660 Vector3<T> qvec(this->qx, this->qy, this->qz);
662 uuv = qvec.
Cross(uv);
663 uv *= (2.0f * this->qw);
666 return _v + uv + uuv;
674 return equal(this->qx, _qt.qx, static_cast<T>(0.001)) &&
675 equal(this->qy, _qt.qy, static_cast<T>(0.001)) &&
676 equal(this->qz, _qt.qz, static_cast<T>(0.001)) &&
677 equal(this->qw, _qt.qw, static_cast<T>(0.001));
685 return !
equal(this->qx, _qt.qx, static_cast<T>(0.001)) ||
686 !
equal(this->qy, _qt.qy, static_cast<T>(0.001)) ||
687 !
equal(this->qz, _qt.qz, static_cast<T>(0.001)) ||
688 !
equal(this->qw, _qt.qw, static_cast<T>(0.001));
695 return Quaternion<T>(-this->qw, -this->qx, -this->qy, -this->qz);
704 _vec.
X(), _vec.
Y(), _vec.
Z());
705 tmp = (*this) * (tmp * this->
Inverse());
716 tmp = this->
Inverse() * (tmp * (*this));
727 return std::isfinite(static_cast<double>(this->qw)) &&
728 std::isfinite(static_cast<double>(this->qx)) &&
729 std::isfinite(static_cast<double>(this->qy)) &&
730 std::isfinite(static_cast<double>(this->qz));
738 if (!std::isfinite(static_cast<double>(this->qx)))
740 if (!std::isfinite(static_cast<double>(this->qy)))
742 if (!std::isfinite(static_cast<double>(this->qz)))
744 if (!std::isfinite(static_cast<double>(this->qw)))
747 if (
equal(this->qw, static_cast<T>(0)) &&
748 equal(this->qx, static_cast<T>(0)) &&
749 equal(this->qy, static_cast<T>(0)) &&
750 equal(this->qz, static_cast<T>(0)))
760 T fTy = 2.0f*this->qy;
761 T fTz = 2.0f*this->qz;
763 T fTwy = fTy*this->qw;
764 T fTwz = fTz*this->qw;
765 T fTxy = fTy*this->qx;
766 T fTxz = fTz*this->qx;
767 T fTyy = fTy*this->qy;
768 T fTzz = fTz*this->qz;
770 return Vector3<T>(1.0f-(fTyy+fTzz), fTxy+fTwz, fTxz-fTwy);
777 T fTx = 2.0f*this->qx;
778 T fTy = 2.0f*this->qy;
779 T fTz = 2.0f*this->qz;
780 T fTwx = fTx*this->qw;
781 T fTwz = fTz*this->qw;
782 T fTxx = fTx*this->qx;
783 T fTxy = fTy*this->qx;
784 T fTyz = fTz*this->qy;
785 T fTzz = fTz*this->qz;
787 return Vector3<T>(fTxy-fTwz, 1.0f-(fTxx+fTzz), fTyz+fTwx);
794 T fTx = 2.0f*this->qx;
795 T fTy = 2.0f*this->qy;
796 T fTz = 2.0f*this->qz;
797 T fTwx = fTx*this->qw;
798 T fTwy = fTy*this->qw;
799 T fTxx = fTx*this->qx;
800 T fTxz = fTz*this->qx;
801 T fTyy = fTy*this->qy;
802 T fTyz = fTz*this->qy;
804 return Vector3<T>(fTxz+fTwy, fTyz-fTwx, 1.0f-(fTxx+fTyy));
811 this->qx =
precision(this->qx, _precision);
812 this->qy =
precision(this->qy, _precision);
813 this->qz =
precision(this->qz, _precision);
814 this->qw =
precision(this->qw, _precision);
822 return this->qw*_q.qw + this->qx * _q.qx +
823 this->qy*_q.qy + this->qz*_q.qz;
839 bool _shortestPath =
false)
841 T fSlerpT = 2.0f*_fT*(1.0f-_fT);
844 return Slerp(fSlerpT, kSlerpP, kSlerpQ);
857 bool _shortestPath =
false)
859 T fCos = _rkP.Dot(_rkQ);
863 if (fCos < 0.0f && _shortestPath)
873 if (std::abs(fCos) < 1 - 1e-03)
876 T fSin = sqrt(1 - (fCos*fCos));
877 T fAngle = atan2(fSin, fCos);
879 T fInvSin = 1.0f / fSin;
880 T fCoeff0 = sin((1.0f - _fT) * fAngle) * fInvSin;
881 T fCoeff1 = sin(_fT * fAngle) * fInvSin;
882 return _rkP * fCoeff0 + rkT * fCoeff1;
910 const T _deltaT)
const 913 Vector3<T> theta = _angularVelocity * _deltaT * 0.5;
916 if (thetaMagSq * thetaMagSq / 24.0 <
MIN_D)
918 deltaQ.W() = 1.0 - thetaMagSq / 2.0;
919 s = 1.0 - thetaMagSq / 6.0;
923 double thetaMag = sqrt(thetaMagSq);
924 deltaQ.W() = cos(thetaMag);
925 s = sin(thetaMag) / thetaMag;
927 deltaQ.X() = theta.
X() * s;
928 deltaQ.Y() = theta.
Y() * s;
929 deltaQ.Z() = theta.
Z() * s;
930 return deltaQ * (*this);
935 public:
inline const T &
W()
const 942 public:
inline const T &
X()
const 949 public:
inline const T &
Y()
const 956 public:
inline const T &
Z()
const 964 public:
inline T &
W()
971 public:
inline T &
X()
978 public:
inline T &
Y()
985 public:
inline T &
Z()
992 public:
inline void X(T _v)
999 public:
inline void Y(T _v)
1006 public:
inline void Z(T _v)
1013 public:
inline void W(T _v)
1038 Angle roll, pitch, yaw;
1041 _in.setf(std::ios_base::skipws);
1042 _in >> roll >> pitch >> yaw;
1062 template<
typename T>
const Quaternion<T>
1065 template<
typename T>
const Quaternion<T>
An angle and related functions.
Definition: Angle.hh:44
Quaternion< double > Quaterniond
Definition: Quaternion.hh:1068
const T & W() const
Get the w component.
Definition: Quaternion.hh:935
T X() const
Get the x value.
Definition: Vector3.hh:635
void Round(int _precision)
Round all values to _precision decimal places.
Definition: Quaternion.hh:809
void Y(T _v)
Set the y component.
Definition: Quaternion.hh:999
const T & Z() const
Get the z component.
Definition: Quaternion.hh:956
T Roll() const
Get the Euler roll angle in radians.
Definition: Quaternion.hh:409
Quaternion(const Vector3< T > &_axis, const T &_angle)
Constructor from axis angle.
Definition: Quaternion.hh:71
void Set(T _x=0, T _y=0, T _z=0)
Set the contents of the vector.
Definition: Vector3.hh:175
~Quaternion()
Destructor.
Definition: Quaternion.hh:102
void X(T _v)
Set the x component.
Definition: Quaternion.hh:992
Quaternion< T > Exp() const
Return the exponent.
Definition: Quaternion.hh:189
void Euler(T _roll, T _pitch, T _yaw)
Set the quaternion from Euler angles.
Definition: Quaternion.hh:309
static const Quaternion Zero
math::Quaternion(0, 0, 0, 0)
Definition: Quaternion.hh:40
Quaternion(const Vector3< T > &_rpy)
Constructor.
Definition: Quaternion.hh:78
T precision(const T &_a, const unsigned int &_precision)
get value at a specified precision
Definition: Helpers.hh:576
Quaternion< T > operator+(const Quaternion< T > &_qt) const
Addition operator.
Definition: Quaternion.hh:588
void Z(T _v)
Set the z component.
Definition: Quaternion.hh:1006
void Invert()
Invert the quaternion.
Definition: Quaternion.hh:117
T & X()
Get a mutable x component.
Definition: Quaternion.hh:971
Vector3< T > RotateVector(const Vector3< T > &_vec) const
Rotate a vector using the quaternion.
Definition: Quaternion.hh:701
Quaternion< float > Quaternionf
Definition: Quaternion.hh:1069
friend std::istream & operator>>(std::istream &_in, ignition::math::Quaternion< T > &_q)
Stream extraction operator.
Definition: Quaternion.hh:1035
Quaternion< T > operator-() const
Unary minus operator.
Definition: Quaternion.hh:693
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:836
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:542
Vector3 Abs() const
Get the absolute value of the vector.
Definition: Vector3.hh:219
T & Y()
Get a mutable y component.
Definition: Quaternion.hh:978
bool operator!=(const Quaternion< T > &_qt) const
Not equal to operator.
Definition: Quaternion.hh:683
Vector3< T > ZAxis() const
Return the Z axis.
Definition: Quaternion.hh:792
void ToAxis(Vector3< T > &_axis, T &_angle) const
Return rotation as axis and angle.
Definition: Quaternion.hh:431
Quaternion< T > Log() const
Return the logarithm.
Definition: Quaternion.hh:157
Quaternion< T > operator+=(const Quaternion< T > &_qt)
Addition operator.
Definition: Quaternion.hh:598
void Correct()
Correct any nan values in this quaternion.
Definition: Quaternion.hh:734
Quaternion(const Quaternion< T > &_qt)
Copy constructor.
Definition: Quaternion.hh:93
static const double MIN_D
Double min value. This value will be similar to 2.22507e-308.
Definition: Helpers.hh:246
static Quaternion< T > EulerToQuaternion(const Vector3< T > &_vec)
Convert euler angles to quatern.
Definition: Quaternion.hh:390
T Pitch() const
Get the Euler pitch angle in radians.
Definition: Quaternion.hh:416
T Dot(const Vector3< T > &_v) const
Return the dot product of this vector and another vector.
Definition: Vector3.hh:195
Quaternion< T > & operator=(const Quaternion< T > &_qt)
Equal operator.
Definition: Quaternion.hh:106
T SquaredLength() const
Return the square of the length (magnitude) of the vector.
Definition: Vector3.hh:120
void Axis(const Vector3< T > &_axis, T _a)
Set the quaternion from an axis and angle.
Definition: Quaternion.hh:277
T Yaw() const
Get the Euler yaw angle in radians.
Definition: Quaternion.hh:423
void Axis(T _ax, T _ay, T _az, T _aa)
Set the quaternion from an axis and angle.
Definition: Quaternion.hh:248
A 3x3 matrix class.
Definition: Matrix3.hh:35
Quaternion(const T &_w, const T &_x, const T &_y, const T &_z)
Constructor.
Definition: Quaternion.hh:55
Quaternion< T > operator*(const Quaternion< T > &_q) const
Multiplication operator.
Definition: Quaternion.hh:627
static const Quaternion Identity
math::Quaternion(1, 0, 0, 0)
Definition: Quaternion.hh:37
const T & Y() const
Get the y component.
Definition: Quaternion.hh:949
friend std::ostream & operator<<(std::ostream &_out, const ignition::math::Quaternion< T > &_q)
Stream insertion operator.
Definition: Quaternion.hh:1022
bool operator==(const Quaternion< T > &_qt) const
Equal to operator.
Definition: Quaternion.hh:672
bool IsFinite() const
See if a quaternion is finite (e.g., not nan)
Definition: Quaternion.hh:723
T Dot(const Quaternion< T > &_q) const
Dot product.
Definition: Quaternion.hh:820
T Y() const
Get the y value.
Definition: Vector3.hh:642
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:500
T & W()
Get a mutable w component.
Definition: Quaternion.hh:964
void Scale(T _scale)
Scale a Quaternion<T>ion.
Definition: Quaternion.hh:572
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:855
Quaternion(const Matrix3< T > &_mat)
Construct from rotation matrix.
Definition: Quaternion.hh:86
T & Z()
Get a mutable z component.
Definition: Quaternion.hh:985
Quaternion< T > Inverse() const
Get the inverse of this quaternion.
Definition: Quaternion.hh:128
Vector3< T > Euler() const
Return the rotation in Euler angles.
Definition: Quaternion.hh:331
Vector3< T > XAxis() const
Return the X axis.
Definition: Quaternion.hh:758
const T & X() const
Get the x component.
Definition: Quaternion.hh:942
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:36
Vector3< T > YAxis() const
Return the Y axis.
Definition: Quaternion.hh:775
Vector3< T > operator*(const Vector3< T > &_v) const
Vector3 multiplication operator.
Definition: Quaternion.hh:657
T Z() const
Get the z value.
Definition: Vector3.hh:649
Vector3 Cross(const Vector3< T > &_v) const
Return the cross product of this vector with another vector.
Definition: Vector3.hh:185
void W(T _v)
Set the w component.
Definition: Quaternion.hh:1013
Quaternion< T > operator*=(const Quaternion< T > &qt)
Multiplication operator.
Definition: Quaternion.hh:648
Quaternion< T > operator-(const Quaternion< T > &_qt) const
Subtraction operator.
Definition: Quaternion.hh:608
Quaternion< int > Quaternioni
Definition: Quaternion.hh:1070
void Euler(const Vector3< T > &_vec)
Set the quaternion from Euler angles.
Definition: Quaternion.hh:300
Quaternion()
Default Constructor.
Definition: Quaternion.hh:43
void Matrix(const Matrix3< T > &_mat)
Set from a rotation matrix.
Definition: Quaternion.hh:454
Vector3< T > RotateVectorReverse(Vector3< T > _vec) const
Do the reverse rotation of a vector by this quaternion.
Definition: Quaternion.hh:712
void Normalize()
Normalize the quaternion.
Definition: Quaternion.hh:220
A quaternion class.
Definition: Matrix3.hh:30
Quaternion< T > operator-=(const Quaternion< T > &_qt)
Subtraction operator.
Definition: Quaternion.hh:618
#define IGN_PI
Define IGN_PI, IGN_PI_2, and IGN_PI_4.
Definition: Helpers.hh:173
Quaternion(const T &_roll, const T &_pitch, const T &_yaw)
Constructor from Euler angles in radians.
Definition: Quaternion.hh:63
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:909
static Quaternion< T > EulerToQuaternion(T _x, T _y, T _z)
Convert euler angles to quatern.
Definition: Quaternion.hh:402
Quaternion< T > operator*(const T &_f) const
Multiplication operator by a scalar.
Definition: Quaternion.hh:639
void Set(T _w, T _x, T _y, T _z)
Set this quaternion from 4 floating numbers.
Definition: Quaternion.hh:287