Class Quaternion

Inheritance Relationships

Base Type

  • public QuadWord

Class Documentation

class Quaternion : public QuadWord

The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x3, Vector3 and Transform.

Public Functions

inline Quaternion()

No initialization constructor.

inline Quaternion(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)

Constructor from scalars.

inline Quaternion(const Vector3 &axis, const tf2Scalar &angle)

Axis angle Constructor.

Parameters:
  • axis – The axis which the rotation is around

  • angle – The magnitude of the rotation around the angle (Radians)

inline void setRotation(const Vector3 &axis, const tf2Scalar &angle)

Set the rotation using axis angle notation.

Parameters:
  • axis – The axis around which to rotate

  • angle – The magnitude of the rotation in Radians

inline void setEuler(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)

Set the quaternion using Euler angles.

Parameters:
  • yaw – Angle around Y

  • pitch – Angle around X

  • roll – Angle around Z

inline void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)

Set the quaternion using fixed axis RPY.

Parameters:
  • roll – Angle around X

  • pitch – Angle around Y

  • yaw – Angle around Z

inline TF2SIMD_FORCE_INLINE Quaternion & operator+= (const Quaternion &q)

Add two quaternions.

Parameters:

q – The quaternion to add to this one

inline Quaternion &operator-=(const Quaternion &q)

Sutf2ract out a quaternion.

Parameters:

q – The quaternion to sutf2ract from this one

inline Quaternion &operator*=(const tf2Scalar &s)

Scale this quaternion.

Parameters:

s – The scalar to scale by

inline Quaternion &operator*=(const Quaternion &q)

Multiply this quaternion by q on the right.

Parameters:

q – The other quaternion Equivilant to this = this * q

inline tf2Scalar dot(const Quaternion &q) const

Return the dot product between this quaternion and another.

Parameters:

q – The other quaternion

inline tf2Scalar length2() const

Return the length squared of the quaternion.

inline tf2Scalar length() const

Return the length of the quaternion.

inline Quaternion &normalize()

Normalize the quaternion Such that x^2 + y^2 + z^2 +w^2 = 1.

inline TF2SIMD_FORCE_INLINE Quaternion operator* (const tf2Scalar &s) const

Return a scaled version of this quaternion.

Parameters:

s – The scale factor

inline Quaternion operator/(const tf2Scalar &s) const

Return an inversely scaled versionof this quaternion.

Parameters:

s – The inverse scale factor

inline Quaternion &operator/=(const tf2Scalar &s)

Inversely scale this quaternion.

Parameters:

s – The scale factor

inline Quaternion normalized() const

Return a normalized version of this quaternion.

inline tf2Scalar angle(const Quaternion &q) const

Return the angle between this quaternion and the other.

Parameters:

q – The other quaternion

inline tf2Scalar angleShortestPath(const Quaternion &q) const

Return the angle between this quaternion and the other along the shortest path.

Parameters:

q – The other quaternion

inline tf2Scalar getAngle() const

Return the angle [0, 2Pi] of rotation represented by this quaternion.

inline tf2Scalar getAngleShortestPath() const

Return the angle [0, Pi] of rotation represented by this quaternion along the shortest path.

inline Vector3 getAxis() const

Return the axis of the rotation represented by this quaternion.

inline Quaternion inverse() const

Return the inverse of this quaternion.

inline TF2SIMD_FORCE_INLINE Quaternion operator+ (const Quaternion &q2) const

Return the sum of this quaternion and the other.

Parameters:

q2 – The other quaternion

inline TF2SIMD_FORCE_INLINE Quaternion operator- (const Quaternion &q2) const

Return the difference between this quaternion and the other.

Parameters:

q2 – The other quaternion

inline TF2SIMD_FORCE_INLINE Quaternion operator- () const

Return the negative of this quaternion This simply negates each element.

inline TF2SIMD_FORCE_INLINE Quaternion farthest (const Quaternion &qd) const

Todo:

document this and it’s use

inline TF2SIMD_FORCE_INLINE Quaternion nearest (const Quaternion &qd) const

Todo:

document this and it’s use

inline Quaternion slerp(const Quaternion &q, const tf2Scalar &t) const

Return the quaternion which is the result of Spherical Linear Interpolation between this and the other quaternion.

Parameters:
  • q – The other quaternion to interpolate with

  • t – The ratio between this and q to interpolate. If t = 0 the result is this, if t=1 the result is q. Slerp interpolates assuming constant velocity.

inline TF2SIMD_FORCE_INLINE const tf2Scalar & getW () const

Public Static Functions

static inline const Quaternion &getIdentity()