Gazebo Math

API Reference

7.4.0

A quaternion class that represents 3D rotations and orientations. Four scalar values, [w,x,y,z], are used represent orientations and rotations. More...

#include <gz/math/Quaternion.hh>

Public Member Functions

constexpr Quaternion ()
 Default Constructor. More...
 
 Quaternion (const Matrix3< T > &_mat)
 Construct from rotation matrix. This constructor does not normalize the quaternion. More...
 
 Quaternion (const Quaternion< T > &_qt)=default
 Copy constructor. This constructor does not normalize the quaternion. More...
 
 Quaternion (const T &_roll, const T &_pitch, const T &_yaw)
 Construct a Quaternion from Euler angles, in radians. This constructor normalizes the quaternion. More...
 
constexpr Quaternion (const T &_w, const T &_x, const T &_y, const T &_z)
 Constructor that initializes each value, [w, x, y, z], of the quaternion. This constructor does not normalize the quaternion. More...
 
 Quaternion (const Vector3< T > &_axis, const T &_angle)
 Constructor from an axis and angle. This constructor normalizes the quaternion. More...
 
 Quaternion (const Vector3< T > &_rpy)
 Construct a Quaternion from Euler angles, in radians. This constructor normalizes the quaternion. More...
 
 ~Quaternion ()=default
 Destructor. More...
 
void Axis (const Vector3< T > &_axis, T _a)
 Set the quaternion from an axis and angle. More...
 
void Axis (T _ax, T _ay, T _az, T _aa)
 Set the quaternion from an axis and angle. More...
 
void AxisAngle (Vector3< T > &_axis, T &_angle) const
 Convert this quaternion to an axis and angle. More...
 
void Correct ()
 Correct any nan values in this quaternion. More...
 
Dot (const Quaternion< T > &_q) const
 Get the dot product of this quaternion with the give _q quaternion. More...
 
bool Equal (const Quaternion &_q, const T &_tol) const
 Equality comparison test with a tolerance parameter. The tolerance is used with the equal function for each component of the quaternions. More...
 
Vector3< T > Euler () const
 Return the rotation in Euler angles, in radians. 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...
 
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. The quaternion is first normalized, then inverted. 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. A tolerance of 0.001 is used with the equal function for each component of the quaternions. 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 set operator. More...
 
Quaternion< T > operator+ (const Quaternion< T > &_qt) const
 Addition operator. More...
 
Quaternion< T > operator+= (const Quaternion< T > &_qt)
 Addition set operator. More...
 
Quaternion< T > operator- () const
 Unary minus operator. More...
 
Quaternion< T > operator- (const Quaternion< T > &_qt) const
 Subtraction operator. More...
 
Quaternion< T > operator-= (const Quaternion< T > &_qt)
 Subtraction set operator. More...
 
Quaternion< T > & operator= (const Quaternion< T > &_qt)=default
 Assignment operator. More...
 
bool operator== (const Quaternion< T > &_qt) const
 Equality comparison operator. A tolerance of 0.001 is used with the equal function for each component of the quaternions. 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
 Get 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 this quaternion. More...
 
void Set (T _w, T _x, T _y, T _z)
 Set this quaternion from 4 floating numbers. More...
 
