Ignition Math

API Reference

6.9.3~pre2

A quaternion class. More...

#include <ignition/math/Quaternion.hh>

Public Member Functions

 Quaternion ()
 Default Constructor. More...
 
 Quaternion (const T &_w, const T &_x, const T &_y, const T &_z)
 Constructor. More...
 
 Quaternion (const T &_roll, const T &_pitch, const T &_yaw)
 Constructor from Euler angles in radians. More...
 
 Quaternion (const Vector3< T > &_axis, const T &_angle)
 Constructor from axis angle. More...
 
 Quaternion (const Vector3< T > &_rpy)
 Constructor. More...
 
 Quaternion (const Matrix3< T > &_mat)
 Construct from rotation matrix. More...
 
 Quaternion (const Quaternion< T > &_qt)
 Copy constructor. More...
 
 ~Quaternion ()
 Destructor. More...
 
void Axis (T _ax, T _ay, T _az, T _aa)
 Set the quaternion from an axis and angle. More...
 
void Axis (const Vector3< T > &_axis, T _a)
 Set the quaternion from an axis and angle. More...
 
void Correct ()
 Correct any nan values in this quaternion. More...
 
Dot (const Quaternion< T > &_q) const
 Dot product. More...
 
bool Equal (const Quaternion< T > &_qt, const T &_tol) const
 Equality test with tolerance. More...
 
void Euler (const Vector3< T > &_vec)
 Set the quaternion from Euler angles. The order of operations is roll, pitch, yaw around a fixed body frame axis (the original frame of the object before rotation is applied). Roll is a rotation about x, pitch is about y, yaw is about z. More...
 
void Euler (T _roll, T _pitch, T _yaw)
 Set the quaternion from Euler angles. More...
 
Vector3< T > Euler () const
 Return the rotation in Euler angles. More...
 
Quaternion< T > Exp () const
 Return the exponent. More...
 
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. More...
 
Quaternion< T > Integrate (const Vector3< T > &_angularVelocity, const T _deltaT) const
 Integrate quaternion for constant angular velocity vector along specified interval _deltaT. Implementation based on: http://physicsforgames.blogspot.com/2010/02/quaternions.html. More...
 
Quaternion< T > Inverse () const
 Get the inverse of this quaternion. More...
 
void Invert ()
 Invert the quaternion. More...
 
bool IsFinite () const
 See if a quaternion is finite (e.g., not nan) More...
 
Quaternion< T > Log () const
 Return the logarithm. More...
 
void Matrix (const Matrix3< T > &_mat)
 Set from a rotation matrix. More...
 
void Normalize ()
 Normalize the quaternion. More...
 
Quaternion< T > Normalized () const
 Gets a normalized version of this quaternion. More...
 
bool operator!= (const Quaternion< T > &_qt) const
 Not equal to operator. More...
 
Quaternion< T > operator* (const Quaternion< T > &_q) const
 Multiplication operator. More...
 
Quaternion< T > operator* (const T &_f) const
 Multiplication operator by a scalar. More...
 
Vector3< T > operator* (const Vector3< T > &_v) const
 Vector3 multiplication operator. More...
 
Quaternion< T > operator*= (const Quaternion< T > &_qt)
 Multiplication operator. More...
 
Quaternion< T > operator+ (const Quaternion< T > &_qt) const
 Addition operator. More...
 
Quaternion< T > operator+= (const Quaternion< T > &_qt)
 Addition operator. More...
 
Quaternion< T > operator- (const Quaternion< T > &_qt) const
 Subtraction operator. More...
 
Quaternion< T > operator- () const
 Unary minus operator. More...
 
Quaternion< T > operator-= (const Quaternion< T > &_qt)
 Subtraction operator. More...
 
Quaternion< T > & operator= (const Quaternion< T > &_qt)
 Assignment operator. More...
 
bool operator== (const Quaternion< T > &_qt) const
 Equal to operator. More...
 
Pitch () const
 Get the Euler pitch angle in radians. More...
 
Roll () const
 Get the Euler roll angle in radians. More...
 
Vector3< T > RotateVector (const Vector3< T > &_vec) const
 Rotate a vector using the quaternion. More...
 
