PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Quaternion class. More...
#include <Dcm.hpp>
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, P > | operator* (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 |
Quaternion class.
The rotation between two coordinate frames is described by this class.
typedef Matrix<Type, 3, 1> matrix::Quaternion< Type >::Matrix31 |
Definition at line 57 of file Quaternion.hpp.
typedef Matrix<Type, 4, 1> matrix::Quaternion< Type >::Matrix41 |
Definition at line 56 of file Quaternion.hpp.
|
inlineexplicit |
|
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().
|
inline |
Constructor from Matrix41.
other | Matrix41 to copy |
Definition at line 86 of file Quaternion.hpp.
|
inline |
Constructor from dcm.
Instance is initialized from a dcm representing coordinate transformation from frame 2 to frame 1.
dcm | dcm to set quaternion to |
Definition at line 99 of file Quaternion.hpp.
References matrix::Vector< Type, 4 >::sqrt(), and matrix::SquareMatrix< Type, 3 >::trace().
|
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.
euler | euler 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().
|
inline |
Quaternion from AxisAngle.
aa | axis-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().
|
inline |
Quaternion from two vectors Generates shortest rotation from source to destination vector.
dst | destination vector (no need to normalize) |
src | source vector (no need to normalize) |
eps | epsilon 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().
|
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).
a | set quaternion value 0 |
b | set quaternion value 1 |
c | set quaternion value 2 |
d | set quaternion value 3 |
Definition at line 240 of file Quaternion.hpp.
|
inline |
Return canonical form of the quaternion.
Definition at line 368 of file Quaternion.hpp.
References matrix::Quaternion< Type >::Quaternion().
Referenced by matrix::Quaternion< Type >::canonicalize(), and main().
|
inline |
Bring quaternion to canonical form.
Definition at line 357 of file Quaternion.hpp.
References matrix::Quaternion< Type >::canonical().
Referenced by main().
|
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.
vec | vector to rotate in frame 1 (typically body frame) |
Definition at line 398 of file Quaternion.hpp.
Referenced by ManualSmoothingXY::_getHeadingToWorldFrame(), main(), positionError(), and MathlibTest::testQuaternionRotate().
|
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.
vec | vector to rotate in frame 2 (typically reference frame) |
Definition at line 414 of file Quaternion.hpp.
Referenced by ManualSmoothingXY::_getWorldToHeadingFrame(), and main().
|
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().
|
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.
w | angular 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().
|
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.
w | angular rate in frame 2 (typically reference frame) |
Definition at line 323 of file Quaternion.hpp.
Referenced by main().
|
inline |
Rotation quaternion from vector.
The axis of rotation is given by vector direction and the angle is given by the norm.
vec | rotation vector |
Definition at line 431 of file Quaternion.hpp.
References matrix::Vector< Type, M >::norm().
Referenced by main(), and MatrixTest::run_tests().
|
inline |
Rotation quaternion from axis and angle XXX DEPRECATED, use AxisAngle class.
axis | axis of rotation |
theta | scalar describing angle of rotation |
Definition at line 454 of file Quaternion.hpp.
References matrix::cos(), f(), and matrix::sin().
|
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().
|
inline |
Imaginary components of quaternion.
Definition at line 501 of file Quaternion.hpp.
Referenced by main(), and AttitudeControl::update().
|
inline |
Invert 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().
|
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().
|
inline |
Quaternion multiplication operator.
q | quaternion to multiply with |
Definition at line 255 of file Quaternion.hpp.
|
inline |
Scalar multiplication operator.
scalar | scalar to multiply with |
Definition at line 283 of file Quaternion.hpp.
|
inline |
Self-multiplication operator.
other | quaternion to multiply with |
Definition at line 271 of file Quaternion.hpp.
|
inline |
Scalar self-multiplication operator.
scalar | scalar to multiply with |
Definition at line 294 of file Quaternion.hpp.
|
inline |
Rotate quaternion from rotation vector.
vec | rotation vector |
Definition at line 383 of file Quaternion.hpp.
Referenced by CollisionPrevention::_addDistanceSensorData(), main(), and MatrixTest::run_tests().
|
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.
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().
|
inline |
XXX DEPRECATED, can use assignment or ctor.
Definition at line 538 of file Quaternion.hpp.
Referenced by Sih::equations_of_motion(), and main().