Quaternion Class Reference

A quaternion class. More...

#include <math/gzmath.hh>

Public Member Functions

 Quaternion ()
 Default Constructor. More...
 
 Quaternion (const double &_w, const double &_x, const double &_y, const double &_z) GAZEBO_DEPRECATED(8.0)
 Constructor. More...
 
 Quaternion (const double &_roll, const double &_pitch, const double &_yaw) GAZEBO_DEPRECATED(8.0)
 Constructor from Euler angles in radians. More...
 
 Quaternion (const Vector3 &_axis, const double &_angle) GAZEBO_DEPRECATED(8.0)
 Constructor from axis angle. More...
 
 Quaternion (const Vector3 &_rpy) GAZEBO_DEPRECATED(8.0)
 Constructor. More...
 
 Quaternion (const Quaternion &_qt) GAZEBO_DEPRECATED(8.0)
 Copy constructor. More...
 
 Quaternion (const ignition::math::Quaterniond &_qt) GAZEBO_DEPRECATED(8.0)
 Copy constructor for ignition::math::Quaterniond. More...
 
 ~Quaternion () GAZEBO_DEPRECATED(8.0)
 Destructor. More...
 
void Correct () GAZEBO_DEPRECATED(8.0)
 Correct any nan values in this quaternion. More...
 
double Dot (const Quaternion &_q) const GAZEBO_DEPRECATED(8.0)
 Dot product. More...
 
void GetAsAxis (Vector3 &_axis, double &_angle) const GAZEBO_DEPRECATED(8.0)
 Return rotation as axis and angle. More...
 
Vector3 GetAsEuler () const GAZEBO_DEPRECATED(8.0)
 Return the rotation in Euler angles. More...
 
Matrix3 GetAsMatrix3 () const GAZEBO_DEPRECATED(8.0)
 Get the quaternion as a 3x3 matrix. More...
 
Matrix4 GetAsMatrix4 () const GAZEBO_DEPRECATED(8.0)
 Get the quaternion as a 4x4 matrix. More...
 
Quaternion GetExp () const GAZEBO_DEPRECATED(8.0)
 Return the exponent. More...
 
Quaternion GetInverse () const GAZEBO_DEPRECATED(8.0)
 Get the inverse of this quaternion. More...
 
Quaternion GetLog () const GAZEBO_DEPRECATED(8.0)
 Return the logarithm. More...
 
double GetPitch () GAZEBO_DEPRECATED(8.0)
 Get the Euler pitch angle in radians. More...
 
double GetRoll () GAZEBO_DEPRECATED(8.0)
 Get the Euler roll angle in radians. More...
 
Vector3 GetXAxis () const GAZEBO_DEPRECATED(8.0)
 Return the X axis. More...
 
double GetYaw () GAZEBO_DEPRECATED(8.0)
 Get the Euler yaw angle in radians. More...
 
Vector3 GetYAxis () const GAZEBO_DEPRECATED(8.0)
 Return the Y axis. More...
 
Vector3 GetZAxis () const GAZEBO_DEPRECATED(8.0)
 Return the Z axis. More...
 
ignition::math::Quaterniond Ign () const GAZEBO_DEPRECATED(8.0)
 Convert this quaternion to an ignition::math::Quaterniond. More...
 
Quaternion Integrate (const Vector3 &_angularVelocity, const double _deltaT) const GAZEBO_DEPRECATED(8.0)
 Integrate quaternion for constant angular velocity vector along specified interval _deltaT. More...
 
void Invert () GAZEBO_DEPRECATED(8.0)
 Invert the quaternion. More...
 
bool IsFinite () const GAZEBO_DEPRECATED(8.0)
 See if a quaternion is finite (e.g., not nan) More...
 
void Normalize () GAZEBO_DEPRECATED(8.0)
 Normalize the quaternion. More...
 
bool operator!= (const Quaternion &_qt) const
 Not equal to operator. More...
 
Quaternion operator* (const Quaternion &_q) const GAZEBO_DEPRECATED(8.0)
 Multiplication operator. More...
 
Quaternion operator* (const double &_f) const GAZEBO_DEPRECATED(8.0)
 Multiplication operator by a scalar. More...
 
Vector3 operator* (const Vector3 &_v) const GAZEBO_DEPRECATED(8.0)
 Vector3 multiplication operator. More...
 
