PX4 Firmware
PX4 Autopilot Software http://px4.io
matrix::Quaternion< Type > Class Template Reference

Quaternion class. More...

#include <Dcm.hpp>

Inheritance diagram for matrix::Quaternion< Type >:
Collaboration diagram for matrix::Quaternion< Type >:

Public Types

typedef Matrix< Type, 4, 1 > Matrix41
 
typedef Matrix< Type, 3, 1 > Matrix31
 
- Public Types inherited from matrix::Vector< Type, 4 >
typedef Matrix< Type, M, 1 > MatrixM1
 

Public Member Functions

 Quaternion (const Type data_[4])
 Constructor from array. More...
 
 Quaternion ()
 Standard constructor. More...
 
 Quaternion (const Matrix41 &other)
 Constructor from Matrix41. More...
 
 Quaternion (const Dcm< Type > &R)
 Constructor from dcm. More...
 
 Quaternion (const Euler< Type > &euler)
 Constructor from euler angles. More...
 
 Quaternion (const AxisAngle< Type > &aa)
 Quaternion from AxisAngle. More...
 
 Quaternion (const Vector3< Type > &src, const Vector3< Type > &dst, const Type eps=Type(1e-5))
 Quaternion from two vectors Generates shortest rotation from source to destination vector. More...
 
 Quaternion (Type a, Type b, Type c, Type d)
 Constructor from quaternion values. More...
 
Quaternion operator* (const Quaternion &q) const
 Quaternion multiplication operator. More...
 
void operator*= (const Quaternion &other)
 Self-multiplication operator. More...
 
Quaternion operator* (Type scalar) const
 Scalar multiplication operator. More...
 
void operator*= (Type scalar)
 Scalar self-multiplication operator. More...
 
Matrix41 derivative1 (const Matrix31 &w) const
 Computes the derivative of q_21 when rotated with angular velocity expressed in frame 1 v_2 = q_21 * v_1 * q_21^-1 d/dt q_21 = 0.5 * q_21 * omega_2. More...
 
Matrix41 derivative2 (const Matrix31 &w) const
 Computes the derivative of q_21 when rotated with angular velocity expressed in frame 2 v_2 = q_21 * v_1 * q_21^-1 d/dt q_21 = 0.5 * omega_1 * q_21. More...
 
void invert ()
 Invert quaternion in place. More...
 
Quaternion inversed () const
 Invert quaternion. More...
 
void canonicalize ()
 Bring quaternion to canonical form. More...
 
Quaternion canonical () const
 Return canonical form of the quaternion. More...
 
void rotate (const AxisAngle< Type > &vec)
 Rotate quaternion from rotation vector. More...
 
Vector3< Type > conjugate (const Vector3< Type > &vec) const
 Rotates vector v_1 in frame 1 to vector v_2 in frame 2 using the rotation quaternion q_21 describing the rotation from frame 1 to 2 v_2 = q_21 * v_1 * q_21^-1. More...
 
Vector3< Type > conjugate_inversed (const Vector3< Type > &vec) const
 Rotates vector v_2 in frame 2 to vector v_1 in frame 1 using the rotation quaternion q_21 describing the rotation from frame 1 to 2 v_1 = q_21^-1 * v_1 * q_21. More...
 
void from_axis_angle (Vector< Type, 3 > vec)
 Rotation quaternion from vector. More...
 
void from_axis_angle (const Vector< Type, 3 > &axis, Type theta)
 Rotation quaternion from axis and angle XXX DEPRECATED, use AxisAngle class. More...
 
Vector< Type, 3 > to_axis_angle () const
 Rotation vector from quaternion XXX DEPRECATED, use AxisAngle class. More...
 
Vector3< Type > imag () const
 Imaginary components of quaternion. More...
 
Vector3< Type > dcm_z () const
 Corresponding body z-axis to an attitude quaternion / last orthogonal unit basis vector. More...
 
Quaternion from_dcm (const Matrix< Type, 3, 3 > &dcm)
 XXX DEPRECATED, can use assignment or ctor. More...
 
Dcm< Type > to_dcm ()
 XXX DEPRECATED, can use assignment or ctor. More...
 