Vector3< T > RotateVectorReverse (const Vector3< T > &_vec) const
 Do the reverse rotation of a vector by this quaternion. More...
 
void Round (int _precision)
 Round all values to _precision decimal places. More...
 
void Scale (T _scale)
 Scale a Quaternion<T> More...
 
void Set (T _w, T _x, T _y, T _z)
 Set this quaternion from 4 floating numbers. More...
 
void ToAxis (Vector3< T > &_axis, T &_angle) const
 Return rotation as axis and angle. More...
 
const T & W () const
 Get the w component. More...
 
T & W ()
 Get a mutable w component. More...
 
void W (T _v)
 Set the w component. More...
 
const T & X () const
 Get the x component. More...
 
T & X ()
 Get a mutable x component. More...
 
void X (T _v)
 Set the x component. More...
 
Vector3< T > XAxis () const
 Return the X axis. More...
 
const T & Y () const
 Get the y component. More...
 
T & Y ()
 Get a mutable y component. More...
 
void Y (T _v)
 Set the y component. More...
 
Yaw () const
 Get the Euler yaw angle in radians. More...
 
Vector3< T > YAxis () const
 Return the Y axis. More...
 
const T & Z () const
 Get the z component. More...
 
T & Z ()
 Get a mutable z component. More...
 
void Z (T _v)
 Set the z component. More...
 
Vector3< T > ZAxis () const
 Return the Z axis. More...
 

Static Public Member Functions

static Quaternion< T > EulerToQuaternion (const Vector3< T > &_vec)
 Convert euler angles to quatern. More...
 
static Quaternion< T > EulerToQuaternion (T _x, T _y, T _z)
 Convert euler angles to quatern. More...
 
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 between 0 and 1. More...
 
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. More...
 

Static Public Attributes

static const Quaternion Identity
 math::Quaternion(1, 0, 0, 0) More...
 
static const Quaternion Zero
 math::Quaternion(0, 0, 0, 0) More...
 

Friends

std::ostreamoperator<< (std::ostream &_out, const Quaternion< T > &_q)
 Stream insertion operator. More...
 
std::istreamoperator>> (std::istream &_in, Quaternion< T > &_q)
 Stream extraction operator. More...
 

Detailed Description

template<typename T>
class ignition::math::Quaternion< T >

A quaternion class.

Constructor & Destructor Documentation

◆ Quaternion() [1/7]

Quaternion ( )
inline

Default Constructor.

◆ Quaternion() [2/7]

Quaternion ( const T &  _w,
const T &  _x,
const T &  _y,
const T &  _z 
)
inline

Constructor.

Parameters
[in]_wW param
[in]_xX param
[in]_yY param
[in]_zZ param

◆ Quaternion() [3/7]

Quaternion ( const T &  _roll,
const T &  _pitch,
const T &  _yaw 
)
inline

Constructor from Euler angles in radians.

Parameters
[in]_rollroll
[in]_pitchpitch
[in]_yawyaw

◆ Quaternion() [4/7]

Quaternion ( const Vector3< T > &  _axis,
const T &  _angle 
)
inline

Constructor from axis angle.

Parameters
[in]_axisthe rotation axis
[in]_anglethe rotation angle in radians

◆ Quaternion() [5/7]

Quaternion ( const Vector3< T > &  _rpy)
inlineexplicit

Constructor.

Parameters
[in]_rpyeuler angles, in radians

◆ Quaternion() [6/7]

Quaternion ( const Matrix3< T > &  _mat)
inlineexplicit

Construct from rotation matrix.