Quaternion operator*= (const Quaternion &qt) GAZEBO_DEPRECATED(8.0)
 Multiplication operator. More...
 
Quaternion operator+ (const Quaternion &_qt) const GAZEBO_DEPRECATED(8.0)
 Addition operator. More...
 
Quaternion operator+= (const Quaternion &_qt) GAZEBO_DEPRECATED(8.0)
 Addition operator. More...
 
Quaternion operator- (const Quaternion &_qt) const GAZEBO_DEPRECATED(8.0)
 Subtraction operator. More...
 
Quaternion operator- () const GAZEBO_DEPRECATED(8.0)
 Unary minus operator. More...
 
Quaternion operator-= (const Quaternion &_qt) GAZEBO_DEPRECATED(8.0)
 Subtraction operator. More...
 
Quaternionoperator= (const Quaternion &_qt) GAZEBO_DEPRECATED(8.0)
 Equal operator. More...
 
Quaternionoperator= (const ignition::math::Quaterniond &_v) GAZEBO_DEPRECATED(8.0)
 Assignment operator for ignition math. More...
 
bool operator== (const Quaternion &_qt) const
 Equal to operator. More...
 
Vector3 RotateVector (const Vector3 &_vec) const GAZEBO_DEPRECATED(8.0)
 Rotate a vector using the quaternion. More...
 
Vector3 RotateVectorReverse (Vector3 _vec) const GAZEBO_DEPRECATED(8.0)
 Do the reverse rotation of a vector by this quaternion. More...
 
void Round (int _precision) GAZEBO_DEPRECATED(8.0)
 Round all values to _precision decimal places. More...
 
void Scale (double _scale) GAZEBO_DEPRECATED(8.0)
 Scale a Quaternionion. More...
 
void Set (double _u, double _x, double _y, double _z) GAZEBO_DEPRECATED(8.0)
 Set this quaternion from 4 floating numbers. More...
 
void SetFromAxis (double _x, double _y, double _z, double _a) GAZEBO_DEPRECATED(8.0)
 Set the quaternion from an axis and angle. More...
 
void SetFromAxis (const Vector3 &_axis, double _a) GAZEBO_DEPRECATED(8.0)
 Set the quaternion from an axis and angle. More...
 
void SetFromEuler (const Vector3 &_vec) GAZEBO_DEPRECATED(8.0)
 Set the quaternion from Euler angles. More...
 
void SetFromEuler (double _roll, double _pitch, double _yaw) GAZEBO_DEPRECATED(8.0)
 Set the quaternion from Euler angles. More...
 
void SetToIdentity () GAZEBO_DEPRECATED(8.0)
 Set the quaternion to the identity. More...
 

Static Public Member Functions

static Quaternion EulerToQuaternion (const Vector3 &_vec) GAZEBO_DEPRECATED(8.0)
 Convert euler angles to a quaternion. More...
 
static Quaternion EulerToQuaternion (double _x, double _y, double _z) GAZEBO_DEPRECATED(8.0)
 Convert euler angles to quatern. More...
 
static Quaternion Slerp (double _fT, const Quaternion &_rkP, const Quaternion &_rkQ, bool _shortestPath=false) GAZEBO_DEPRECATED(8.0)
 Spherical linear interpolation between 2 quaternions, given the ends and an interpolation parameter between 0 and 1. More...
 
static Quaternion Squad (double _fT, const Quaternion &_rkP, const Quaternion &_rkA, const Quaternion &_rkB, const Quaternion &_rkQ, bool _shortestPath=false) GAZEBO_DEPRECATED(8.0)
 Spherical quadratic interpolation given the ends and an interpolation parameter between 0 and 1. More...
 

Public Attributes

double w
 w value of the quaternion More...
 
double x
 x value of the quaternion More...
 
double y
 y value of the quaternion More...
 
double z
 z value of the quaternion More...
 

Friends

std::ostream & operator<< (std::ostream &_out, const gazebo::math::Quaternion &_q) GAZEBO_DEPRECATED(8.0)
 Stream insertion operator. More...
 
std::istream & operator>> (std::istream &_in, gazebo::math::Quaternion &_q) GAZEBO_DEPRECATED(8.0)
 Stream extraction operator. More...
 

Detailed Description

A quaternion class.

Constructor & Destructor Documentation

Default Constructor.