- Public Member Functions inherited from matrix::Vector< Type, 4 >
 Vector ()=default
 
 Vector (const MatrixM1 &other)
 
 Vector (const Type data_[M])
 
 Vector (const Slice< Type, M, 1, P, Q > &slice_in)
 
Type operator() (size_t i) const
 
Type & operator() (size_t i)
 
Type dot (const MatrixM1 &b) const
 
Type operator* (const MatrixM1 &b) const
 
Vector operator* (Type b) const
 
Type norm () const
 
Type norm_squared () const
 
Type length () const
 
void normalize ()
 
Vector unit () const
 
Vector unit_or_zero (const Type eps=Type(1e-5)) const
 
Vector normalized () const
 
bool longerThan (Type testVal) const
 
Vector sqrt () const
 
- Public Member Functions inherited from matrix::Matrix< Type, M, 1 >
 Matrix ()=default
 
 Matrix (const Type data_[M *N])
 
 Matrix (const Type data_[M][N])
 
 Matrix (const Matrix &other)
 
 Matrix (const Slice< Type, M, N, P, Q > &in_slice)
 
Type operator() (size_t i, size_t j) const
 Accessors/ Assignment etc. More...
 
Type & operator() (size_t i, size_t j)
 
Matrix< Type, M, N > & operator= (const Matrix< Type, M, N > &other)
 
void copyTo (Type dst[M *N]) const
 
void copyToColumnMajor (Type dst[M *N]) const
 
Matrix< Type, M, Poperator* (const Matrix< Type, N, P > &other) const
 Matrix Operations. More...
 
Matrix< Type, M, N > operator* (Type scalar) const
 Scalar Operations. More...
 
Matrix< Type, M, N > emult (const Matrix< Type, M, N > &other) const
 
Matrix< Type, M, N > edivide (const Matrix< Type, M, N > &other) const
 
Matrix< Type, M, N > operator+ (const Matrix< Type, M, N > &other) const
 
Matrix< Type, M, N > operator+ (Type scalar) const
 
Matrix< Type, M, N > operator- (const Matrix< Type, M, N > &other) const
 
Matrix< Type, M, N > operator- () const
 
Matrix< Type, M, N > operator- (Type scalar) const
 
void operator+= (const Matrix< Type, M, N > &other)
 
void operator+= (Type scalar)
 
void operator-= (const Matrix< Type, M, N > &other)
 
void operator-= (Type scalar)
 
void operator*= (const Matrix< Type, N, P > &other)
 
void operator*= (Type scalar)
 
Matrix< Type, M, N > operator/ (Type scalar) const
 
void operator/= (Type scalar)
 
bool operator== (const Matrix< Type, M, N > &other) const
 
bool operator!= (const Matrix< Type, M, N > &other) const
 
void write_string (char *buf, size_t n) const
 Misc. More...
 
void print (FILE *stream=stdout) const
 
Matrix< Type, N, M > transpose () const
 
Matrix< Type, N, M > T () const
 
const Slice< Type, P, Q, M, N > slice (size_t x0, size_t y0) const
 
Slice< Type, P, Q, M, N > slice (size_t x0, size_t y0)
 
const Slice< Type, 1, N, M, N > row (size_t i) const
 
Slice< Type, 1, N, M, N > row (size_t i)
 
const Slice< Type, M, 1, M, N > col (size_t j) const
 
Slice< Type, M, 1, M, N > col (size_t j)
 
void setRow (size_t i, const Matrix< Type, N, 1 > &row_in)
 
void setCol (size_t j, const Matrix< Type, M, 1 > &column)
 
void setZero ()
 
void zero ()
 
void setAll (Type val)
 
void setOne ()
 
void setNaN ()
 
void setIdentity ()
 
void identity ()
 
void swapRows (size_t a, size_t b)
 
void swapCols (size_t a, size_t b)
 
Matrix< Type, M, N > abs () const
 
Type max () const
 
Type min () const
 
bool isAllNan () const
 

Detailed Description

template<typename Type>
class matrix::Quaternion< Type >

Quaternion class.

The rotation between two coordinate frames is described by this class.

Definition at line 24 of file Dcm.hpp.

Member Typedef Documentation

◆ Matrix31

template<typename Type>
typedef Matrix<Type, 3, 1> matrix::Quaternion< Type >::Matrix31

Definition at line 57 of file Quaternion.hpp.

