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... | |
| Quaternion & | operator= (const Quaternion &_qt) GAZEBO_DEPRECATED(8.0) |
| Equal operator. More... | |
| Quaternion & | operator= (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... | |
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::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 |
|
static |
Convert euler angles to a quaternion.
| [in] | _vec | The vector of angles to convert. |
|
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 |
| Vector3 GetAsEuler | ( | ) | const |
Return the rotation in Euler angles.
| Matrix3 GetAsMatrix3 | ( | ) | const |
Get the quaternion as a 3x3 matrix.
| Matrix4 GetAsMatrix4 | ( | ) | const |
Get the quaternion as a 4x4 matrix.
| Quaternion GetExp | ( | ) | const |
Return the exponent.
|
inline |
Get the inverse of this quaternion.
References Quaternion::w, Quaternion::x, Quaternion::y, and Quaternion::z.
Referenced by Pose::CoordPositionSub(), and Quaternion::RotateVector().
| Quaternion GetLog | ( | ) | const |
Return the logarithm.
| double GetPitch | ( | ) |
Get the Euler pitch angle in radians.
| double GetRoll | ( | ) |
Get the Euler roll angle in radians.
| Vector3 GetXAxis | ( | ) | const |
Return the X axis.
| double GetYaw | ( | ) |
Get the Euler yaw angle in radians.
| Vector3 GetYAxis | ( | ) | const |
Return the Y axis.
| Vector3 GetZAxis | ( | ) | const |
Return the Z axis.
| 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. |
| void Invert | ( | ) |
Invert the quaternion.
| bool IsFinite | ( | ) | const |
See if a quaternion is finite (e.g., not nan)
| void Normalize | ( | ) |
Normalize the quaternion.
Referenced by Pose::CoordRotationSub().
| bool operator!= | ( | const Quaternion & | _qt | ) | const |
Not equal to operator.
| [in] | _qt | Quaternion for comparison |
|
inline |
Multiplication operator.
| [in] | _q | Quaternion for multiplication |
References Quaternion::Quaternion(), and Quaternion::w.
| 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 |
| Quaternion operator+ | ( | const Quaternion & | _qt | ) | const |
Addition operator.
| [in] | _qt | quaternion for addition |
| Quaternion operator+= | ( | const Quaternion & | _qt | ) |
Addition operator.
| [in] | _qt | quaternion for addition |
| Quaternion operator- | ( | const Quaternion & | _qt | ) | const |
Subtraction operator.
| [in] | _qt | quaternion to subtract |
| Quaternion operator- | ( | ) | const |
Unary minus operator.
| Quaternion operator-= | ( | const Quaternion & | _qt | ) |
| 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 |
Rotate a vector using the quaternion.
| [in] | _vec | vector to rotate |
References Quaternion::GetInverse(), Quaternion::x, Quaternion::y, and Quaternion::z.
Do the reverse rotation of a vector by this quaternion.
| [in] | _vec | the vector |
| void Round | ( | int | _precision | ) |
Round all values to _precision decimal places.
| [in] | _precision | the precision |
| void Scale | ( | double | _scale | ) |
Scale a Quaternionion.
| [in] | _scale | Amount to scale this rotation |
| 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 |
| 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 |
| 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 |
| 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.
|
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 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 |
|
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 Quaternion::Correct(), Quaternion::GetInverse(), and Quaternion::operator*().
| double x |
x value of the quaternion
Referenced by Pose::CoordPositionSub(), Quaternion::Correct(), Quaternion::GetInverse(), and Quaternion::RotateVector().
| double y |
y value of the quaternion
Referenced by Pose::CoordPositionSub(), Quaternion::Correct(), Quaternion::GetInverse(), and Quaternion::RotateVector().
| double z |
z value of the quaternion
Referenced by Pose::CoordPositionSub(), Quaternion::Correct(), Quaternion::GetInverse(), and Quaternion::RotateVector().