Parameters
[in]_matrotation matrix (must be orthogonal, the function doesn't check it)

◆ Quaternion() [7/7]

Quaternion ( const Quaternion< T > &  _qt)
inline

Copy constructor.

Parameters
[in]_qtQuaternion<T> to copy

◆ ~Quaternion()

~Quaternion ( )
inline

Destructor.

Member Function Documentation

◆ Axis() [1/2]

void Axis ( _ax,
_ay,
_az,
_aa 
)
inline

Set the quaternion from an axis and angle.

Parameters
[in]_axX axis
[in]_ayY axis
[in]_azZ axis
[in]_aaAngle in radians

Referenced by Quaternion< Precision >::Axis(), Quaternion< Precision >::Quaternion(), and Quaternion< Precision >::Scale().

◆ Axis() [2/2]

void Axis ( const Vector3< T > &  _axis,
_a 
)
inline

Set the quaternion from an axis and angle.

Parameters
[in]_axisAxis
[in]_aAngle in radians

◆ Correct()

void Correct ( )
inline

Correct any nan values in this quaternion.

◆ Dot()

T Dot ( const Quaternion< T > &  _q) const
inline

Dot product.

Parameters
[in]_qthe other quaternion
Returns
the product

◆ Equal()

bool Equal ( const Quaternion< T > &  _qt,
const T &  _tol 
) const
inline

Equality test with tolerance.

Parameters
[in]_qtQuaternion<T> for comparison
[in]_tolequality tolerance
Returns
true if the elements of the quaternions are equal within the tolerance specified by _tol, false otherwise

Referenced by Quaternion< Precision >::operator==().

◆ Euler() [1/3]

void Euler ( const Vector3< T > &  _vec)
inline

Set the quaternion from Euler angles. The order of operations is roll, pitch, yaw around a fixed body frame axis (the original frame of the object before rotation is applied). Roll is a rotation about x, pitch is about y, yaw is about z.

Parameters
[in]_vecEuler angle

◆ Euler() [2/3]

void Euler ( _roll,
_pitch,
_yaw 
)
inline

Set the quaternion from Euler angles.

Parameters
[in]_rollRoll angle (radians).
[in]_pitchPitch angle (radians).
[in]_yawYaw angle (radians).

◆ Euler() [3/3]

Vector3<T> Euler ( ) const
inline

Return the rotation in Euler angles.

Returns
This quaternion as an Euler vector

Referenced by Quaternion< Precision >::Euler(), Quaternion< Precision >::Pitch(), Quaternion< Precision >::Quaternion(), Quaternion< Precision >::Roll(), and Quaternion< Precision >::Yaw().

◆ EulerToQuaternion() [1/2]

static Quaternion<T> EulerToQuaternion ( const Vector3< T > &  _vec)
inlinestatic

Convert euler angles to quatern.

Parameters
[in]_vecThe vector of angles to convert.
Returns
The converted quaternion.

Referenced by Quaternion< Precision >::EulerToQuaternion().

◆ EulerToQuaternion() [2/2]

static Quaternion<T> EulerToQuaternion ( _x,
_y,
_z 
)
inlinestatic

Convert euler angles to quatern.

Parameters
[in]_xrotation along x
[in]_yrotation along y
[in]_zrotation along z
Returns
The converted quaternion.

◆ Exp()

Quaternion<T> Exp ( ) const
inline

Return the exponent.

Returns
the exp

◆ From2Axes()

void From2Axes ( const Vector3< T > &  _v1,
const Vector3< T > &  _v2 
)
inline

Set this quaternion to represent rotation from vector _v1 to vector _v2, so that _v2.Normalize() == this * _v1.Normalize() holds.

Parameters
[in]_v1The first vector
[in]_v2The second vector

Implementation inspired by http://stackoverflow.com/a/11741520/1076564

◆ Integrate()

Quaternion<T> Integrate ( const Vector3< T > &  _angularVelocity,
const T  _deltaT 
) const
inline

Integrate quaternion for constant angular velocity vector along specified interval _deltaT. Implementation based on: http://physicsforgames.blogspot.com/2010/02/quaternions.html.

Parameters
[in]_angularVelocityAngular velocity vector, specified in same reference frame as base of this quaternion.
[in]_deltaTTime interval in seconds to integrate over.
Returns
Quaternion at integrated configuration.

◆ Inverse()

Quaternion<T> Inverse ( ) const
inline

◆ Invert()

void Invert ( )
inline

Invert the quaternion.

◆ IsFinite()

bool IsFinite ( ) const
inline

See if a quaternion is finite (e.g., not nan)

Returns
True if quaternion is finite

◆ Log()

Quaternion<T> Log ( ) const
inline

Return the logarithm.

Returns
the log

◆ Matrix()

void Matrix ( const Matrix3< T > &  _mat)
inline

Set from a rotation matrix.

Parameters
[in]_matrotation matrix (must be orthogonal, the function doesn't check it)

Implementation inspired by http://www.euclideanspace.com/maths/geometry/rotations/ conversions/matrixToQuaternion/

Referenced by Quaternion< Precision >::Quaternion().

◆ Normalize()

◆ Normalized()

Quaternion<T> Normalized ( ) const
inline

Gets a normalized version of this quaternion.

Returns
a normalized quaternion

◆ operator!=()

bool operator!= ( const Quaternion< T > &  _qt) const
inline

Not equal to operator.

Parameters
[in]_qtQuaternion<T> for comparison
Returns
True if not equal

◆ operator*() [1/3]

Quaternion<T> operator* ( const Quaternion< T > &  _q) const
inline

Multiplication operator.

Parameters
[in]_qQuaternion<T> for multiplication
Returns
This quaternion multiplied by the parameter

◆ operator*() [2/3]

Quaternion<T> operator* ( const T &  _f) const
inline

Multiplication operator by a scalar.

Parameters
[in]_ffactor
Returns
quaternion multiplied by the scalar

◆ operator*() [3/3]

Vector3<T> operator* ( const Vector3< T > &  _v) const
inline

Vector3 multiplication operator.

Parameters
[in]_vvector to multiply
Returns
The result of the vector multiplication

◆ operator*=()

Quaternion<T> operator*= ( const Quaternion< T > &  _qt)
inline

Multiplication operator.

Parameters
[in]_qtQuaternion<T> for multiplication
Returns
This quaternion multiplied by the parameter

◆ operator+()

Quaternion<T> operator+ ( const Quaternion< T > &  _qt) const
inline

Addition operator.

Parameters
[in]_qtquaternion for addition
Returns
this quaternion + _qt

◆ operator+=()

Quaternion<T> operator+= ( const Quaternion< T > &  _qt)
inline

Addition operator.

Parameters
[in]_qtquaternion for addition
Returns
this quaternion + qt

◆ operator-() [1/2]

Quaternion<T> operator- ( const Quaternion< T > &  _qt) const
inline

Subtraction operator.

Parameters
[in]_qtquaternion to subtract
Returns
this quaternion - _qt

◆ operator-() [2/2]

Quaternion<T> operator- ( ) const
inline

Unary minus operator.

Returns
negates each component of the quaternion

◆ operator-=()

Quaternion<T> operator-= ( const Quaternion< T > &  _qt)
inline

Subtraction operator.

Parameters
[in]_qtQuaternion<T> for subtraction
Returns
This quaternion - qt

◆ operator=()

Quaternion<T>& operator= ( const Quaternion< T > &  _qt)
inline

Assignment operator.

Parameters
[in]_qtQuaternion<T> to copy

◆ operator==()

bool operator== ( const Quaternion< T > &  _qt) const
inline

Equal to operator.

Parameters
[in]_qtQuaternion<T> for comparison
Returns
True if equal

◆ Pitch()

T Pitch ( ) const
inline

Get the Euler pitch angle in radians.

Returns
the pitch component

◆ Roll()

T Roll ( ) const
inline

Get the Euler roll angle in radians.

Returns
the roll component

◆ RotateVector()

Vector3<T> RotateVector ( const Vector3< T > &  _vec) const
inline

Rotate a vector using the quaternion.

Parameters
[in]_vecvector to rotate
Returns
the rotated vector

◆ RotateVectorReverse()

Vector3<T> RotateVectorReverse ( const Vector3< T > &  _vec) const
inline

Do the reverse rotation of a vector by this quaternion.

Parameters
[in]_vecthe vector
Returns
the reversed vector

◆ Round()

void Round ( int  _precision)
inline

Round all values to _precision decimal places.

Parameters
[in]_precisionthe precision

◆ Scale()

void Scale ( _scale)
inline

Scale a Quaternion<T>

Parameters
[in]_scaleAmount to scale this rotation

◆ Set()

void Set ( _w,
_x,
_y,
_z 
)
inline

Set this quaternion from 4 floating numbers.

Parameters
[in]_ww
[in]_xx
[in]_yy
[in]_zz

◆ Slerp()

static Quaternion<T> Slerp ( _fT,
const Quaternion< T > &  _rkP,
const Quaternion< T > &  _rkQ,
bool  _shortestPath = false 
)
inlinestatic

Spherical linear interpolation between 2 quaternions, given the ends and an interpolation parameter between 0 and 1.

Parameters
[in]_fTthe interpolation parameter
[in]_rkPthe beginning quaternion
[in]_rkQthe end quaternion
[in]_shortestPathwhen true, the rotation may be inverted to get to minimize rotation
Returns
The result of the linear interpolation

Referenced by OnePoleQuaternion::Process(), and Quaternion< Precision >::Squad().

◆ Squad()

static Quaternion<T> Squad ( _fT,
const Quaternion< T > &  _rkP,
const Quaternion< T > &  _rkA,
const Quaternion< T > &  _rkB,
const Quaternion< T > &  _rkQ,
bool  _shortestPath = false 
)
inlinestatic

Spherical quadratic interpolation given the ends and an interpolation parameter between 0 and 1.

Parameters
[in]_fTthe interpolation parameter
[in]_rkPthe beginning quaternion
[in]_rkAfirst intermediate quaternion
[in]_rkBsecond intermediate quaternion
[in]_rkQthe end quaternion
[in]_shortestPathwhen true, the rotation may be inverted to get to minimize rotation
Returns
The result of the quadratic interpolation

◆ ToAxis()

void ToAxis ( Vector3< T > &  _axis,
T &  _angle 
) const
inline

Return rotation as axis and angle.

Parameters
[out]_axisrotation axis
[out]_angleccw angle in radians

Referenced by Quaternion< Precision >::Scale().

◆ W() [1/3]

const T& W ( ) const
inline

◆ W() [2/3]

T& W ( )
inline

Get a mutable w component.

Returns
The w quaternion component.

◆ W() [3/3]

void W ( _v)
inline

Set the w component.

Parameters
[in]_vThe new value for the w quaternion component.

◆ X() [1/3]

◆ X() [2/3]

T& X ( )
inline

Get a mutable x component.

Returns
The x quaternion component.

◆ X() [3/3]

void X ( _v)
inline

Set the x component.

Parameters
[in]_vThe new value for the x quaternion component.

◆ XAxis()

Vector3<T> XAxis ( ) const
inline

Return the X axis.

Returns
the X axis of the vector

◆ Y() [1/3]

◆ Y() [2/3]

T& Y ( )
inline

Get a mutable y component.

Returns
The y quaternion component.

◆ Y() [3/3]

void Y ( _v)
inline

Set the y component.

Parameters
[in]_vThe new value for the y quaternion component.

◆ Yaw()

T Yaw ( ) const
inline

Get the Euler yaw angle in radians.

Returns
the yaw component

◆ YAxis()

Vector3<T> YAxis ( ) const
inline

Return the Y axis.

Returns
the Y axis of the vector

◆ Z() [1/3]

◆ Z() [2/3]

T& Z ( )
inline

Get a mutable z component.

Returns
The z quaternion component.

◆ Z() [3/3]

void Z ( _v)
inline

Set the z component.

Parameters
[in]_vThe new value for the z quaternion component.

◆ ZAxis()

Vector3<T> ZAxis ( ) const
inline

Return the Z axis.

Returns
the Z axis of the vector

Friends And Related Function Documentation

◆ operator<<

std::ostream& operator<< ( std::ostream _out,
const Quaternion< T > &  _q 
)
friend

Stream insertion operator.

Parameters
[in]_outoutput stream
[in]_qquaternion to output
Returns
the stream

◆ operator>>

std::istream& operator>> ( std::istream _in,
Quaternion< T > &  _q 
)
friend

Stream extraction operator.

Parameters
[in]_ininput stream
[in]_qQuaternion<T> to read values into
Returns
The istream

Member Data Documentation

◆ Identity

const Quaternion< T > Identity
static

math::Quaternion(1, 0, 0, 0)

◆ Zero

const Quaternion< T > Zero
static

math::Quaternion(0, 0, 0, 0)


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