◆ Matrix41

template<typename Type>
typedef Matrix<Type, 4, 1> matrix::Quaternion< Type >::Matrix41

Definition at line 56 of file Quaternion.hpp.

Constructor & Destructor Documentation

◆ Quaternion() [1/8]

template<typename Type>
matrix::Quaternion< Type >::Quaternion ( const Type  data_[4])
inlineexplicit

Constructor from array.

Parameters
data_array

Definition at line 64 of file Quaternion.hpp.

◆ Quaternion() [2/8]

template<typename Type>
matrix::Quaternion< Type >::Quaternion ( )
inline

Standard constructor.

Definition at line 72 of file Quaternion.hpp.

Referenced by matrix::Quaternion< Type >::canonical(), matrix::Quaternion< Type >::from_dcm(), and matrix::Quaternion< Type >::inversed().

Here is the caller graph for this function:

◆ Quaternion() [3/8]

template<typename Type>
matrix::Quaternion< Type >::Quaternion ( const Matrix41 other)
inline

Constructor from Matrix41.

Parameters
otherMatrix41 to copy

Definition at line 86 of file Quaternion.hpp.

◆ Quaternion() [4/8]

template<typename Type>
matrix::Quaternion< Type >::Quaternion ( const Dcm< Type > &  R)
inline

Constructor from dcm.

Instance is initialized from a dcm representing coordinate transformation from frame 2 to frame 1.

Parameters
dcmdcm to set quaternion to

Definition at line 99 of file Quaternion.hpp.

References matrix::Vector< Type, 4 >::sqrt(), and matrix::SquareMatrix< Type, 3 >::trace().

Here is the call graph for this function:

◆ Quaternion() [5/8]

template<typename Type>
matrix::Quaternion< Type >::Quaternion ( const Euler< Type > &  euler)
inline

Constructor from euler angles.

This sets the instance to a quaternion representing coordinate transformation from frame 2 to frame 1 where the rotation from frame 1 to frame 2 is described by a 3-2-1 intrinsic Tait-Bryan rotation sequence.

Parameters
eulereuler angle instance

Definition at line 143 of file Quaternion.hpp.

References matrix::cos(), matrix::Euler< Type >::phi(), matrix::Euler< Type >::psi(), matrix::sin(), and matrix::Euler< Type >::theta().

Here is the call graph for this function:

◆ Quaternion() [6/8]

template<typename Type>
matrix::Quaternion< Type >::Quaternion ( const AxisAngle< Type > &  aa)
inline

Quaternion from AxisAngle.

Parameters
aaaxis-angle vector

Definition at line 167 of file Quaternion.hpp.

References matrix::cos(), f(), matrix::Vector< Type, 3 >::norm(), matrix::sin(), and matrix::Vector< Type, 3 >::unit().

Here is the call graph for this function:

◆ Quaternion() [7/8]

template<typename Type>
matrix::Quaternion< Type >::Quaternion ( const Vector3< Type > &  src,
const Vector3< Type > &  dst,
const Type  eps = Type(1e-5) 
)
inline

Quaternion from two vectors Generates shortest rotation from source to destination vector.

Parameters
dstdestination vector (no need to normalize)
srcsource vector (no need to normalize)
epsepsilon threshold which decides if a value is considered zero

Definition at line 192 of file Quaternion.hpp.

References matrix::Matrix< Type, M, 1 >::abs(), matrix::Vector3< Type >::cross(), matrix::Vector< Type, 3 >::dot(), dt, matrix::Vector< Type, 3 >::norm(), matrix::Vector< Type, 3 >::norm_squared(), and matrix::Vector< Type, 4 >::sqrt().

Here is the call graph for this function:

◆ Quaternion() [8/8]

template<typename Type>
matrix::Quaternion< Type >::Quaternion ( Type  a,
Type  b,
Type  c,
Type  d 
)
inline

Constructor from quaternion values.

Instance is initialized from quaternion values representing coordinate transformation from frame 2 to frame 1. A zero-rotation quaternion is represented by (1,0,0,0).

Parameters
aset quaternion value 0
bset quaternion value 1
cset quaternion value 2
dset quaternion value 3

Definition at line 240 of file Quaternion.hpp.

Member Function Documentation

◆ canonical()