void SetFrom2Axes (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...
 
void SetFromAxisAngle (const Vector3< T > &_axis, T _a)
 Set the quaternion from an axis and angle. More...
 
void SetFromAxisAngle (T _ax, T _ay, T _az, T _aa)
 Set the quaternion from an axis and angle. More...
 
void SetFromEuler (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 SetFromEuler (T _roll, T _pitch, T _yaw)
 Set the quaternion from Euler angles. More...
 
void SetFromMatrix (const Matrix3< T > &_mat)
 Set from a rotation matrix. More...
 
void SetW (T _v)
 Set the w component. More...
 
void SetX (T _v)
 Set the x component. More...
 
void SetY (T _v)
 Set the y component. More...
 
void SetZ (T _v)
 Set the z component. More...
 
void ToAxis (Vector3< T > &_axis, T &_angle) const
 Return rotation as axis and angle. More...
 
T & W ()
 Get a mutable w component. More...
 
W () const
 Get the w component. More...
 
void W (T _v)
 Set the w component. More...
 
T & X ()
 Get a mutable x component. More...
 
X () const
 Get the x component. More...
 
void X (T _v)
 Set the x component. More...
 
Vector3< T > XAxis () const
 Return the X axis. More...
 
T & Y ()
 Get a mutable y component. More...
 
Y () const
 Get the 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...
 
T & Z ()
 Get a mutable z component. More...
 
Z () const
 Get the 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 a quaternion. More...
 
static Quaternion< T > EulerToQuaternion (T _x, T _y, T _z)
 Convert Euler angles, in radians, to a quaternion. 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 QuaternionIdentity = detail::gQuaternionIdentity<T>
 A Quaternion initialized to identity. This is equivalent to math::Quaternion<T>(1, 0, 0, 0) More...
 
static const QuaternionZero = detail::gQuaternionZero<T>
 A Quaternion initialized to zero. This is equivalent to math::Quaternion<T>(0, 0, 0, 0) More...
 

Detailed Description

A quaternion class that represents 3D rotations and orientations. Four scalar values, [w,x,y,z], are used represent orientations and rotations.

The following two type definitions are provided:

Examples

  • C++
#include <stdio.h>
int main(int argc, char **argv)
{
// Construct a default quaternion.
printf("A default quaternion has the following values\n" \
"\tW=%f X=%f Y=%f Z=%f\n", q.W(), q.X(), q.Y(), q.Z());
// Set the quaternion to [1, 0, 0, 0], the identity.
printf("The identity quaternion has the following values\n" \
"\tW=%f X=%f Y=%f Z=%f\n", q.W(), q.X(), q.Y(), q.Z());
// Create a new quaternion using Euler angles.
gz::math::Quaterniond q2(0, 0, 3.14);
printf("A quaternion initialized from roll=0, pitch=0, and yaw=3.14 has"\
"the following values\n" \
"\tW=%f X=%f Y=%f Z=%f\n", q2.W(), q2.X(), q2.Y(), q2.Z());
// Get the Euler angles back from the quaternion.
gz::math::Vector3d euler = q2.Euler();
printf("Getting back the euler angles from the quaternion\n"\
"\troll=%f pitch=%f yaw=%f\n", euler.X(), euler.Y(), euler.Z());
}
  • Ruby
# Modify the RUBYLIB environment variable to include the Gazebo Math
# library install path. For example, if you install to /user:
#
# $ export RUBYLIB=/usr/lib/ruby:$RUBYLIB
#
require 'gz/math'
q = Gz::Math::Quaterniond.new
printf("A default quaternion has the following values\n"+
"\tW=%f X=%f Y=%f Z=%f\n", q.W(), q.X(), q.Y(), q.Z())
q = Gz::Math::Quaterniond.Identity
printf("The identity quaternion has the following values\n" +
"\tW=%f X=%f Y=%f Z=%f\n", q.W(), q.X(), q.Y(), q.Z())
q2 = Gz::Math::Quaterniond.new(0, 0, 3.14)
printf("A quaternion initialized from roll=0, pitch=0, and yaw=3.14 " +
"has the following values\n" +
"\tW=%f X=%f Y=%f Z=%f\n", q2.W(), q2.X(), q2.Y(), q2.Z())
euler = q2.Euler()
printf("Getting back the euler angles from the quaternion\n" +
"\troll=%f pitch=%f yaw=%f\n", euler.X(), euler.Y(), euler.Z())

Constructor & Destructor Documentation

◆ Quaternion() [1/7]

constexpr Quaternion ( )
inlineconstexpr

Default Constructor.

◆ Quaternion() [2/7]

constexpr Quaternion ( const T &  _w,
const T &  _x,
const T &  _y,
const T &  _z 
)
inlineconstexpr

Constructor that initializes each value, [w, x, y, z], of the quaternion. This constructor does not normalize the quaternion.

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

Construct a Quaternion from Euler angles, in radians. This constructor normalizes the quaternion.

Parameters
[in]_rollRoll radians.
[in]_pitchPitch radians.
[in]_yawYaw radians.
See also
SetFromEuler(T, T, T)

◆ Quaternion() [4/7]

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

Constructor from an axis and angle. This constructor normalizes the quaternion.

Parameters
[in]_axisThe rotation axis.
[in]_angleThe rotation angle in radians.

◆ Quaternion() [5/7]

Quaternion ( const Vector3< T > &  _rpy)
inlineexplicit

Construct a Quaternion from Euler angles, in radians. This constructor normalizes the quaternion.

Parameters
[in]_rpyEuler angles in radians.

◆ Quaternion() [6/7]

Quaternion ( const Matrix3< T > &  _mat)
inlineexplicit

Construct from rotation matrix. This constructor does not normalize the quaternion.

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

◆ Quaternion() [7/7]

Quaternion ( const Quaternion< T > &  _qt)
default

Copy constructor. This constructor does not normalize the quaternion.

Parameters
[in]_qtQuaternion<T> to copy

◆ ~Quaternion()

~Quaternion ( )
default

Destructor.

Member Function Documentation

◆ Axis() [1/2]

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

Set the quaternion from an axis and angle.

Parameters
[in]_axisAxis
[in]_aAngle in radians
Deprecated:
Use SetFromAxisAngle(const Vector3<T> &_axis, T _a)

◆ Axis() [2/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
Deprecated:
Use SetFromAxisAngle(T, T, T, T)

◆ AxisAngle()

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

Convert this quaternion to an axis and angle.

Parameters
[out]_axisRotation axis.
[out]_angleCCW angle in radians.

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

◆ Correct()

void Correct ( )
inline

Correct any nan values in this quaternion.

Referenced by Pose3< T >::Correct().

◆ Dot()

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

Get the dot product of this quaternion with the give _q quaternion.

Parameters
[in]_qThe other quaternion.
Returns
The dot product.

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

◆ Equal()

bool Equal ( const Quaternion _q,
const T &  _tol 
) const
inline

Equality comparison test with a tolerance parameter. The tolerance is used with the equal function for each component of the quaternions.

Parameters
[in]_qThe quaternion to compare against.
[in]_tolequality tolerance.
Returns
True if the elements of the quaternions are equal within the tolerence specified by _tol.

Referenced by Pose3< T >::Equal(), and Quaternion< Precision >::operator==().

◆ Euler() [1/3]

Vector3<T> Euler ( ) const
inline

Return the rotation in Euler angles, in radians.

Returns
This quaternion as Euler angles.

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

◆ Euler() [2/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
Deprecated:
Use SetFromEuler(const Vector3<T> &)

◆ Euler() [3/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).
Deprecated:
Use SetFromEuler(T, T, T)

◆ EulerToQuaternion() [1/2]

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

Convert Euler angles to a quaternion.

Parameters
[in]_vecThe vector of angles, in radians, to convert.
Returns
The resulting quaternion

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

◆ EulerToQuaternion() [2/2]

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

Convert Euler angles, in radians, to a quaternion.

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

◆ Exp()

Quaternion<T> Exp ( ) const
inline

Return the exponent.

If q = A*(x*i+y*j+z*k) where (x, y, z) is unit length, then exp(q) = cos(A)+sin(A)*(x*i+y*j+z*k). If sin(A) is near zero, use exp(q) = cos(A)+A*(x*i+y*j+z*k) since A/sin(A) has limit 1.

Returns
The exponent.

◆ 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

Deprecated:
Use SetFrom2Axes(const Vector3<T> &, const Vector3<T> &)

◆ 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()

◆ Invert()

void Invert ( )
inline

Invert the quaternion. The quaternion is first normalized, then inverted.

◆ IsFinite()

bool IsFinite ( ) const
inline

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

Returns
True if quaternion is finite.

Referenced by Pose3< T >::IsFinite().

◆ Log()

Quaternion<T> Log ( ) const
inline

Return the logarithm.

If q = cos(A)+sin(A)*(x*i+y*j+z*k) where (x, y, z) is unit length, then log(q) = A*(x*i+y*j+z*k). If sin(A) is near zero, use log(q) = sin(A)*(x*i+y*j+z*k) since sin(A)/A has limit 1.

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/

Deprecated:
Use SetFromMatrix(const Matrix3<T>&)

◆ 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. A tolerance of 0.001 is used with the equal function for each component of the quaternions.

Parameters
[in]_qtQuaternion for comparison.
Returns
True if any component of both quaternions is not within the tolerance of 0.001 of its counterpart.

◆ operator*() [1/3]

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

Multiplication operator.

Parameters
[in]_qQuaternion 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 set 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 set operator.

Parameters
[in]_qtQuaternion for addition.
Returns
This quaternion + qt.

◆ operator-() [1/2]

Quaternion<T> operator- ( ) const
inline

Unary minus operator.

Returns
Negation of each component of this quaternion.

◆ operator-() [2/2]

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

Subtraction operator.

Parameters
[in]_qtQuaternion to subtract.
Returns
This quaternion - _qt

◆ operator-=()

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

Subtraction set operator.

Parameters
[in]_qtQuaternion for subtraction.
Returns
This quaternion - qt.

◆ operator=()

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

Assignment operator.

Parameters
[in]_qtQuaternion<T> to copy

◆ operator==()

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

Equality comparison operator. A tolerance of 0.001 is used with the equal function for each component of the quaternions.

Parameters
[in]_qtQuaternion<T> for comparison.
Returns
True if each component of both quaternions is within the tolerance of 0.001 of its counterpart.

◆ Pitch()

T Pitch ( ) const
inline

Get the Euler pitch angle in radians.

Returns
The pitch component.

Referenced by Pose3< T >::Pitch().

◆ Roll()

T Roll ( ) const
inline

Get the Euler roll angle in radians.

Returns
The roll component.

Referenced by Pose3< T >::Roll().

◆ 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

Get 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.

Referenced by Pose3< T >::Round().

◆ Scale()

void Scale ( _scale)
inline

Scale this quaternion.

Parameters
[in]_scaleAmount to scale this quaternion

◆ Set()

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

Set this quaternion from 4 floating numbers.

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

◆ SetFrom2Axes()

void SetFrom2Axes ( 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

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

◆ SetFromAxisAngle() [1/2]

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

Set the quaternion from an axis and angle.

Parameters
[in]_axisAxis
[in]_aAngle in radians

◆ SetFromAxisAngle() [2/2]

void SetFromAxisAngle ( _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(), Quaternion< Precision >::Scale(), and Quaternion< Precision >::SetFromAxisAngle().

◆ SetFromEuler() [1/2]

void SetFromEuler ( 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 angles in radians.

Referenced by Quaternion< Precision >::Euler(), Quaternion< Precision >::EulerToQuaternion(), Quaternion< Precision >::Quaternion(), Pose3< T >::Set(), and Quaternion< Precision >::SetFromEuler().

◆ SetFromEuler() [2/2]

void SetFromEuler ( _roll,
_pitch,
_yaw 
)
inline

Set the quaternion from Euler angles.

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

◆ SetFromMatrix()

void SetFromMatrix ( 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 >::Matrix(), and Quaternion< Precision >::Quaternion().

◆ SetW()

void SetW ( _v)
inline

Set the w component.

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

Referenced by Matrix4< T >::Rotation(), and Quaternion< Precision >::W().

◆ SetX()

void SetX ( _v)
inline

Set the x component.

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

Referenced by Matrix4< T >::Rotation(), and Quaternion< Precision >::X().

◆ SetY()

void SetY ( _v)
inline

Set the y component.

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

Referenced by Matrix4< T >::Rotation(), and Quaternion< Precision >::Y().

◆ SetZ()

void SetZ ( _v)
inline

Set the z component.

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

Referenced by Matrix4< T >::Rotation(), and Quaternion< Precision >::Z().

◆ 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
Deprecated:
Use AxisAngle(Vector3<T> &_axis, T &_angle) const

◆ W() [1/3]

T& W ( )
inline

Get a mutable w component.

Returns
The w quaternion component.

◆ W() [2/3]

T W ( ) const
inline

◆ W() [3/3]

void W ( _v)
inline

Set the w component.

Parameters
[in]_vThe new value for the w quaternion component.
Deprecated:
Use SetW(T)

◆ X() [1/3]

T& X ( )
inline

Get a mutable x component.

Returns
The x quaternion component.

◆ X() [2/3]

◆ X() [3/3]

void X ( _v)
inline

Set the x component.

Parameters
[in]_vThe new value for the x quaternion component.
Deprecated:
Use SetX(T)

◆ XAxis()

Vector3<T> XAxis ( ) const
inline

Return the X axis.

Returns
the X axis of the vector.

◆ Y() [1/3]

T& Y ( )
inline

Get a mutable y component.

Returns
The y quaternion component.

◆ Y() [2/3]

◆ Y() [3/3]

void Y ( _v)
inline

Set the y component.

Parameters
[in]_vThe new value for the y quaternion component.
Deprecated:
Use SetY(T)

◆ Yaw()

T Yaw ( ) const
inline

Get the Euler yaw angle in radians.

Returns
The yaw component.

Referenced by Pose3< T >::Yaw().

◆ YAxis()

Vector3<T> YAxis ( ) const
inline

Return the Y axis.

Returns
the Y axis of the vector.

◆ Z() [1/3]

T& Z ( )
inline

Get a mutable z component.

Returns
The z quaternion component.

◆ Z() [2/3]

◆ Z() [3/3]

void Z ( _v)
inline

Set the z component.

Parameters
[in]_vThe new value for the z quaternion component.
Deprecated:
Use SetZ(T)

◆ ZAxis()

Vector3<T> ZAxis ( ) const
inline

Return the Z axis.

Returns
the Z axis of the vector.

Member Data Documentation

◆ Identity

const Quaternion< T > & Identity = detail::gQuaternionIdentity<T>
static

A Quaternion initialized to identity. This is equivalent to math::Quaternion<T>(1, 0, 0, 0)

◆ Zero

const Quaternion< T > & Zero = detail::gQuaternionZero<T>
static

A Quaternion initialized to zero. This is equivalent to math::Quaternion<T>(0, 0, 0, 0)


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