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

Euler angles class. More...

#include <AxisAngle.hpp>

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

Public Member Functions

 Euler ()=default
 Standard constructor. More...
 
 Euler (const Vector< Type, 3 > &other)
 Copy constructor. More...
 
 Euler (const Matrix< Type, 3, 1 > &other)
 Constructor from Matrix31. More...
 
 Euler (Type phi_, Type theta_, Type psi_)
 Constructor from euler angles. More...
 
 Euler (const Dcm< Type > &dcm)
 Constructor from DCM matrix. More...
 
 Euler (const Quaternion< Type > &q)
 Constructor from quaternion instance. More...
 
Type phi () const
 
Type theta () const
 
Type psi () const
 
Type & phi ()
 
Type & theta ()
 
Type & psi ()
 
- Public Member Functions inherited from matrix::Vector< Type, 3 >
 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
 

Additional Inherited Members

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

Detailed Description

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

Euler angles class.

This class describes the rotation from frame 1 to frame 2 via 3-2-1 intrinsic Tait-Bryan rotation sequence.

Definition at line 18 of file AxisAngle.hpp.

Constructor & Destructor Documentation

◆ Euler() [1/6]

template<typename Type>
matrix::Euler< Type >::Euler ( )
default

Standard constructor.

Referenced by matrix::Euler< Type >::Euler().

Here is the caller graph for this function:

◆ Euler() [2/6]

template<typename Type>
matrix::Euler< Type >::Euler ( const Vector< Type, 3 > &  other)
inline

Copy constructor.

Parameters
othervector to copy

Definition at line 49 of file Euler.hpp.

◆ Euler() [3/6]

template<typename Type>
matrix::Euler< Type >::Euler ( const Matrix< Type, 3, 1 > &  other)
inline

Constructor from Matrix31.

Parameters
otherMatrix31 to copy

Definition at line 59 of file Euler.hpp.

◆ Euler() [4/6]

template<typename Type>
matrix::Euler< Type >::Euler ( Type  phi_,
Type  theta_,
Type  psi_ 
)
inline

Constructor from euler angles.

Instance is initialized from an 3-2-1 intrinsic Tait-Bryan rotation sequence representing transformation from frame 1 to frame 2.

Parameters
phi_rotation angle about X axis
theta_rotation angle about Y axis
psi_rotation angle about Z axis

Definition at line 75 of file Euler.hpp.

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

Here is the call graph for this function:

◆ Euler() [5/6]

template<typename Type>
matrix::Euler< Type >::Euler ( const Dcm< Type > &  dcm)
inline

Constructor from DCM matrix.

Instance is set from Dcm representing transformation from frame 2 to frame 1. This instance will hold the angles defining the 3-2-1 intrinsic Tait-Bryan rotation sequence from frame 1 to frame 2.

Parameters
dcmDirection cosine matrix

Definition at line 92 of file Euler.hpp.

References matrix::asin(), matrix::atan2(), M_PI, matrix::Euler< Type >::phi(), matrix::Euler< Type >::psi(), and matrix::Euler< Type >::theta().

Here is the call graph for this function:

◆ Euler() [6/6]

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

Constructor from quaternion instance.

Instance is set from a quaternion representing transformation from frame 2 to frame 1. This instance will hold the angles defining the 3-2-1 intrinsic Tait-Bryan rotation sequence from frame 1 to frame 2.

Parameters
qquaternion

Definition at line 123 of file Euler.hpp.

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

Here is the call graph for this function:

Member Function Documentation

◆ phi() [1/2]

◆ phi() [2/2]

template<typename Type>
Type& matrix::Euler< Type >::phi ( )
inline

Definition at line 141 of file Euler.hpp.

◆ psi() [1/2]

template<typename Type>
Type matrix::Euler< Type >::psi ( ) const
inline

Definition at line 136 of file Euler.hpp.

Referenced by matrix::Dcm< float >::Dcm(), matrix::Euler< Type >::Euler(), Simulator::handle_message_hil_state_quaternion(), matrix::Quaternion< Type >::Quaternion(), FixedwingAttitudeControl::Run(), px4::bst::BST::Run(), MavlinkStreamAttitude::send(), and Tailsitter::update_transition_state().

Here is the caller graph for this function:

◆ psi() [2/2]

template<typename Type>
Type& matrix::Euler< Type >::psi ( )
inline

Definition at line 149 of file Euler.hpp.

◆ theta() [1/2]

◆ theta() [2/2]

template<typename Type>
Type& matrix::Euler< Type >::theta ( )
inline

Definition at line 145 of file Euler.hpp.


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