template<typename Type>
Quaternion matrix::Quaternion< Type >::canonical ( ) const
inline

Return canonical form of the quaternion.

Returns
quaternion in canonical from

Definition at line 368 of file Quaternion.hpp.

References matrix::Quaternion< Type >::Quaternion().

Referenced by matrix::Quaternion< Type >::canonicalize(), and main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ canonicalize()

template<typename Type>
void matrix::Quaternion< Type >::canonicalize ( )
inline

Bring quaternion to canonical form.

Definition at line 357 of file Quaternion.hpp.

References matrix::Quaternion< Type >::canonical().

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ conjugate()

template<typename Type>
Vector3<Type> matrix::Quaternion< Type >::conjugate ( const Vector3< Type > &  vec) const
inline

Rotates vector v_1 in frame 1 to vector v_2 in frame 2 using the rotation quaternion q_21 describing the rotation from frame 1 to 2 v_2 = q_21 * v_1 * q_21^-1.

Parameters
vecvector to rotate in frame 1 (typically body frame)
Returns
rotated vector in frame 2 (typically reference frame)

Definition at line 398 of file Quaternion.hpp.

Referenced by ManualSmoothingXY::_getHeadingToWorldFrame(), main(), positionError(), and MathlibTest::testQuaternionRotate().

Here is the caller graph for this function:

◆ conjugate_inversed()

template<typename Type>
Vector3<Type> matrix::Quaternion< Type >::conjugate_inversed ( const Vector3< Type > &  vec) const
inline

Rotates vector v_2 in frame 2 to vector v_1 in frame 1 using the rotation quaternion q_21 describing the rotation from frame 1 to 2 v_1 = q_21^-1 * v_1 * q_21.

Parameters
vecvector to rotate in frame 2 (typically reference frame)
Returns
rotated vector in frame 1 (typically body frame)

Definition at line 414 of file Quaternion.hpp.

Referenced by ManualSmoothingXY::_getWorldToHeadingFrame(), and main().

Here is the caller graph for this function:

◆ dcm_z()

template<typename Type>
Vector3<Type> matrix::Quaternion< Type >::dcm_z ( ) const
inline

Corresponding body z-axis to an attitude quaternion / last orthogonal unit basis vector.

== last column of the equivalent rotation matrix but calculated more efficiently than a full conversion

Definition at line 514 of file Quaternion.hpp.

Referenced by main(), AttitudeControl::update(), and Tailsitter::update_transition_state().

Here is the caller graph for this function:

◆ derivative1()

template<typename Type>
Matrix41 matrix::Quaternion< Type >::derivative1 ( const Matrix31 w) const
inline

Computes the derivative of q_21 when rotated with angular velocity expressed in frame 1 v_2 = q_21 * v_1 * q_21^-1 d/dt q_21 = 0.5 * q_21 * omega_2.

Parameters
wangular rate in frame 1 (typically body frame)

Definition at line 308 of file Quaternion.hpp.

Referenced by Sih::equations_of_motion(), main(), and MatrixTest::run_tests().

Here is the caller graph for this function:

◆ derivative2()

template<typename Type>
Matrix41 matrix::Quaternion< Type >::derivative2 ( const Matrix31 w) const
inline

Computes the derivative of q_21 when rotated with angular velocity expressed in frame 2 v_2 = q_21 * v_1 * q_21^-1 d/dt q_21 = 0.5 * omega_1 * q_21.

Parameters
wangular rate in frame 2 (typically reference frame)

Definition at line 323 of file Quaternion.hpp.

Referenced by main().

Here is the caller graph for this function:

◆ from_axis_angle() [1/2]

template<typename Type>
void matrix::Quaternion< Type >::from_axis_angle ( Vector< Type, 3 >  vec)
inline

Rotation quaternion from vector.

The axis of rotation is given by vector direction and the angle is given by the norm.

Parameters
vecrotation vector
Returns
quaternion representing the rotation

Definition at line 431 of file Quaternion.hpp.

References matrix::Vector< Type, M >::norm().

Referenced by main(), and MatrixTest::run_tests().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ from_axis_angle() [2/2]

template<typename Type>
void matrix::Quaternion< Type >::from_axis_angle ( const Vector< Type, 3 > &  axis,
Type  theta 
)
inline

