tf2  master
tf2 maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.
Public Member Functions | Static Public Member Functions | List of all members
tf2::Quaternion Class Reference

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

#include <Quaternion.h>

Inheritance diagram for tf2::Quaternion:
Inheritance graph
[legend]
Collaboration diagram for tf2::Quaternion:
Collaboration graph
[legend]

Public Member Functions

 Quaternion ()
 No initialization constructor. More...
 
 Quaternion (const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
 Constructor from scalars. More...
 
 Quaternion (const Vector3 &axis, const tf2Scalar &angle)
 Axis angle Constructor. More...
 
void setRotation (const Vector3 &axis, const tf2Scalar &angle)
 Set the rotation using axis angle notation. More...
 
void setEuler (const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
 Set the quaternion using Euler angles. More...
 
void setRPY (const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
 Set the quaternion using fixed axis RPY. More...
 
TF2SIMD_FORCE_INLINE Quaternionoperator+= (const Quaternion &q)
 Add two quaternions. More...
 
Quaternionoperator-= (const Quaternion &q)
 Sutf2ract out a quaternion. More...
 
Quaternionoperator*= (const tf2Scalar &s)
 Scale this quaternion. More...
 
Quaternionoperator*= (const Quaternion &q)
 Multiply this quaternion by q on the right. More...
 
tf2Scalar dot (const Quaternion &q) const
 Return the dot product between this quaternion and another. More...
 
tf2Scalar length2 () const
 Return the length squared of the quaternion. More...
 
tf2Scalar length () const
 Return the length of the quaternion. More...
 
Quaternionnormalize ()
 Normalize the quaternion Such that x^2 + y^2 + z^2 +w^2 = 1. More...
 
TF2SIMD_FORCE_INLINE Quaternion operator* (const tf2Scalar &s) const
 Return a scaled version of this quaternion. More...
 
Quaternion operator/ (const tf2Scalar &s) const
 Return an inversely scaled versionof this quaternion. More...
 
Quaternionoperator/= (const tf2Scalar &s)
 Inversely scale this quaternion. More...
 
Quaternion normalized () const
 Return a normalized version of this quaternion. More...
 
tf2Scalar angle (const Quaternion &q) const
 Return the half angle between this quaternion and the other. More...
 
tf2Scalar angleShortestPath (const Quaternion &q) const
 Return the angle between this quaternion and the other along the shortest path. More...
 
tf2Scalar getAngle () const
 Return the angle [0, 2Pi] of rotation represented by this quaternion. More...
 
tf2Scalar getAngleShortestPath () const
 Return the angle [0, Pi] of rotation represented by this quaternion along the shortest path. More...
 
Vector3 getAxis () const
 Return the axis of the rotation represented by this quaternion. More...
 
Quaternion inverse () const
 Return the inverse of this quaternion. More...
 
TF2SIMD_FORCE_INLINE Quaternion operator+ (const Quaternion &q2) const
 Return the sum of this quaternion and the other. More...
 
TF2SIMD_FORCE_INLINE Quaternion operator- (const Quaternion &q2) const
 Return the difference between this quaternion and the other. More...
 
TF2SIMD_FORCE_INLINE Quaternion operator- () const
 Return the negative of this quaternion This simply negates each element. More...
 
TF2SIMD_FORCE_INLINE Quaternion farthest (const Quaternion &qd) const
 
TF2SIMD_FORCE_INLINE Quaternion nearest (const Quaternion &qd) const
 
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. More...
 
const TF2SIMD_FORCE_INLINE tf2ScalargetW () const
 

Static Public Member Functions

static const QuaterniongetIdentity ()
 

Detailed Description

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

Constructor & Destructor Documentation

◆ Quaternion() [1/3]

tf2::Quaternion::Quaternion ( )
inline

No initialization constructor.

◆ Quaternion() [2/3]

tf2::Quaternion::Quaternion ( const tf2Scalar x,
const tf2Scalar y,
const tf2Scalar z,
const tf2Scalar w 
)
inline

Constructor from scalars.

◆ Quaternion() [3/3]

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

Axis angle Constructor.

Parameters
axisThe axis which the rotation is around
angleThe magnitude of the rotation around the angle (Radians)

Member Function Documentation

◆ setRotation()

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

Set the rotation using axis angle notation.

Parameters
axisThe axis around which to rotate
angleThe magnitude of the rotation in Radians

◆ setEuler()

void tf2::Quaternion::setEuler ( const tf2Scalar yaw,
const tf2Scalar pitch,
const tf2Scalar roll 
)
inline

Set the quaternion using Euler angles.

Parameters
yawAngle around Y
pitchAngle around X
rollAngle around Z

◆ setRPY()

void tf2::Quaternion::setRPY ( const tf2Scalar roll,
const tf2Scalar pitch,
const tf2Scalar yaw 
)
inline

Set the quaternion using fixed axis RPY.

Parameters
rollAngle around X
pitchAngle around Y
yawAngle around Z

◆ operator+=()

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

Add two quaternions.

Parameters
qThe quaternion to add to this one

◆ operator-=()

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

Sutf2ract out a quaternion.

Parameters
qThe quaternion to sutf2ract from this one

◆ operator*=() [1/2]

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

Scale this quaternion.

Parameters
sThe scalar to scale by

◆ operator*=() [2/2]

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

Multiply this quaternion by q on the right.

Parameters
qThe other quaternion Equivilant to this = this * q

◆ dot()

tf2Scalar tf2::Quaternion::dot ( const Quaternion q) const
inline

Return the dot product between this quaternion and another.

Parameters
qThe other quaternion

◆ length2()

tf2Scalar tf2::Quaternion::length2 ( ) const
inline

Return the length squared of the quaternion.

◆ length()

tf2Scalar tf2::Quaternion::length ( ) const
inline

Return the length of the quaternion.

◆ normalize()

Quaternion& tf2::Quaternion::normalize ( )
inline

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

◆ operator*()

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::operator* ( const tf2Scalar s) const
inline

Return a scaled version of this quaternion.

Parameters
sThe scale factor

◆ operator/()

Quaternion tf2::Quaternion::operator/ ( const tf2Scalar s) const
inline

Return an inversely scaled versionof this quaternion.

Parameters
sThe inverse scale factor

◆ operator/=()

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

Inversely scale this quaternion.

Parameters
sThe scale factor

◆ normalized()

Quaternion tf2::Quaternion::normalized ( ) const
inline

Return a normalized version of this quaternion.

◆ angle()

tf2Scalar tf2::Quaternion::angle ( const Quaternion q) const
inline

Return the half angle between this quaternion and the other.

Parameters
qThe other quaternion

◆ angleShortestPath()

tf2Scalar tf2::Quaternion::angleShortestPath ( const Quaternion q) const
inline

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

Parameters
qThe other quaternion

◆ getAngle()

tf2Scalar tf2::Quaternion::getAngle ( ) const
inline

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

◆ getAngleShortestPath()

tf2Scalar tf2::Quaternion::getAngleShortestPath ( ) const
inline

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

◆ getAxis()

Vector3 tf2::Quaternion::getAxis ( ) const
inline

Return the axis of the rotation represented by this quaternion.

◆ inverse()

Quaternion tf2::Quaternion::inverse ( ) const
inline

Return the inverse of this quaternion.

◆ operator+()

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::operator+ ( const Quaternion q2) const
inline

Return the sum of this quaternion and the other.

Parameters
q2The other quaternion

◆ operator-() [1/2]

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::operator- ( const Quaternion q2) const
inline

Return the difference between this quaternion and the other.

Parameters
q2The other quaternion

◆ operator-() [2/2]

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::operator- ( ) const
inline

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

◆ farthest()

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::farthest ( const Quaternion qd) const
inline
Todo:
document this and it's use

◆ nearest()

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::nearest ( const Quaternion qd) const
inline
Todo:
document this and it's use

◆ slerp()

Quaternion tf2::Quaternion::slerp ( const Quaternion q,
const tf2Scalar t 
) const
inline

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

Parameters
qThe other quaternion to interpolate with
tThe 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.

◆ getIdentity()

static const Quaternion& tf2::Quaternion::getIdentity ( )
inlinestatic

◆ getW()

const TF2SIMD_FORCE_INLINE tf2Scalar& tf2::Quaternion::getW ( ) const
inline

The documentation for this class was generated from the following file: