17 #ifndef _IGNITION_QUATERNION_HH_
18 #define _IGNITION_QUATERNION_HH_
38 : qw(1), qx(0), qy(0), qz(0)
49 public:
Quaternion(
const T &_w,
const T &_x,
const T &_y,
const T &_z)
50 : qw(_w), qx(_x), qy(_y), qz(_z)
57 public:
Quaternion(
const T &_roll,
const T &_pitch,
const T &_yaw)
67 this->
Axis(_axis, _angle);
107 this->qx = -this->qx;
108 this->qy = -this->qy;
109 this->qz = -this->qz;
120 s = q.qw * q.qw + q.qx * q.qx + q.qy * q.qy + q.qz * q.qz;
122 if (equal<T>(s, static_cast<T>(0)))
152 if (std::abs(this->qw) < 1.0)
154 T fAngle = acos(this->qw);
155 T fSin = sin(fAngle);
156 if (std::abs(fSin) >= 1e-3)
158 T fCoeff = fAngle/fSin;
159 result.qx = fCoeff*this->qx;
160 result.qy = fCoeff*this->qy;
161 result.qz = fCoeff*this->qz;
166 result.qx = this->qx;
167 result.qy = this->qy;
168 result.qz = this->qz;
181 T fAngle = sqrt(this->qx*this->qx+
182 this->qy*this->qy+this->qz*this->qz);
183 T fSin = sin(fAngle);
186 result.qw = cos(fAngle);
188 if (std::abs(fSin) >= 1e-3)
190 T fCoeff = fSin/fAngle;
191 result.qx = fCoeff*this->qx;
192 result.qy = fCoeff*this->qy;
193 result.qz = fCoeff*this->qz;
197 result.qx = this->qx;
198 result.qy = this->qy;
199 result.qz = this->qz;
210 s = sqrt(this->qw * this->qw + this->qx * this->qx +
211 this->qy * this->qy + this->qz * this->qz);
213 if (equal<T>(s, static_cast<T>(0)))
234 public:
void Axis(T _ax, T _ay, T _az, T _aa)
238 l = _ax * _ax + _ay * _ay + _az * _az;
240 if (equal<T>(l, static_cast<T>(0)))
250 l = sin(_aa) / sqrt(l);
265 this->
Axis(_axis.
X(), _axis.
Y(), _axis.
Z(), _a);
273 public:
void Set(T _w, T _x, T _y, T _z)
288 this->
Euler(_vec.
X(), _vec.
Y(), _vec.
Z());
295 public:
void Euler(T _roll, T _pitch, T _yaw)
303 this->qw = cos(phi) * cos(the) * cos(psi) +
304 sin(phi) * sin(the) * sin(psi);
305 this->qx = sin(phi) * cos(the) * cos(psi) -
306 cos(phi) * sin(the) * sin(psi);
307 this->qy = cos(phi) * sin(the) * cos(psi) +
308 sin(phi) * cos(the) * sin(psi);
309 this->qz = cos(phi) * cos(the) * sin(psi) -
310 sin(phi) * sin(the) * cos(psi);
329 squ = copy.qw * copy.qw;
330 sqx = copy.qx * copy.qx;
331 sqy = copy.qy * copy.qy;
332 sqz = copy.qz * copy.qz;
335 vec.
X(atan2(2 * (copy.qy*copy.qz + copy.qw*copy.qx),
336 squ - sqx - sqy + sqz));
339 T sarg = -2 * (copy.qx*copy.qz - copy.qw * copy.qy);
340 vec.
Y(sarg <= -1.0 ? -0.5*
IGN_PI :
341 (sarg >= 1.0 ? 0.5*
IGN_PI : asin(sarg)));
344 vec.
Z(atan2(2 * (copy.qx*copy.qy + copy.qw*copy.qz),
345 squ + sqx - sqy - sqz));
374 return this->
Euler().X();
381 return this->
Euler().Y();
388 return this->
Euler().Z();
396 T len = this->qx*this->qx + this->qy*this->qy + this->qz*this->qz;
397 if (equal<T>(len, static_cast<T>(0)))
404 _angle = 2.0 * acos(this->qw);
405 T invLen = 1.0 / sqrt(len);
406 _axis.
Set(this->qx*invLen, this->qy*invLen, this->qz*invLen);
419 this->
ToAxis(axis, angle);
422 this->
Axis(axis.
X(), axis.
Y(), axis.
Z(), angle);
431 this->qy + _qt.qy, this->qz + _qt.qz);
451 this->qy - _qt.qy, this->qz - _qt.qz);
470 this->qw*_q.qw-this->qx*_q.qx-this->qy*_q.qy-this->qz*_q.qz,
471 this->qw*_q.qx+this->qx*_q.qw+this->qy*_q.qz-this->qz*_q.qy,
472 this->qw*_q.qy-this->qx*_q.qz+this->qy*_q.qw+this->qz*_q.qx,
473 this->qw*_q.qz+this->qx*_q.qy-this->qy*_q.qx+this->qz*_q.qw);
482 this->qy*_f, this->qz*_f);
500 Vector3<T> qvec(this->qx, this->qy, this->qz);
502 uuv = qvec.
Cross(uv);
503 uv *= (2.0f * this->qw);
506 return _v + uv + uuv;
514 return equal(this->qx, _qt.qx, static_cast<T>(0.001)) &&
515 equal(this->qy, _qt.qy, static_cast<T>(0.001)) &&
516 equal(this->qz, _qt.qz, static_cast<T>(0.001)) &&
517 equal(this->qw, _qt.qw, static_cast<T>(0.001));
525 return !
equal(this->qx, _qt.qx, static_cast<T>(0.001)) ||
526 !
equal(this->qy, _qt.qy, static_cast<T>(0.001)) ||
527 !
equal(this->qz, _qt.qz, static_cast<T>(0.001)) ||
528 !
equal(this->qw, _qt.qw, static_cast<T>(0.001));
535 return Quaternion<T>(-this->qw, -this->qx, -this->qy, -this->qz);
544 _vec.
X(), _vec.
Y(), _vec.
Z());
545 tmp = (*this) * (tmp * this->
Inverse());
556 tmp = this->
Inverse() * (tmp * (*this));
567 return std::isfinite(static_cast<double>(this->qw)) &&
568 std::isfinite(static_cast<double>(this->qx)) &&
569 std::isfinite(static_cast<double>(this->qy)) &&
570 std::isfinite(static_cast<double>(this->qz));
578 if (!std::isfinite(static_cast<double>(this->qx)))
580 if (!std::isfinite(static_cast<double>(this->qy)))
582 if (!std::isfinite(static_cast<double>(this->qz)))
584 if (!std::isfinite(static_cast<double>(this->qw)))
587 if (
equal(this->qw, static_cast<T>(0)) &&
588 equal(this->qx, static_cast<T>(0)) &&
589 equal(this->qy, static_cast<T>(0)) &&
590 equal(this->qz, static_cast<T>(0)))
600 T fTy = 2.0f*this->qy;
601 T fTz = 2.0f*this->qz;
603 T fTwy = fTy*this->qw;
604 T fTwz = fTz*this->qw;
605 T fTxy = fTy*this->qx;
606 T fTxz = fTz*this->qx;
607 T fTyy = fTy*this->qy;
608 T fTzz = fTz*this->qz;
610 return Vector3<T>(1.0f-(fTyy+fTzz), fTxy+fTwz, fTxz-fTwy);
617 T fTx = 2.0f*this->qx;
618 T fTy = 2.0f*this->qy;
619 T fTz = 2.0f*this->qz;
620 T fTwx = fTx*this->qw;
621 T fTwz = fTz*this->qw;
622 T fTxx = fTx*this->qx;
623 T fTxy = fTy*this->qx;
624 T fTyz = fTz*this->qy;
625 T fTzz = fTz*this->qz;
627 return Vector3<T>(fTxy-fTwz, 1.0f-(fTxx+fTzz), fTyz+fTwx);
634 T fTx = 2.0f*this->qx;
635 T fTy = 2.0f*this->qy;
636 T fTz = 2.0f*this->qz;
637 T fTwx = fTx*this->qw;
638 T fTwy = fTy*this->qw;
639 T fTxx = fTx*this->qx;
640 T fTxz = fTz*this->qx;
641 T fTyy = fTy*this->qy;
642 T fTyz = fTz*this->qy;
644 return Vector3<T>(fTxz+fTwy, fTyz-fTwx, 1.0f-(fTxx+fTyy));
651 this->qx =
precision(this->qx, _precision);
652 this->qy =
precision(this->qy, _precision);
653 this->qz =
precision(this->qz, _precision);
654 this->qw =
precision(this->qw, _precision);
662 return this->qw*_q.qw + this->qx * _q.qx +
663 this->qy*_q.qy + this->qz*_q.qz;
679 bool _shortestPath =
false)
681 T fSlerpT = 2.0f*_fT*(1.0f-_fT);
684 return Slerp(fSlerpT, kSlerpP, kSlerpQ);
697 bool _shortestPath =
false)
699 T fCos = _rkP.
Dot(_rkQ);
703 if (fCos < 0.0f && _shortestPath)
713 if (std::abs(fCos) < 1 - 1e-03)
716 T fSin = sqrt(1 - (fCos*fCos));
717 T fAngle = atan2(fSin, fCos);
719 T fInvSin = 1.0f / fSin;
720 T fCoeff0 = sin((1.0f - _fT) * fAngle) * fInvSin;
721 T fCoeff1 = sin(_fT * fAngle) * fInvSin;
722 return _rkP * fCoeff0 + rkT * fCoeff1;
750 const T _deltaT)
const
753 Vector3<T> theta = _angularVelocity * _deltaT * 0.5;
758 deltaQ.
W() = 1.0 - thetaMagSq / 2.0;
759 s = 1.0 - thetaMagSq / 6.0;
763 double thetaMag = sqrt(thetaMagSq);
764 deltaQ.
W() = cos(thetaMag);
765 s = sin(thetaMag) / thetaMag;
767 deltaQ.
X() = theta.
X() * s;
768 deltaQ.
Y() = theta.
Y() * s;
769 deltaQ.
Z() = theta.
Z() * s;
770 return deltaQ * (*this);
775 public:
inline const T &
W()
const
782 public:
inline const T &
X()
const
789 public:
inline const T &
Y()
const
796 public:
inline const T &
Z()
const
804 public:
inline T &
W()
811 public:
inline T &
X()
818 public:
inline T &
Y()
825 public:
inline T &
Z()
832 public:
inline void X(T _v)
839 public:
inline void Y(T _v)
846 public:
inline void Z(T _v)
853 public:
inline void W(T _v)
878 Angle roll, pitch, yaw;
881 _in.setf(std::ios_base::skipws);
882 _in >> roll >> pitch >> yaw;
902 template<
typename T>
const Quaternion<T>
An angle and related functions.
Definition: Angle.hh:44
Quaternion< double > Quaterniond
Definition: Quaternion.hh:905
void Round(int _precision)
Round all values to _precision decimal places.
Definition: Quaternion.hh:649
void Y(T _v)
Set the y component.
Definition: Quaternion.hh:839
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:832
void Euler(T _roll, T _pitch, T _yaw)
Set the quaternion from Euler angles.
Definition: Quaternion.hh:295
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:250
Vector3< T > operator*(const Vector3< T > &_v) const
Vector3 multiplication operator.
Definition: Quaternion.hh:497
bool operator==(const Quaternion< T > &_qt) const
Equal to operator.
Definition: Quaternion.hh:512
void Z(T _v)
Set the z component.
Definition: Quaternion.hh:846
#define IGN_DBL_MIN
Double min value. This value will be similar to 2.22507e-308.
Definition: Helpers.hh:35
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
Subtraction operator.
Definition: Quaternion.hh:448
T & X()
Get a mutable x component.
Definition: Quaternion.hh:811
T Roll() const
Get the Euler roll angle in radians.
Definition: Quaternion.hh:372
Quaternion< float > Quaternionf
Definition: Quaternion.hh:906
friend std::istream & operator>>(std::istream &_in, ignition::math::Quaternion< T > &_q)
Stream extraction operator.
Definition: Quaternion.hh:875
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:676
const T & Y() const
Get the y component.
Definition: Quaternion.hh:789
T & Y()
Get a mutable y component.
Definition: Quaternion.hh:818
Vector3< T > Euler() const
Return the rotation in Euler angles.
Definition: Quaternion.hh:317
T Pitch() const
Get the Euler pitch angle in radians.
Definition: Quaternion.hh:379
T X() const
Get the x value.
Definition: Vector3.hh:560
Quaternion< T > operator*(const T &_f) const
Multiplication operator by a scalar.
Definition: Quaternion.hh:479
const T & Z() const
Get the z component.
Definition: Quaternion.hh:796
Quaternion< T > operator+=(const Quaternion< T > &_qt)
Addition operator.
Definition: Quaternion.hh:438
void Correct()
Correct any nan values in this quaternion.
Definition: Quaternion.hh:574
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:615
static Quaternion< T > EulerToQuaternion(const Vector3< T > &_vec)
Convert euler angles to quatern.
Definition: Quaternion.hh:353
T Dot(const Quaternion< T > &_q) const
Dot product.
Definition: Quaternion.hh:660
Quaternion< T > & operator=(const Quaternion< T > &_qt)
Equal operator.
Definition: Quaternion.hh:92
T Y() const
Get the y value.
Definition: Vector3.hh:567
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:552
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:862
Vector3< T > XAxis() const
Return the X axis.
Definition: Quaternion.hh:598
Quaternion< T > operator*(const Quaternion< T > &_q) const
Multiplication operator.
Definition: Quaternion.hh:467
T & W()
Get a mutable w component.
Definition: Quaternion.hh:804
T Z() const
Get the z value.
Definition: Vector3.hh:574
void Scale(T _scale)
Scale a Quaternion<T>ion.
Definition: Quaternion.hh:412
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:695
void ToAxis(Vector3< T > &_axis, T &_angle) const
Return rotation as axis and angle.
Definition: Quaternion.hh:394
Quaternion< T > operator-() const
Unary minus operator.
Definition: Quaternion.hh:533
Quaternion< T > operator+(const Quaternion< T > &_qt) const
Addition operator.
Definition: Quaternion.hh:428
T & Z()
Get a mutable z component.
Definition: Quaternion.hh:825
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:37
bool IsFinite() const
See if a quaternion is finite (e.g., not nan)
Definition: Quaternion.hh:563
bool operator!=(const Quaternion< T > &_qt) const
Not equal to operator.
Definition: Quaternion.hh:523
void W(T _v)
Set the w component.
Definition: Quaternion.hh:853
T SquaredLength() const
Return the square of the length (magnitude) of the vector.
Definition: Vector3.hh:123
Quaternion< T > operator*=(const Quaternion< T > &qt)
Multiplication operator.
Definition: Quaternion.hh:488
Quaternion< int > Quaternioni
Definition: Quaternion.hh:907
void Euler(const Vector3< T > &_vec)
Set the quaternion from Euler angles.
Definition: Quaternion.hh:286
T Yaw() const
Get the Euler yaw angle in radians.
Definition: Quaternion.hh:386
Quaternion()
Default Constructor.
Definition: Quaternion.hh:37
const T & W() const
Get the w component.
Definition: Quaternion.hh:775
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:238
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)
Subtraction operator.
Definition: Quaternion.hh:458
#define IGN_PI
Define IGN_PI, IGN_PI_2, and IGN_PI_4.
Definition: Helpers.hh:79
Vector3< T > RotateVector(const Vector3< T > &_vec) const
Rotate a vector using the quaternion.
Definition: Quaternion.hh:541
Quaternion(const T &_roll, const T &_pitch, const T &_yaw)
Constructor from Euler angles in radians.
Definition: Quaternion.hh:57
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:749
Quaternion< T > Log() const
Return the logarithm.
Definition: Quaternion.hh:143
Vector3< T > ZAxis() const
Return the Z axis.
Definition: Quaternion.hh:632
static Quaternion< T > EulerToQuaternion(T _x, T _y, T _z)
Convert euler angles to quatern.
Definition: Quaternion.hh:365
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:782