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) | |
Constructor. More... | |
Quaternion (const double &_roll, const double &_pitch, const double &_yaw) | |
Constructor from Euler angles in radians. More... | |
Quaternion (const Vector3 &_axis, const double &_angle) | |
Constructor from axis angle. More... | |
Quaternion (const Vector3 &_rpy) | |
Constructor. More... | |
Quaternion (const Quaternion &_qt) | |
Copy constructor. More... | |
Quaternion (const ignition::math::Quaterniond &_qt) | |
Copy constructor for ignition::math::Quaterniond. More... | |
~Quaternion () | |
Destructor. More... | |
void | Correct () |
Correct any nan values in this quaternion. More... | |
double | Dot (const Quaternion &_q) const |
Dot product. More... | |
void | GetAsAxis (Vector3 &_axis, double &_angle) const |
Return rotation as axis and angle. More... | |
Vector3 | GetAsEuler () const |
Return the rotation in Euler angles. More... | |
Matrix3 | GetAsMatrix3 () const |
Get the quaternion as a 3x3 matrix. More... | |
Matrix4 | GetAsMatrix4 () const |
Get the quaternion as a 4x4 matrix. More... | |
Quaternion | GetExp () const |
Return the exponent. More... | |
Quaternion | GetInverse () const |
Get the inverse of this quaternion. More... | |
Quaternion | GetLog () const |
Return the logarithm. More... | |
double | GetPitch () |
Get the Euler pitch angle in radians. More... | |
double | GetRoll () |
Get the Euler roll angle in radians. More... | |
Vector3 | GetXAxis () const |
Return the X axis. More... | |
double | GetYaw () |
Get the Euler yaw angle in radians. More... | |
Vector3 | GetYAxis () const |
Return the Y axis. More... | |
Vector3 | GetZAxis () const |
Return the Z axis. More... | |
ignition::math::Quaterniond | Ign () const |
Convert this quaternion to an ignition::math::Quaterniond. More... | |
Quaternion | Integrate (const Vector3 &_angularVelocity, const double _deltaT) const |
Integrate quaternion for constant angular velocity vector along specified interval _deltaT . More... | |
void | Invert () |
Invert the quaternion. More... | |
bool | IsFinite () const |
See if a quaternion is finite (e.g., not nan) More... | |
void | Normalize () |
Normalize the quaternion. More... | |
bool | operator!= (const Quaternion &_qt) const |
Not equal to operator. More... | |
Quaternion | operator* (const Quaternion &_q) const |
Multiplication operator. More... | |
Quaternion | operator* (const double &_f) const |
Multiplication operator by a scalar. More... | |
Vector3 | operator* (const Vector3 &_v) const |
Vector3 multiplication operator. More... | |
Quaternion | operator*= (const Quaternion &qt) |
Multiplication operator. More... | |
Quaternion | operator+ (const Quaternion &_qt) const |
Addition operator. More... | |
Quaternion | operator+= (const Quaternion &_qt) |
Addition operator. More... | |
Quaternion | operator- (const Quaternion &_qt) const |
Subtraction operator. More... | |
Quaternion | operator- () const |
Unary minus operator. More... | |
Quaternion | operator-= (const Quaternion &_qt) |
Subtraction operator. More... | |
Quaternion & | operator= (const Quaternion &_qt) |
Equal operator. More... | |
Quaternion & | operator= (const ignition::math::Quaterniond &_v) |
Assignment operator for ignition math. More... | |
bool | operator== (const Quaternion &_qt) const |
Equal to operator. More... | |
Vector3 | RotateVector (const Vector3 &_vec) const |
Rotate a vector using the quaternion. More... | |
Vector3 | RotateVectorReverse (Vector3 _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 (double _scale) |
Scale a Quaternionion. More... | |
void | Set (double _u, double _x, double _y, double _z) |
Set this quaternion from 4 floating numbers. More... | |
void | SetFromAxis (double _x, double _y, double _z, double _a) |
Set the quaternion from an axis and angle. More... | |
void | SetFromAxis (const Vector3 &_axis, double _a) |
Set the quaternion from an axis and angle. More... | |
void | SetFromEuler (const Vector3 &_vec) |
Set the quaternion from Euler angles. More... | |
void | SetFromEuler (double _roll, double _pitch, double _yaw) |
Set the quaternion from Euler angles. More... | |
void | SetToIdentity () |
Set the quaternion to the identity. More... | |
Static Public Member Functions | |
static Quaternion | EulerToQuaternion (const Vector3 &_vec) |
Convert euler angles to a quaternion. More... | |
static Quaternion | EulerToQuaternion (double _x, double _y, double _z) |
Convert euler angles to quatern. More... | |
static Quaternion | Slerp (double _fT, const Quaternion &_rkP, const Quaternion &_rkQ, bool _shortestPath=false) |
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) |
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) |
Stream insertion operator. More... | |
std::istream & | operator>> (std::istream &_in, gazebo::math::Quaternion &_q) |
Stream extraction operator. More... | |
A quaternion class.
Quaternion | ( | ) |
Default Constructor.
Referenced by Quaternion::operator*().
Quaternion | ( | const double & | _w, |
const double & | _x, | ||
const double & | _y, | ||
const double & | _z | ||
) |
Constructor.
[in] | _w | W param |
[in] | _x | X param |
[in] | _y | Y param |
[in] | _z | Z param |
Quaternion | ( | const double & | _roll, |
const double & | _pitch, | ||
const double & | _yaw | ||
) |
Constructor from Euler angles in radians.
[in] | _roll | roll |
[in] | _pitch | pitch |
[in] | _yaw | yaw |
Quaternion | ( | const Vector3 & | _axis, |
const double & | _angle | ||
) |
Constructor from axis angle.
[in] | _axis | the rotation axis |
[in] | _angle | the rotation angle in radians |
Quaternion | ( | const Vector3 & | _rpy | ) |
Constructor.
[in] | _rpy | euler angles |
Quaternion | ( | const Quaternion & | _qt | ) |
Copy constructor.
[in] | _qt | Quaternion to copy |
Quaternion | ( | const ignition::math::Quaterniond & | _qt | ) |
Copy constructor for ignition::math::Quaterniond.
[in] | _qt | Ignition math quaterniond to copy |
~Quaternion | ( | ) |
Destructor.
|
inline |
Correct any nan values in this quaternion.
References Quaternion::Dot(), gazebo::math::equal(), Quaternion::GetAsMatrix3(), Quaternion::GetAsMatrix4(), Quaternion::GetXAxis(), Quaternion::GetYAxis(), Quaternion::GetZAxis(), Quaternion::Integrate(), Quaternion::Round(), Quaternion::Slerp(), Quaternion::Squad(), Quaternion::w, Quaternion::x, Quaternion::y, and Quaternion::z.
Referenced by Pose::Correct().
double Dot | ( | const Quaternion & | _q | ) | const |
Dot product.
[in] | _q | the other quaternion |
Referenced by Quaternion::Correct().
|
static |
Convert euler angles to a quaternion.
[in] | _vec | The vector of angles to convert. |
Referenced by Quaternion::GetInverse().
|
static |
Convert euler angles to quatern.
[in] | _x | rotation along x |
[in] | _y | rotation along y |
[in] | _z | rotation along z |
void GetAsAxis | ( | Vector3 & | _axis, |
double & | _angle | ||
) | const |
Return rotation as axis and angle.
[in] | _axis | rotation axis |
[in] | _angle | ccw angle in radians |
Referenced by Quaternion::GetInverse().
Vector3 GetAsEuler | ( | ) | const |
Return the rotation in Euler angles.
Referenced by Quaternion::GetInverse().
Matrix3 GetAsMatrix3 | ( | ) | const |
Get the quaternion as a 3x3 matrix.
Referenced by Quaternion::Correct().
Matrix4 GetAsMatrix4 | ( | ) | const |
Quaternion GetExp | ( | ) | const |
|
inline |
Get the inverse of this quaternion.
References gazebo::math::equal(), Quaternion::EulerToQuaternion(), Quaternion::GetAsAxis(), Quaternion::GetAsEuler(), Quaternion::GetExp(), Quaternion::GetLog(), Quaternion::GetPitch(), Quaternion::GetRoll(), Quaternion::GetYaw(), Quaternion::Normalize(), Quaternion::operator+(), Quaternion::operator+=(), Quaternion::operator-(), Quaternion::operator-=(), Quaternion::Scale(), Quaternion::Set(), Quaternion::SetFromAxis(), Quaternion::SetFromEuler(), Quaternion::SetToIdentity(), Quaternion::w, Quaternion::x, Quaternion::y, and Quaternion::z.
Referenced by Pose::CoordPositionSub(), Pose::CoordRotationSub(), and Quaternion::RotateVector().
Quaternion GetLog | ( | ) | const |
double GetPitch | ( | ) |
Get the Euler pitch angle in radians.
Referenced by Quaternion::GetInverse().
double GetRoll | ( | ) |
Get the Euler roll angle in radians.
Referenced by Quaternion::GetInverse().
Vector3 GetXAxis | ( | ) | const |
double GetYaw | ( | ) |
Get the Euler yaw angle in radians.
Referenced by Quaternion::GetInverse().
Vector3 GetYAxis | ( | ) | const |
Vector3 GetZAxis | ( | ) | const |
ignition::math::Quaterniond Ign | ( | ) | const |
Convert this quaternion to an ignition::math::Quaterniond.
Quaternion Integrate | ( | const Vector3 & | _angularVelocity, |
const double | _deltaT | ||
) | const |
Integrate quaternion for constant angular velocity vector along specified interval _deltaT
.
[in] | _angularVelocity | Angular velocity vector, specified in same reference frame as base of this quaternion. |
[in] | _deltaT | Time interval in seconds to integrate over. |
Referenced by Quaternion::Correct().
void Invert | ( | ) |
Invert the quaternion.
bool IsFinite | ( | ) | const |
See if a quaternion is finite (e.g., not nan)
Referenced by Quaternion::RotateVector().
void Normalize | ( | ) |
Normalize the quaternion.
Referenced by Pose::CoordRotationSub(), and Quaternion::GetInverse().
bool operator!= | ( | const Quaternion & | _qt | ) | const |
Not equal to operator.
[in] | _qt | Quaternion for comparison |
Referenced by Quaternion::operator*().
|
inline |
Multiplication operator.
[in] | _q | Quaternion for multiplication |
References Quaternion::operator!=(), Quaternion::operator*=(), Quaternion::operator-(), Quaternion::operator==(), Quaternion::Quaternion(), Quaternion::w, Quaternion::x, Quaternion::y, and Quaternion::z.
Quaternion operator* | ( | const double & | _f | ) | const |
Multiplication operator by a scalar.
[in] | _f | factor |
Vector3 multiplication operator.
[in] | _v | vector to multiply |
Quaternion operator*= | ( | const Quaternion & | qt | ) |
Multiplication operator.
[in] | _qt | Quaternion for multiplication |
Referenced by Quaternion::operator*().
Quaternion operator+ | ( | const Quaternion & | _qt | ) | const |
Addition operator.
[in] | _qt | quaternion for addition |
Referenced by Quaternion::GetInverse().
Quaternion operator+= | ( | const Quaternion & | _qt | ) |
Addition operator.
[in] | _qt | quaternion for addition |
Referenced by Quaternion::GetInverse().
Quaternion operator- | ( | const Quaternion & | _qt | ) | const |
Subtraction operator.
[in] | _qt | quaternion to subtract |
Quaternion operator- | ( | ) | const |
Unary minus operator.
Referenced by Quaternion::GetInverse(), and Quaternion::operator*().
Quaternion operator-= | ( | const Quaternion & | _qt | ) |
Subtraction operator.
[in] | _qt | Quaternion for subtraction |
Referenced by Quaternion::GetInverse().
Quaternion& operator= | ( | const Quaternion & | _qt | ) |
Equal operator.
[in] | _qt | Quaternion to copy |
Quaternion& operator= | ( | const ignition::math::Quaterniond & | _v | ) |
Assignment operator for ignition math.
[in] | _v | a new value |
bool operator== | ( | const Quaternion & | _qt | ) | const |
Equal to operator.
[in] | _qt | Quaternion for comparison |
Referenced by Quaternion::operator*().
Rotate a vector using the quaternion.
[in] | _vec | vector to rotate |
References Quaternion::GetInverse(), Quaternion::IsFinite(), Quaternion::RotateVectorReverse(), Vector3::x, Quaternion::x, Vector3::y, Quaternion::y, Vector3::z, and Quaternion::z.
Do the reverse rotation of a vector by this quaternion.
[in] | _vec | the vector |
Referenced by Quaternion::RotateVector().
void Round | ( | int | _precision | ) |
Round all values to _precision decimal places.
[in] | _precision | the precision |
Referenced by Quaternion::Correct().
void Scale | ( | double | _scale | ) |
Scale a Quaternionion.
[in] | _scale | Amount to scale this rotation |
Referenced by Quaternion::GetInverse().
void Set | ( | double | _u, |
double | _x, | ||
double | _y, | ||
double | _z | ||
) |
Set this quaternion from 4 floating numbers.
[in] | _u | u |
[in] | _x | x |
[in] | _y | y |
[in] | _z | z |
Referenced by Quaternion::GetInverse().
void SetFromAxis | ( | double | _x, |
double | _y, | ||
double | _z, | ||
double | _a | ||
) |
Set the quaternion from an axis and angle.
[in] | _x | X axis |
[in] | _y | Y axis |
[in] | _z | Z axis |
[in] | _a | Angle in radians |
Referenced by Quaternion::GetInverse().
void SetFromAxis | ( | const Vector3 & | _axis, |
double | _a | ||
) |
Set the quaternion from an axis and angle.
[in] | _axis | Axis |
[in] | _a | Angle 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.
[in] | _vec | Euler angle |
Referenced by Quaternion::GetInverse().
void SetFromEuler | ( | double | _roll, |
double | _pitch, | ||
double | _yaw | ||
) |
Set the quaternion from Euler angles.
[in] | _roll | Roll angle (radians). |
[in] | _pitch | Pitch angle (radians). |
[in] | _yaw | Yaw angle (radians). |
void SetToIdentity | ( | ) |
Set the quaternion to the identity.
Referenced by Quaternion::GetInverse().
|
static |
Spherical linear interpolation between 2 quaternions, given the ends and an interpolation parameter between 0 and 1.
[in] | _ft | the interpolation parameter |
[in] | _rkP | the beginning quaternion |
[in] | _rkQ | the end quaternion |
[in] | _shortestPath | when true, the rotation may be inverted to get to minimize rotation |
Referenced by Quaternion::Correct(), and OnePoleQuaternion::Process().
|
static |
Spherical quadratic interpolation given the ends and an interpolation parameter between 0 and 1.
[in] | _ft | the interpolation parameter |
[in] | _rkP | the beginning quaternion |
[in] | _rkA | first intermediate quaternion |
[in] | _rkB | second intermediate quaternion |
[in] | _rkQ | the end quaternion |
[in] | _shortestPath | when true, the rotation may be inverted to get to minimize rotation |
Referenced by Quaternion::Correct().
|
friend |
Stream insertion operator.
[in] | _out | output stream |
[in] | _q | quaternion to output |
|
friend |
Stream extraction operator.
[in] | _in | input stream |
[in] | _q | Quaternion to read values into |
double w |
w value of the quaternion
Referenced by BulletTypes::ConvertPose(), DARTTypes::ConvQuat(), Quaternion::Correct(), Quaternion::GetInverse(), and Quaternion::operator*().
double x |
x value of the quaternion
Referenced by BulletTypes::ConvertPose(), DARTTypes::ConvQuat(), Pose::CoordPositionSub(), Quaternion::Correct(), Quaternion::GetInverse(), Quaternion::operator*(), and Quaternion::RotateVector().
double y |
y value of the quaternion
Referenced by BulletTypes::ConvertPose(), DARTTypes::ConvQuat(), Pose::CoordPositionSub(), Quaternion::Correct(), Quaternion::GetInverse(), Quaternion::operator*(), and Quaternion::RotateVector().
double z |
z value of the quaternion
Referenced by BulletTypes::ConvertPose(), DARTTypes::ConvQuat(), Pose::CoordPositionSub(), Quaternion::Correct(), Quaternion::GetInverse(), Quaternion::operator*(), and Quaternion::RotateVector().