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... | |
T | 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... | |
T | Pitch () const |
Get the Euler pitch angle in radians. More... | |
T | 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... | |
T | W () const |
Get the w component. More... | |
void | W (T _v) |
Set the w component. More... | |
T & | X () |
Get a mutable x component. More... | |
T | 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... | |
T | Y () const |
Get the y component. More... | |
void | Y (T _v) |
Set the y component. More... | |
T | 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... | |
T | 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 Quaternion & | Identity = detail::gQuaternionIdentity<T> |
A Quaternion initialized to identity. This is equivalent to math::Quaternion<T>(1, 0, 0, 0) More... | |
static const Quaternion & | Zero = detail::gQuaternionZero<T> |
A Quaternion initialized to zero. This is equivalent to math::Quaternion<T>(0, 0, 0, 0) More... | |
Detailed Description
template<typename T>
class gz::math::Quaternion< T >
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++
- Ruby
Constructor & Destructor Documentation
◆ Quaternion() [1/7]
|
inlineconstexpr |
Default Constructor.
◆ Quaternion() [2/7]
|
inlineconstexpr |
Constructor that initializes each value, [w, x, y, z], of the quaternion. This constructor does not normalize the quaternion.
- Parameters
-
[in] _w W param [in] _x X param [in] _y Y param [in] _z Z param
◆ Quaternion() [3/7]
|
inline |
Construct a Quaternion from Euler angles, in radians. This constructor normalizes the quaternion.
- Parameters
-
[in] _roll Roll radians. [in] _pitch Pitch radians. [in] _yaw Yaw radians.
- See also
- SetFromEuler(T, T, T)
References Quaternion< T >::SetFromEuler().
◆ Quaternion() [4/7]
|
inline |
Constructor from an axis and angle. This constructor normalizes the quaternion.
- Parameters
-
[in] _axis The rotation axis. [in] _angle The rotation angle in radians.
References Quaternion< T >::SetFromAxisAngle().
◆ Quaternion() [5/7]
|
inlineexplicit |
Construct a Quaternion from Euler angles, in radians. This constructor normalizes the quaternion.
- Parameters
-
[in] _rpy Euler angles in radians.
References Quaternion< T >::SetFromEuler().
◆ Quaternion() [6/7]
|
inlineexplicit |
Construct from rotation matrix. This constructor does not normalize the quaternion.
- Parameters
-
[in] _mat Rotation matrix (must be orthogonal, the function doesn't check it)
References Quaternion< T >::SetFromMatrix().
◆ Quaternion() [7/7]
|
default |
Copy constructor. This constructor does not normalize the quaternion.
- Parameters
-
[in] _qt Quaternion<T> to copy
◆ ~Quaternion()
|
default |
Destructor.
Member Function Documentation
◆ Axis() [1/2]
|
inline |
Set the quaternion from an axis and angle.
- Parameters
-
[in] _axis Axis [in] _a Angle in radians
References Quaternion< T >::SetFromAxisAngle().
◆ Axis() [2/2]
|
inline |
Set the quaternion from an axis and angle.
- Parameters
-
[in] _ax X axis [in] _ay Y axis [in] _az Z axis [in] _aa Angle in radians
References Quaternion< T >::SetFromAxisAngle().
◆ AxisAngle()
|
inline |
Convert this quaternion to an axis and angle.
- Parameters
-
[out] _axis Rotation axis. [out] _angle CCW angle in radians.
References Vector3< T >::Set().
Referenced by Quaternion< T >::Scale(), and Quaternion< T >::ToAxis().
◆ Correct()
|
inline |
Correct any nan values in this quaternion.
References gz::math::equal(), and std::isfinite().
◆ Dot()
|
inline |
Get the dot product of this quaternion with the give _q quaternion.
- Parameters
-
[in] _q The other quaternion.
- Returns
- The dot product.
◆ Equal()
|
inline |
Equality comparison test with a tolerance parameter. The tolerance is used with the equal function for each component of the quaternions.
- Parameters
-
[in] _q The quaternion to compare against. [in] _tol equality tolerance.
- Returns
- True if the elements of the quaternions are equal within the tolerence specified by _tol.
References gz::math::equal().
Referenced by Quaternion< T >::operator==().
◆ Euler() [1/3]
|
inline |
Return the rotation in Euler angles, in radians.
- Returns
- This quaternion as Euler angles.
References GZ_PI, Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().
Referenced by Quaternion< T >::Pitch(), Quaternion< T >::Roll(), and Quaternion< T >::Yaw().
◆ Euler() [2/3]
|
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] _vec Euler angle
References Quaternion< T >::SetFromEuler().
◆ Euler() [3/3]
|
inline |
Set the quaternion from Euler angles.
- Parameters
-
[in] _roll Roll angle (radians). [in] _pitch Pitch angle (radians). [in] _yaw Yaw angle (radians).
References Quaternion< T >::SetFromEuler().
◆ EulerToQuaternion() [1/2]
|
inlinestatic |
Convert Euler angles to a quaternion.
- Parameters
-
[in] _vec The vector of angles, in radians, to convert.
- Returns
- The resulting quaternion
References Quaternion< T >::SetFromEuler().
Referenced by Quaternion< T >::EulerToQuaternion().
◆ EulerToQuaternion() [2/2]
|
inlinestatic |
Convert Euler angles, in radians, to a quaternion.
- Parameters
-
[in] _x rotation along x in radians [in] _y rotation along y in radians [in] _z rotation along z in radians
- Returns
- The resulting quaternion.
References Quaternion< T >::EulerToQuaternion().
◆ Exp()
|
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()
Set this quaternion to represent rotation from vector _v1 to vector _v2, so that _v2.Normalize() == this * _v1.Normalize() holds.
- Parameters
-
[in] _v1 The first vector. [in] _v2 The second vector.
Implementation inspired by http://stackoverflow.com/a/11741520/1076564
References Quaternion< T >::SetFrom2Axes().
◆ Integrate()
|
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] _angularVelocity Angular velocity vector, specified in same reference frame as base of this quaternion. [in] _deltaT Time interval in seconds to integrate over.
- Returns
- Quaternion at integrated configuration.
References gz::math::MIN_D, Vector3< T >::SquaredLength(), Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().
◆ Inverse()
|
inline |
Get the inverse of this quaternion.
- Returns
- Inverse quaternion
Referenced by Pose3< T >::CoordRotationSub(), MassMatrix3< T >::PrincipalAxesOffset(), Quaternion< T >::RotateVector(), Quaternion< T >::RotateVectorReverse(), and Inertial< T >::SetMassMatrixRotation().
◆ Invert()
|
inline |
Invert the quaternion. The quaternion is first normalized, then inverted.
References Quaternion< T >::Normalize().
◆ IsFinite()
|
inline |
See if a quaternion is finite (e.g., not nan).
- Returns
- True if quaternion is finite.
References std::isfinite().
◆ Log()
|
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()
|
inline |
Set from a rotation matrix.
- Parameters
-
[in] _mat rotation matrix (must be orthogonal, the function doesn't check it)
Implementation inspired by http://www.euclideanspace.com/maths/geometry/rotations/ conversions/matrixToQuaternion/
References Quaternion< T >::SetFromMatrix().
◆ Normalize()
|
inline |
Normalize the quaternion.
Referenced by Matrix3< T >::Matrix3(), Matrix4< T >::Matrix4(), Pose3< T >::CoordRotationSub(), Quaternion< T >::Invert(), Quaternion< T >::Normalized(), Quaternion< T >::SetFrom2Axes(), Quaternion< T >::SetFromAxisAngle(), Quaternion< T >::SetFromEuler(), and Quaternion< T >::Slerp().
◆ Normalized()
|
inline |
Gets a normalized version of this quaternion.
- Returns
- a normalized quaternion
References Quaternion< T >::Normalize().
◆ operator!=()
|
inline |
Not equal to operator. A tolerance of 0.001 is used with the equal function for each component of the quaternions.
- Parameters
-
[in] _qt Quaternion for comparison.
- Returns
- True if any component of both quaternions is not within the tolerance of 0.001 of its counterpart.
◆ operator*() [1/3]
|
inline |
Multiplication operator.
- Parameters
-
[in] _q Quaternion for multiplication.
- Returns
- This quaternion multiplied by the parameter.
◆ operator*() [2/3]
|
inline |
Multiplication operator by a scalar.
- Parameters
-
[in] _f Factor.
- Returns
- Quaternion multiplied by the scalar.
◆ operator*() [3/3]
Vector3 multiplication operator.
- Parameters
-
[in] _v vector to multiply.
- Returns
- The result of the vector multiplication.
References Vector3< T >::Cross().
◆ operator*=()
|
inline |
Multiplication set operator.
- Parameters
-
[in] _qt Quaternion<T> for multiplication.
- Returns
- This quaternion multiplied by the parameter.
◆ operator+()
|
inline |
◆ operator+=()
|
inline |
◆ operator-() [1/2]
|
inline |
Unary minus operator.
- Returns
- Negation of each component of this quaternion.
◆ operator-() [2/2]
|
inline |
◆ operator-=()
|
inline |
Subtraction set operator.
- Parameters
-
[in] _qt Quaternion for subtraction.
- Returns
- This quaternion - qt.
◆ operator=()
|
default |
Assignment operator.
- Parameters
-
[in] _qt Quaternion<T> to copy
◆ operator==()
|
inline |
Equality comparison operator. A tolerance of 0.001 is used with the equal function for each component of the quaternions.
- Parameters
-
[in] _qt Quaternion<T> for comparison.
- Returns
- True if each component of both quaternions is within the tolerance of 0.001 of its counterpart.
References Quaternion< T >::Equal().
◆ Pitch()
|
inline |
Get the Euler pitch angle in radians.
- Returns
- The pitch component.
References Quaternion< T >::Euler().
◆ Roll()
|
inline |
Get the Euler roll angle in radians.
- Returns
- The roll component.
References Quaternion< T >::Euler().
◆ RotateVector()
Rotate a vector using the quaternion.
- Parameters
-
[in] _vec Vector to rotate.
- Returns
- The rotated vector.
References Quaternion< T >::Inverse(), Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().
◆ RotateVectorReverse()
Get the reverse rotation of a vector by this quaternion.
- Parameters
-
[in] _vec The vector.
- Returns
- The reversed vector.
References Quaternion< T >::Inverse(), Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().
◆ Round()
|
inline |
Round all values to _precision decimal places.
- Parameters
-
[in] _precision the precision.
References gz::math::precision().
◆ Scale()
|
inline |
Scale this quaternion.
- Parameters
-
[in] _scale Amount to scale this quaternion
References Quaternion< T >::AxisAngle(), Quaternion< T >::SetFromAxisAngle(), Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().
◆ Set()
|
inline |
Set this quaternion from 4 floating numbers.
- Parameters
-
[in] _w w [in] _x x [in] _y y [in] _z z
◆ SetFrom2Axes()
Set this quaternion to represent rotation from vector _v1 to vector _v2, so that _v2.Normalize() == this * _v1.Normalize() holds.
- Parameters
-
[in] _v1 The first vector. [in] _v2 The second vector.
Implementation inspired by http://stackoverflow.com/a/11741520/1076564
References Vector3< T >::Abs(), Vector3< T >::Cross(), Vector3< T >::Dot(), Quaternion< T >::Normalize(), Vector3< T >::Normalize(), Vector3< T >::Set(), Vector3< T >::SquaredLength(), Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().
Referenced by Quaternion< T >::From2Axes().
◆ SetFromAxisAngle() [1/2]
|
inline |
Set the quaternion from an axis and angle.
- Parameters
-
[in] _axis Axis [in] _a Angle in radians
References Quaternion< T >::SetFromAxisAngle(), Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().
◆ SetFromAxisAngle() [2/2]
|
inline |
Set the quaternion from an axis and angle.
- Parameters
-
[in] _ax X axis [in] _ay Y axis [in] _az Z axis [in] _aa Angle in radians
References Quaternion< T >::Normalize().
Referenced by Quaternion< T >::Quaternion(), Quaternion< T >::Axis(), Quaternion< T >::Scale(), and Quaternion< T >::SetFromAxisAngle().
◆ SetFromEuler() [1/2]
|
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] _vec Euler angles in radians.
References Vector3< T >::X(), Vector3< T >::Y(), and Vector3< T >::Z().
Referenced by Quaternion< T >::Quaternion(), Quaternion< T >::Euler(), and Quaternion< T >::EulerToQuaternion().
◆ SetFromEuler() [2/2]
|
inline |
Set the quaternion from Euler angles.
- Parameters
-
[in] _roll Roll angle in radians. [in] _pitch Pitch angle in radians. [in] _yaw Yaw angle in radians.
References Quaternion< T >::Normalize().
◆ SetFromMatrix()
|
inline |
Set from a rotation matrix.
- Parameters
-
[in] _mat Rotation 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< T >::Quaternion(), and Quaternion< T >::Matrix().
◆ SetW()
|
inline |
Set the w component.
- Parameters
-
[in] _v The new value for the w quaternion component.
Referenced by Matrix4< T >::Rotation(), and Quaternion< T >::W().
◆ SetX()
|
inline |
Set the x component.
- Parameters
-
[in] _v The new value for the x quaternion component.
Referenced by Matrix4< T >::Rotation(), and Quaternion< T >::X().
◆ SetY()
|
inline |
Set the y component.
- Parameters
-
[in] _v The new value for the y quaternion component.
Referenced by Matrix4< T >::Rotation(), and Quaternion< T >::Y().
◆ SetZ()
|
inline |
Set the z component.
- Parameters
-
[in] _v The new value for the z quaternion component.
Referenced by Matrix4< T >::Rotation(), and Quaternion< T >::Z().
◆ Slerp()
|
inlinestatic |
Spherical linear interpolation between 2 quaternions, given the ends and an interpolation parameter between 0 and 1.
- Parameters
-
[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.
- Returns
- The result of the linear interpolation.
References Quaternion< T >::Normalize().
Referenced by OnePoleQuaternion::Process(), and Quaternion< T >::Squad().
◆ Squad()
|
inlinestatic |
Spherical quadratic interpolation given the ends and an interpolation parameter between 0 and 1.
- Parameters
-
[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.
- Returns
- The result of the quadratic interpolation.
References Quaternion< T >::Slerp().
◆ ToAxis()
|
inline |
Return rotation as axis and angle.
- Parameters
-
[out] _axis rotation axis [out] _angle ccw angle in radians
References Quaternion< T >::AxisAngle().
◆ W() [1/3]
|
inline |
Get a mutable w component.
- Returns
- The w quaternion component.
◆ W() [2/3]
|
inline |
Get the w component.
- Returns
- The w quaternion component.
Referenced by Matrix3< T >::Matrix3(), Matrix4< T >::Matrix4(), and Pose3< T >::RotatePositionAboutOrigin().
◆ W() [3/3]
|
inline |
Set the w component.
- Parameters
-
[in] _v The new value for the w quaternion component.
References Quaternion< T >::SetW().
◆ X() [1/3]
|
inline |
Get a mutable x component.
- Returns
- The x quaternion component.
◆ X() [2/3]
|
inline |
Get the x component.
- Returns
- The x quaternion component.
Referenced by Matrix3< T >::Matrix3(), Matrix4< T >::Matrix4(), Pose3< T >::CoordPoseSolve(), Pose3< T >::CoordPositionAdd(), Pose3< T >::CoordPositionSub(), and Pose3< T >::RotatePositionAboutOrigin().
◆ X() [3/3]
|
inline |
Set the x component.
- Parameters
-
[in] _v The new value for the x quaternion component.
References Quaternion< T >::SetX().
◆ XAxis()
|
inline |
Return the X axis.
- Returns
- the X axis of the vector.
◆ Y() [1/3]
|
inline |
Get a mutable y component.
- Returns
- The y quaternion component.
◆ Y() [2/3]
|
inline |
Get the y component.
- Returns
- The y quaternion component.
Referenced by Matrix3< T >::Matrix3(), Matrix4< T >::Matrix4(), Pose3< T >::CoordPoseSolve(), Pose3< T >::CoordPositionAdd(), Pose3< T >::CoordPositionSub(), and Pose3< T >::RotatePositionAboutOrigin().
◆ Y() [3/3]
|
inline |
Set the y component.
- Parameters
-
[in] _v The new value for the y quaternion component.
References Quaternion< T >::SetY().
◆ Yaw()
|
inline |
◆ YAxis()
|
inline |
Return the Y axis.
- Returns
- the Y axis of the vector.
◆ Z() [1/3]
|
inline |
Get a mutable z component.
- Returns
- The z quaternion component.
◆ Z() [2/3]
|
inline |
Get the z component.
- Returns
- The z quaternion component.
Referenced by Matrix3< T >::Matrix3(), Matrix4< T >::Matrix4(), Pose3< T >::CoordPoseSolve(), Pose3< T >::CoordPositionAdd(), Pose3< T >::CoordPositionSub(), and Pose3< T >::RotatePositionAboutOrigin().
◆ Z() [3/3]
|
inline |
Set the z component.
- Parameters
-
[in] _v The new value for the z quaternion component.
References Quaternion< T >::SetZ().
◆ ZAxis()
|
inline |
Return the Z axis.
- Returns
- the Z axis of the vector.
Member Data Documentation
◆ Identity
|
static |
A Quaternion initialized to identity. This is equivalent to math::Quaternion<T>(1, 0, 0, 0)
◆ Zero
|
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: