17 #ifndef IGNITION_MATH_QUATERNION_HH_ 18 #define IGNITION_MATH_QUATERNION_HH_ 24 #include <ignition/math/config.hh> 31 inline namespace IGNITION_MATH_VERSION_NAMESPACE {
33 template <
typename T>
class Matrix3;
48 : qw(1), qx(0), qy(0), qz(0)
59 public:
Quaternion(
const T &_w,
const T &_x,
const T &_y,
const T &_z)
60 : qw(_w), qx(_x), qy(_y), qz(_z)
67 public:
Quaternion(
const T &_roll,
const T &_pitch,
const T &_yaw)
77 this->Axis(_axis, _angle);
125 this->qx = -this->qx;
126 this->qy = -this->qy;
127 this->qz = -this->qz;
138 s = q.qw * q.qw + q.qx * q.qx + q.qy * q.qy + q.qz * q.qz;
140 if (equal<T>(s, static_cast<T>(0)))
170 if (std::abs(this->qw) < 1.0)
172 T fAngle = acos(this->qw);
173 T fSin = sin(fAngle);
174 if (std::abs(fSin) >= 1e-3)
176 T fCoeff = fAngle/fSin;
177 result.qx = fCoeff*this->qx;
178 result.qy = fCoeff*this->qy;
179 result.qz = fCoeff*this->qz;
184 result.qx = this->qx;
185 result.qy = this->qy;
186 result.qz = this->qz;
199 T fAngle = sqrt(this->qx*this->qx+
200 this->qy*this->qy+this->qz*this->qz);
201 T fSin = sin(fAngle);
204 result.qw = cos(fAngle);
206 if (std::abs(fSin) >= 1e-3)
208 T fCoeff = fSin/fAngle;
209 result.qx = fCoeff*this->qx;
210 result.qy = fCoeff*this->qy;
211 result.qz = fCoeff*this->qz;
215 result.qx = this->qx;
216 result.qy = this->qy;
217 result.qz = this->qz;
228 s = T(sqrt(this->qw * this->qw + this->qx * this->qx +
229 this->qy * this->qy + this->qz * this->qz));
231 if (equal<T>(s, static_cast<T>(0)))
252 public:
void Axis(T _ax, T _ay, T _az, T _aa)
256 l = _ax * _ax + _ay * _ay + _az * _az;
258 if (equal<T>(l, static_cast<T>(0)))
268 l = sin(_aa) / sqrt(l);
283 this->Axis(_axis.
X(), _axis.
Y(), _axis.
Z(), _a);
291 public:
void Set(T _w, T _x, T _y, T _z)
306 this->Euler(_vec.
X(), _vec.
Y(), _vec.
Z());
313 public:
void Euler(T _roll, T _pitch, T _yaw)
317 phi = _roll / T(2.0);
318 the = _pitch / T(2.0);
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));
339 T tol =
static_cast<T
>(1e-15);
349 squ = copy.qw * copy.qw;
350 sqx = copy.qx * copy.qx;
351 sqy = copy.qy * copy.qy;
352 sqz = copy.qz * copy.qz;
355 T sarg = -2 * (copy.qx*copy.qz - copy.qw * copy.qy);
360 else if (sarg >= T(1.0))
366 vec.
Y(T(asin(sarg)));
374 if (std::abs(sarg - 1) < tol)
377 vec.
X(T(atan2(2 * (copy.qx*copy.qy - copy.qz*copy.qw),
378 squ - sqx + sqy - sqz)));
381 else if (std::abs(sarg + 1) < tol)
384 vec.
X(T(atan2(-2 * (copy.qx*copy.qy - copy.qz*copy.qw),
385 squ - sqx + sqy - sqz)));
390 vec.
X(T(atan2(2 * (copy.qy*copy.qz + copy.qw*copy.qx),
391 squ - sqx - sqy + sqz)));
394 vec.
Z(T(atan2(2 * (copy.qx*copy.qy + copy.qw*copy.qz),
395 squ + sqx - sqy - sqz)));
418 return EulerToQuaternion(
Vector3<T>(_x, _y, _z));
425 return this->Euler().X();
432 return this->Euler().Y();
439 return this->Euler().Z();
447 T len = this->qx*this->qx + this->qy*this->qy + this->qz*this->qz;
448 if (equal<T>(len, static_cast<T>(0)))
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);
470 const T trace = _mat(0, 0) + _mat(1, 1) + _mat(2, 2);
471 if (trace > 0.0000001)
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;
479 else if (_mat(0, 0) > _mat(1, 1) && _mat(0, 0) > _mat(2, 2))
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;
487 else if (_mat(1, 1) > _mat(2, 2))
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;
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;
531 const T kCosTheta = _v1.
Dot(_v2);
534 if (fabs(kCosTheta/k + 1) < 1e-6)
541 if (_v1Abs.X() < _v1Abs.Y())
543 if (_v1Abs.X() < _v1Abs.Z())
554 if (_v1Abs.Y() < _v1Abs.Z())
593 this->ToAxis(axis, angle);
596 this->Axis(axis.
X(), axis.
Y(), axis.
Z(), angle);
605 this->qy + _qt.qy, this->qz + _qt.qz);
625 this->qy - _qt.qy, this->qz - _qt.qz);
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);
656 this->qy*_f, this->qz*_f);
674 Vector3<T> qvec(this->qx, this->qy, this->qz);
676 uuv = qvec.
Cross(uv);
677 uv *= (2.0f * this->qw);
680 return _v + uv + uuv;
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));
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));
709 return Quaternion<T>(-this->qw, -this->qx, -this->qy, -this->qz);
718 _vec.
X(), _vec.
Y(), _vec.
Z());
719 tmp = (*this) * (tmp * this->Inverse());
730 tmp = this->Inverse() * (tmp * (*this));
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)))
774 T fTy = 2.0f*this->qy;
775 T fTz = 2.0f*this->qz;
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;
784 return Vector3<T>(1.0f-(fTyy+fTzz), fTxy+fTwz, fTxz-fTwy);
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;
801 return Vector3<T>(fTxy-fTwz, 1.0f-(fTxx+fTzz), fTyz+fTwx);
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;
818 return Vector3<T>(fTxz+fTwy, fTyz-fTwx, 1.0f-(fTxx+fTyy));
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);
836 return this->qw*_q.qw + this->qx * _q.qx +
837 this->qy*_q.qy + this->qz*_q.qz;
853 bool _shortestPath =
false)
855 T fSlerpT = 2.0f*_fT*(1.0f-_fT);
856 Quaternion<T> kSlerpP = Slerp(_fT, _rkP, _rkQ, _shortestPath);
858 return Slerp(fSlerpT, kSlerpP, kSlerpQ);
871 bool _shortestPath =
false)
873 T fCos = _rkP.Dot(_rkQ);
877 if (fCos < 0.0f && _shortestPath)
887 if (std::abs(fCos) < 1 - 1e-03)
890 T fSin = sqrt(1 - (fCos*fCos));
891 T fAngle = atan2(fSin, fCos);
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;
924 const T _deltaT)
const 927 Vector3<T> theta = _angularVelocity * _deltaT * 0.5;
930 if (thetaMagSq * thetaMagSq / 24.0 <
MIN_D)
932 deltaQ.W() = 1.0 - thetaMagSq / 2.0;
933 s = 1.0 - thetaMagSq / 6.0;
937 double thetaMag = sqrt(thetaMagSq);
938 deltaQ.W() = cos(thetaMag);
939 s = sin(thetaMag) / thetaMag;
941 deltaQ.X() = theta.
X() * s;
942 deltaQ.Y() = theta.
Y() * s;
943 deltaQ.Z() = theta.
Z() * s;
944 return deltaQ * (*this);
949 public:
inline const T &
W()
const 956 public:
inline const T &
X()
const 963 public:
inline const T &
Y()
const 970 public:
inline const T &
Z()
const 978 public:
inline T &
W()
985 public:
inline T &
X()
992 public:
inline T &
Y()
999 public:
inline T &
Z()
1006 public:
inline void X(T _v)
1013 public:
inline void Y(T _v)
1020 public:
inline void Z(T _v)
1027 public:
inline void W(T _v)
1052 Angle roll, pitch, yaw;
1055 _in.
setf(std::ios_base::skipws);
1056 _in >> roll >> pitch >> yaw;
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
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
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
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'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
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
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