Referenced by Quaternion::operator*().

Quaternion ( const double &  _w,
const double &  _x,
const double &  _y,
const double &  _z 
)

Constructor.

Parameters
[in]_wW param
[in]_xX param
[in]_yY param
[in]_zZ param
Quaternion ( const double &  _roll,
const double &  _pitch,
const double &  _yaw 
)

Constructor from Euler angles in radians.

Parameters
[in]_rollroll
[in]_pitchpitch
[in]_yawyaw
Quaternion ( const Vector3 _axis,
const double &  _angle 
)

Constructor from axis angle.

Parameters
[in]_axisthe rotation axis
[in]_anglethe rotation angle in radians
Quaternion ( const Vector3 _rpy)

Constructor.

Parameters
[in]_rpyeuler angles
Quaternion ( const Quaternion _qt)

Copy constructor.

Parameters
[in]_qtQuaternion to copy
Quaternion ( const ignition::math::Quaterniond &  _qt)

Copy constructor for ignition::math::Quaterniond.

Parameters
[in]_qtIgnition math quaterniond to copy
~Quaternion ( )

Destructor.

Member Function Documentation

void Correct ( )
inline

Correct any nan values in this quaternion.

References Quaternion::w, Quaternion::x, Quaternion::y, and Quaternion::z.

Referenced by Pose::Correct().

double Dot ( const Quaternion _q) const

Dot product.

Parameters
[in]_qthe other quaternion
Returns
the product
static Quaternion EulerToQuaternion ( const Vector3 _vec)
static

Convert euler angles to a quaternion.

Parameters
[in]_vecThe vector of angles to convert.
Returns
The converted quaternion.
static Quaternion EulerToQuaternion ( double  _x,
double  _y,
double  _z 
)
static

Convert euler angles to quatern.

Parameters
[in]_xrotation along x
[in]_yrotation along y
[in]_zrotation along z
Returns
The converted quaternion.
void GetAsAxis ( Vector3 _axis,
double &  _angle 
) const

Return rotation as axis and angle.

Parameters
[in]_axisrotation axis
[in]_angleccw angle in radians
Vector3 GetAsEuler ( ) const

Return the rotation in Euler angles.

Returns
This quaternion as an Euler vector
Matrix3 GetAsMatrix3 ( ) const

Get the quaternion as a 3x3 matrix.

Returns
The 3x3 matrix form of the quaternion
Matrix4 GetAsMatrix4 ( ) const

Get the quaternion as a 4x4 matrix.

Returns
a 4x4 matrix
Quaternion GetExp ( ) const

Return the exponent.

Returns
the exp
Quaternion GetInverse ( ) const
inline

Get the inverse of this quaternion.

Returns
Inverse quaternion

References Quaternion::w, Quaternion::x, Quaternion::y, and Quaternion::z.

Referenced by Pose::CoordPositionSub(), and Quaternion::RotateVector().

Quaternion GetLog ( ) const

Return the logarithm.

Returns
the log
double GetPitch ( )

Get the Euler pitch angle in radians.

Returns
the pitch component
double GetRoll ( )

Get the Euler roll angle in radians.

Returns
the roll component
Vector3 GetXAxis ( ) const

Return the X axis.

Returns
the X axis of the vector
double GetYaw ( )

Get the Euler yaw angle in radians.

Returns
the yaw component
Vector3 GetYAxis ( ) const

Return the Y axis.

Returns
the Y axis of the vector
Vector3 GetZAxis ( ) const

Return the Z axis.

Returns
the Z axis of the vector
ignition::math::Quaterniond Ign ( ) const

Convert this quaternion to an ignition::math::Quaterniond.

Returns
This quaternion as an ignition::math::Quaterniond.
Quaternion Integrate ( const Vector3 _angularVelocity,
const double  _deltaT 
) const

Integrate quaternion for constant angular velocity vector along specified interval _deltaT.

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.
void Invert ( )

Invert the quaternion.

bool IsFinite ( ) const

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

Returns
True if quaternion is finite
void Normalize ( )

Normalize the quaternion.

Referenced by Pose::CoordRotationSub().

bool operator!= ( const Quaternion _qt) const

Not equal to operator.

Parameters
[in]_qtQuaternion for comparison
Returns
True if not equal Note: not explicitly deprecated on purpose, because gtest catches it
Quaternion operator* ( const Quaternion _q) const
inline