Rotation quaternion from axis and angle XXX DEPRECATED, use AxisAngle class.

Parameters
axisaxis of rotation
thetascalar describing angle of rotation
Returns
quaternion representing the rotation

Definition at line 454 of file Quaternion.hpp.

References matrix::cos(), f(), and matrix::sin().

Here is the call graph for this function:

◆ from_dcm()

template<typename Type>
Quaternion matrix::Quaternion< Type >::from_dcm ( const Matrix< Type, 3, 3 > &  dcm)
inline

XXX DEPRECATED, can use assignment or ctor.

Definition at line 531 of file Quaternion.hpp.

References matrix::Quaternion< Type >::Quaternion().

Referenced by main(), MathlibTest::testQuaternionfrom_dcm(), and MathlibTest::testQuaternionfrom_euler().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ imag()

template<typename Type>
Vector3<Type> matrix::Quaternion< Type >::imag ( ) const
inline

Imaginary components of quaternion.

Definition at line 501 of file Quaternion.hpp.

Referenced by main(), and AttitudeControl::update().

Here is the caller graph for this function:

◆ inversed()

template<typename Type>
Quaternion matrix::Quaternion< Type >::inversed ( ) const
inline

Invert quaternion.

Returns
inverted quaternion

Definition at line 343 of file Quaternion.hpp.

References matrix::Quaternion< Type >::Quaternion().

Referenced by Ekf2::get_vel_body_wind(), matrix::Quaternion< Type >::invert(), main(), MatrixTest::run_tests(), and AttitudeControl::update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ invert()

template<typename Type>
void matrix::Quaternion< Type >::invert ( )
inline

Invert quaternion in place.

Definition at line 333 of file Quaternion.hpp.

References matrix::Quaternion< Type >::inversed().

Referenced by main(), and MatrixTest::run_tests().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ operator*() [1/2]

template<typename Type>
Quaternion matrix::Quaternion< Type >::operator* ( const Quaternion< Type > &  q) const
inline

Quaternion multiplication operator.

Parameters
qquaternion to multiply with
Returns
product

Definition at line 255 of file Quaternion.hpp.

◆ operator*() [2/2]

template<typename Type>
Quaternion matrix::Quaternion< Type >::operator* ( Type  scalar) const
inline

Scalar multiplication operator.

Parameters
scalarscalar to multiply with
Returns
product

Definition at line 283 of file Quaternion.hpp.

◆ operator*=() [1/2]

template<typename Type>
void matrix::Quaternion< Type >::operator*= ( const Quaternion< Type > &  other)
inline

Self-multiplication operator.

Parameters
otherquaternion to multiply with

Definition at line 271 of file Quaternion.hpp.

◆ operator*=() [2/2]

template<typename Type>
void matrix::Quaternion< Type >::operator*= ( Type  scalar)
inline

Scalar self-multiplication operator.

Parameters
scalarscalar to multiply with

Definition at line 294 of file Quaternion.hpp.

◆ rotate()

template<typename Type>
void matrix::Quaternion< Type >::rotate ( const AxisAngle< Type > &  vec)
inline

Rotate quaternion from rotation vector.

Parameters
vecrotation vector

Definition at line 383 of file Quaternion.hpp.

Referenced by CollisionPrevention::_addDistanceSensorData(), main(), and MatrixTest::run_tests().

Here is the caller graph for this function:

◆ to_axis_angle()

template<typename Type>
Vector<Type, 3> matrix::Quaternion< Type >::to_axis_angle ( ) const
inline

Rotation vector from quaternion XXX DEPRECATED, use AxisAngle class.

The axis of rotation is given by vector direction and the angle is given by the norm.

Returns
vector, direction representing rotation axis and norm representing angle

Definition at line 481 of file Quaternion.hpp.

References matrix::atan2(), matrix::Vector< Type, 4 >::sqrt(), and matrix::wrap_pi().

Referenced by main(), and MatrixTest::run_tests().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ to_dcm()

template<typename Type>
Dcm<Type> matrix::Quaternion< Type >::to_dcm ( )
inline

XXX DEPRECATED, can use assignment or ctor.

Definition at line 538 of file Quaternion.hpp.

Referenced by Sih::equations_of_motion(), and main().

Here is the caller graph for this function:

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