#include <math/gzmath.hh>
Public Member Functions | |
Quaternion () | |
Default Constructor. | |
Quaternion (const double &_w, const double &_x, const double &_y, const double &_z) | |
Constructor. | |
Quaternion (const double &_roll, const double &_pitch, const double &_yaw) | |
Constructor from Euler angles in radians. | |
Quaternion (const Vector3 &_axis, const double &_angle) | |
Constructor from axis angle. | |
Quaternion (const Vector3 &_rpy) | |
Constructor. | |
Quaternion (const Quaternion &_qt) | |
Copy constructor. | |
~Quaternion () | |
Destructor. | |
void | Correct () |
Correct any nan. | |
double | Dot (const Quaternion &_q) const |
Dot product. | |
void | GetAsAxis (Vector3 &_axis, double &_angle) const |
Return rotation as axis and angle. | |
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. | |
Quaternion | GetInverse () const |
Get the inverse of this quaternion. | |
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. | |
void | Invert () |
Invert the quaternion. | |
bool | IsFinite () const |
See if a quatern is finite (e.g., not nan) | |
void | Normalize () |
Normalize the quaternion. | |
bool | operator!= (const Quaternion &_qt) const |
Not equal to operator. | |
Quaternion | operator* (const Quaternion &_q) const |
Multiplication operator. | |
Quaternion | operator* (const double &_f) const |
Multiplication operator. | |
Vector3 | operator* (const Vector3 &_v) const |
Vector3 multiplication operator. | |
Quaternion | operator*= (const Quaternion &qt) |
Multiplication operator. | |
Quaternion | operator+ (const Quaternion &_qt) const |
Addition operator. | |
Quaternion | operator+= (const Quaternion &_qt) |
Addition operator. | |
Quaternion | operator- (const Quaternion &_qt) const |
Substraction operator. | |
Quaternion | operator- () const |
Unary minus operator. | |
Quaternion | operator-= (const Quaternion &_qt) |
Substraction operator. | |
Quaternion & | operator= (const Quaternion &_qt) |
Equal operator. | |
bool | operator== (const Quaternion &_qt) const |
Equal to operator. | |
Vector3 | RotateVector (const Vector3 &_vec) const |
Rotate a vector using the quaternion. | |
Vector3 | RotateVectorReverse (Vector3 _vec) const |
Do the reverse rotation of a vector by this quaternion. | |
void | Round (int _precision) |
Round all values to _precision decimal places. | |
void | Scale (double _scale) |
Scale a Quaternionion. | |
void | Set (double _u, double _x, double _y, double _z) |
Set this quaternion from 4 floating numbers. | |
void | SetFromAxis (double _x, double _y, double _z, double _a) |
Set the quaternion from an axis and angle. | |
void | SetFromAxis (const Vector3 &_axis, double _a) |
Set the quaternion from an axis and angle. | |
void | SetFromEuler (const Vector3 &_vec) |
Set the quaternion from Euler angles. | |
void | SetFromEuler (double _roll, double _pitch, double _yaw) |
Set the quaternion from Euler angles. | |
void | SetToIdentity () |
Set the quatern to the identity. | |
Static Public Member Functions | |
static Quaternion | EulerToQuaternion (const Vector3 &_vec) |
Convert euler angles to quatern. | |
static Quaternion | EulerToQuaternion (double _x, double _y, double _z) |
Convert euler angles to quatern. | |
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. | |
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. | |
Public Attributes | |
double | w |
Attributes of the quaternion. | |
double | x |
Attributes of the quaternion. | |
double | y |
Attributes of the quaternion. | |
double | z |
Attributes of the quaternion. | |
Friends | |
std::ostream & | operator<< (std::ostream &_out, const gazebo::math::Quaternion &_q) |
Stream insertion operator. | |
std::istream & | operator>> (std::istream &_in, gazebo::math::Quaternion &_q) |
Stream extraction operator. | |
A quaternion class.
gazebo::math::Quaternion::Quaternion | ( | ) |
Default Constructor.
Referenced by operator*().
gazebo::math::Quaternion::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 |
gazebo::math::Quaternion::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 |
gazebo::math::Quaternion::Quaternion | ( | const Vector3 & | _axis, |
const double & | _angle | ||
) |
Constructor from axis angle.
[in] | _axis | the rotation axis |
[in] | _angle | the rotation angle in radians |
gazebo::math::Quaternion::Quaternion | ( | const Vector3 & | _rpy | ) |
Constructor.
[in] | _rpy | euler angles |
gazebo::math::Quaternion::Quaternion | ( | const Quaternion & | _qt | ) |
Copy constructor.
qt | Quaternion to copy |
gazebo::math::Quaternion::~Quaternion | ( | ) |
Destructor.
|
inline |
Correct any nan.
References gazebo::math::equal(), w, x, y, and z.
Referenced by gazebo::math::Pose::Correct().
double gazebo::math::Quaternion::Dot | ( | const Quaternion & | _q | ) | const |
Dot product.
[in] | _q | the other quaternion |
|
static |
Convert euler angles to quatern.
[in] |
|
static |
Convert euler angles to quatern.
[in] | _x | rotation along x |
[in] | _y | rotation along y |
[in] | _z | rotation along z |
void gazebo::math::Quaternion::GetAsAxis | ( | Vector3 & | _axis, |
double & | _angle | ||
) | const |
Return rotation as axis and angle.
[in] | _axis | rotation axis |
[in] | _angle | ccw angle in radians |
Vector3 gazebo::math::Quaternion::GetAsEuler | ( | ) | const |
Return the rotation in Euler angles.
Matrix3 gazebo::math::Quaternion::GetAsMatrix3 | ( | ) | const |
Get the quaternion as a 3x3 matrix.
Matrix4 gazebo::math::Quaternion::GetAsMatrix4 | ( | ) | const |
Get the quaternion as a 4x4 matrix.
Quaternion gazebo::math::Quaternion::GetExp | ( | ) | const |
Return the exponent.
|
inline |
Get the inverse of this quaternion.
References gazebo::math::equal(), w, x, y, and z.
Referenced by gazebo::math::Pose::CoordPositionSub(), gazebo::math::Pose::CoordRotationSub(), and RotateVector().
Quaternion gazebo::math::Quaternion::GetLog | ( | ) | const |
Return the logarithm.
double gazebo::math::Quaternion::GetPitch | ( | ) |
Get the Euler pitch angle in radians.
double gazebo::math::Quaternion::GetRoll | ( | ) |
Get the Euler roll angle in radians.
Vector3 gazebo::math::Quaternion::GetXAxis | ( | ) | const |
Return the X axis.
double gazebo::math::Quaternion::GetYaw | ( | ) |
Get the Euler yaw angle in radians.
Vector3 gazebo::math::Quaternion::GetYAxis | ( | ) | const |
Return the Y axis.
Vector3 gazebo::math::Quaternion::GetZAxis | ( | ) | const |
Return the Z axis.
void gazebo::math::Quaternion::Invert | ( | ) |
Invert the quaternion.
bool gazebo::math::Quaternion::IsFinite | ( | ) | const |
See if a quatern is finite (e.g., not nan)
void gazebo::math::Quaternion::Normalize | ( | ) |
Normalize the quaternion.
Referenced by gazebo::math::Pose::CoordRotationSub().
bool gazebo::math::Quaternion::operator!= | ( | const Quaternion & | _qt | ) | const |
|
inline |
Multiplication operator.
[in] | _qt | Quaternion for multiplication |
References Quaternion(), w, x, y, and z.
Quaternion gazebo::math::Quaternion::operator* | ( | const double & | _f | ) | const |
Multiplication operator.
[in] | _f | factor |
Vector3 multiplication operator.
[in] | _v | vector to multiply |
Quaternion gazebo::math::Quaternion::operator*= | ( | const Quaternion & | qt | ) |
Multiplication operator.
[in] | _qt | Quaternion for multiplication |
Quaternion gazebo::math::Quaternion::operator+ | ( | const Quaternion & | _qt | ) | const |
Addition operator.
[in] | _qt | quaternion for addition |
Quaternion gazebo::math::Quaternion::operator+= | ( | const Quaternion & | _qt | ) |
Addition operator.
[in] | _qt | quaternion for addition |
Quaternion gazebo::math::Quaternion::operator- | ( | const Quaternion & | _qt | ) | const |
Substraction operator.
[in] | _qt | quaternion to substract |
Quaternion gazebo::math::Quaternion::operator- | ( | ) | const |
Unary minus operator.
Quaternion gazebo::math::Quaternion::operator-= | ( | const Quaternion & | _qt | ) |
Quaternion& gazebo::math::Quaternion::operator= | ( | const Quaternion & | _qt | ) |
Equal operator.
[in] | _qt | Quaternion to copy |
bool gazebo::math::Quaternion::operator== | ( | const Quaternion & | _qt | ) | const |
Rotate a vector using the quaternion.
[in] | _vec | vector to rotate |
References GetInverse(), gazebo::math::Vector3::x, x, gazebo::math::Vector3::y, y, gazebo::math::Vector3::z, and z.
Do the reverse rotation of a vector by this quaternion.
[in] | _vec | the vector |
void gazebo::math::Quaternion::Round | ( | int | _precision | ) |
Round all values to _precision decimal places.
[in] | _precision | the precision |
void gazebo::math::Quaternion::Scale | ( | double | _scale | ) |
Scale a Quaternionion.
[in] | _scale | Amount to scale this rotation |
void gazebo::math::Quaternion::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 gazebo::math::Quaternion::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 gazebo::math::Quaternion::SetFromAxis | ( | const Vector3 & | _axis, |
double | _a | ||
) |
Set the quaternion from an axis and angle.
[in] | _axis | Axis |
[in] | _a | Angle in radians |
void gazebo::math::Quaternion::SetFromEuler | ( | const Vector3 & | _vec | ) |
Set the quaternion from Euler angles.
[in] | vec | Euler angle |
void gazebo::math::Quaternion::SetFromEuler | ( | double | _roll, |
double | _pitch, | ||
double | _yaw | ||
) |
Set the quaternion from Euler angles.
[in] | _roll | Roll angle (radians). |
[in] | _pitch | Roll angle (radians). |
[in] | _yaw | Roll angle (radians). |
void gazebo::math::Quaternion::SetToIdentity | ( | ) |
Set the quatern 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 |
|
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 gazebo::math::Quaternion::w |
Attributes of the quaternion.
Referenced by Correct(), GetInverse(), and operator*().
double gazebo::math::Quaternion::x |
Attributes of the quaternion.
Referenced by gazebo::math::Pose::CoordPositionSub(), Correct(), GetInverse(), operator*(), and RotateVector().
double gazebo::math::Quaternion::y |
Attributes of the quaternion.
Referenced by gazebo::math::Pose::CoordPositionSub(), Correct(), GetInverse(), operator*(), and RotateVector().
double gazebo::math::Quaternion::z |
Attributes of the quaternion.
Referenced by gazebo::math::Pose::CoordPositionSub(), Correct(), GetInverse(), operator*(), and RotateVector().