Multiplication operator.

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

References Quaternion::Quaternion(), and Quaternion::w.

Quaternion operator* ( const double &  _f) const

Multiplication operator by a scalar.

Parameters
[in]_ffactor
Returns
quaternion multiplied by the scalar
Vector3 operator* ( const Vector3 _v) const

Vector3 multiplication operator.

Parameters
[in]_vvector to multiply
Returns
The result of the vector multiplication
Quaternion operator*= ( const Quaternion qt)

Multiplication operator.

Parameters
[in]_qtQuaternion for multiplication
Returns
This quaternion multiplied by the parameter
Quaternion operator+ ( const Quaternion _qt) const

Addition operator.

Parameters
[in]_qtquaternion for addition
Returns
this quaternion + _qt
Quaternion operator+= ( const Quaternion _qt)

Addition operator.

Parameters
[in]_qtquaternion for addition
Returns
this quaternion + qt
Quaternion operator- ( const Quaternion _qt) const

Subtraction operator.

Parameters
[in]_qtquaternion to subtract
Returns
this quaternion - _qt
Quaternion operator- ( ) const

Unary minus operator.

Returns
negates each component of the quaternion
Quaternion operator-= ( const Quaternion _qt)

Subtraction operator.

Parameters
[in]_qtQuaternion for subtraction
Returns
This quaternion - qt
Quaternion& operator= ( const Quaternion _qt)

Equal operator.

Parameters
[in]_qtQuaternion to copy
Quaternion& operator= ( const ignition::math::Quaterniond &  _v)

Assignment operator for ignition math.

Parameters
[in]_va new value
Returns
The new quaternion.
bool operator== ( const Quaternion _qt) const

Equal to operator.

Parameters
[in]_qtQuaternion for comparison
Returns
True if equal Note: not explicitly deprecated on purpose, because gtest catches it
Vector3 RotateVector ( const Vector3 _vec) const
inline

Rotate a vector using the quaternion.

Parameters
[in]_vecvector to rotate
Returns
the rotated vector

References Quaternion::GetInverse(), Quaternion::x, Quaternion::y, and Quaternion::z.

Vector3 RotateVectorReverse ( Vector3  _vec) const

Do the reverse rotation of a vector by this quaternion.

Parameters
[in]_vecthe vector
Returns
the reversed vector
void Round ( int  _precision)

Round all values to _precision decimal places.

Parameters
[in]_precisionthe precision
void Scale ( double  _scale)

Scale a Quaternionion.

Parameters
[in]_scaleAmount to scale this rotation
void Set ( double  _u,
double  _x,
double  _y,
double  _z 
)

Set this quaternion from 4 floating numbers.

Parameters
[in]_uu
[in]_xx
[in]_yy
[in]_zz
void SetFromAxis ( double  _x,
double  _y,
double  _z,
double  _a 
)

Set the quaternion from an axis and angle.

Parameters
[in]_xX axis
[in]_yY axis
[in]_zZ axis
[in]_aAngle in radians
void SetFromAxis ( const Vector3 _axis,
double  _a 
)

Set the quaternion from an axis and angle.

Parameters
[in]_axisAxis
[in]_aAngle in radians
void SetFromEuler ( const Vector3 _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.

Parameters
[in]_vecEuler angle
void SetFromEuler ( double  _roll,
double  _pitch,
double  _yaw 
)

Set the quaternion from Euler angles.

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

Set the quaternion to the identity.

static Quaternion Slerp ( double  _fT,
const Quaternion _rkP,
const Quaternion _rkQ,
bool  _shortestPath = false 
)
static

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

static Quaternion Squad ( double  _fT,
const Quaternion _rkP,
const Quaternion _rkA,
const Quaternion _rkB,
const Quaternion _rkQ,
bool  _shortestPath = false 
)
static

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

Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  _out,
const gazebo::math::Quaternion _q 
)
friend

Stream insertion operator.

Parameters
[in]_outoutput stream
[in]_qquaternion to output
Returns
the stream
std::istream& operator>> ( std::istream &  _in,
gazebo::math::Quaternion _q 
)
friend

Stream extraction operator.

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

Member Data Documentation

double w

w value of the quaternion

Referenced by Quaternion::Correct(), Quaternion::GetInverse(), and Quaternion::operator*().


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