APM:Libraries
Public Member Functions | Public Attributes | List of all members
Quaternion Class Reference

#include <quaternion.h>

Public Member Functions

 Quaternion ()
 
 Quaternion (const float _q1, const float _q2, const float _q3, const float _q4)
 
 Quaternion (const float _q[4])
 
void operator() (const float _q1, const float _q2, const float _q3, const float _q4)
 
bool is_nan (void) const
 
void rotation_matrix (Matrix3f &m) const
 
void rotation_matrix_norm (Matrix3f &m) const
 
void from_rotation_matrix (const Matrix3f &m)
 
void earth_to_body (Vector3f &v) const
 
void from_euler (float roll, float pitch, float yaw)
 
void from_vector312 (float roll, float pitch, float yaw)
 
void to_axis_angle (Vector3f &v)
 
void from_axis_angle (Vector3f v)
 
void from_axis_angle (const Vector3f &axis, float theta)
 
void rotate (const Vector3f &v)
 
void from_axis_angle_fast (Vector3f v)
 
void from_axis_angle_fast (const Vector3f &axis, float theta)
 
void rotate_fast (const Vector3f &v)
 
float get_euler_roll () const
 
float get_euler_pitch () const
 
float get_euler_yaw () const
 
void to_euler (float &roll, float &pitch, float &yaw) const
 
Vector3f to_vector312 (void) const
 
float length (void) const
 
void normalize ()
 
void initialise ()
 
Quaternion inverse (void) const
 
float & operator[] (uint8_t i)
 
const float & operator[] (uint8_t i) const
 
Quaternion operator* (const Quaternion &v) const
 
Quaternionoperator*= (const Quaternion &v)
 
Quaternion operator/ (const Quaternion &v) const
 

Public Attributes

float q1
 
float q2
 
float q3
 
float q4
 

Detailed Description

Definition at line 25 of file quaternion.h.

Constructor & Destructor Documentation

◆ Quaternion() [1/3]

Quaternion::Quaternion ( )
inline

Definition at line 31 of file quaternion.h.

Referenced by inverse().

Here is the caller graph for this function:

◆ Quaternion() [2/3]

Quaternion::Quaternion ( const float  _q1,
const float  _q2,
const float  _q3,
const float  _q4 
)
inline

Definition at line 38 of file quaternion.h.

◆ Quaternion() [3/3]

Quaternion::Quaternion ( const float  _q[4])
inline

Definition at line 44 of file quaternion.h.

Member Function Documentation

◆ earth_to_body()

void Quaternion::earth_to_body ( Vector3f v) const

Definition at line 122 of file quaternion.cpp.

Referenced by is_nan(), and test_frame_transforms().

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

◆ from_axis_angle() [1/2]

void Quaternion::from_axis_angle ( Vector3f  v)

Definition at line 154 of file quaternion.cpp.

Referenced by AC_AttitudeControl::attitude_controller_run_quat(), NavEKF2_core::calcOutputStates(), NavEKF3_core::calcOutputStates(), AC_AttitudeControl::input_angle_step_bf_roll_pitch_yaw(), AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(), AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3(), is_nan(), rotate(), AC_AttitudeControl::shift_ef_yaw_target(), and AC_AttitudeControl::thrust_heading_rotation_angles().

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

◆ from_axis_angle() [2/2]

void Quaternion::from_axis_angle ( const Vector3f axis,
float  theta 
)

Definition at line 166 of file quaternion.cpp.

Here is the call graph for this function:

◆ from_axis_angle_fast() [1/2]

void Quaternion::from_axis_angle_fast ( Vector3f  v)

Definition at line 199 of file quaternion.cpp.

Referenced by is_nan().

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

◆ from_axis_angle_fast() [2/2]

void Quaternion::from_axis_angle_fast ( const Vector3f axis,
float  theta 
)

Definition at line 211 of file quaternion.cpp.

Here is the call graph for this function:

◆ from_euler()

void Quaternion::from_euler ( float  roll,
float  pitch,
float  yaw 
)

◆ from_rotation_matrix()

void Quaternion::from_rotation_matrix ( const Matrix3f m)

◆ from_vector312()

void Quaternion::from_vector312 ( float  roll,
float  pitch,
float  yaw 
)

Definition at line 146 of file quaternion.cpp.

Referenced by is_nan(), and SoloGimbalEKF::RunEKF().

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

◆ get_euler_pitch()

float Quaternion::get_euler_pitch ( ) const

Definition at line 260 of file quaternion.cpp.

Referenced by is_nan(), and to_euler().

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

◆ get_euler_roll()

float Quaternion::get_euler_roll ( ) const

Definition at line 254 of file quaternion.cpp.

Referenced by is_nan(), and to_euler().

Here is the caller graph for this function:

◆ get_euler_yaw()

float Quaternion::get_euler_yaw ( ) const

Definition at line 266 of file quaternion.cpp.

Referenced by is_nan(), and to_euler().

Here is the caller graph for this function:

◆ initialise()

void Quaternion::initialise ( )
inline

Definition at line 113 of file quaternion.h.

Here is the call graph for this function:

◆ inverse()

Quaternion Quaternion::inverse ( void  ) const

Definition at line 292 of file quaternion.cpp.

Referenced by AC_AttitudeControl::attitude_controller_run_quat(), initialise(), AC_AttitudeControl::input_quaternion(), AC_AttitudeControl::thrust_heading_rotation_angles(), NavEKF2_core::UpdateStrapdownEquationsNED(), and NavEKF3_core::UpdateStrapdownEquationsNED().

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

◆ is_nan()

bool Quaternion::is_nan ( void  ) const
inline

Definition at line 59 of file quaternion.h.

Referenced by NavEKF2_core::getFilterFaults(), NavEKF3_core::getFilterFaults(), NavEKF2_core::updateFilterStatus(), and NavEKF3_core::updateFilterStatus().

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

◆ length()

float Quaternion::length ( void  ) const

Definition at line 287 of file quaternion.cpp.

Referenced by NavEKF3_core::getTiltError(), is_nan(), and normalize().

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

◆ normalize()

void Quaternion::normalize ( void  )

◆ operator()()

void Quaternion::operator() ( const float  _q1,
const float  _q2,
const float  _q3,
const float  _q4 
)
inline

Definition at line 50 of file quaternion.h.

◆ operator*()

Quaternion Quaternion::operator* ( const Quaternion v) const

Definition at line 309 of file quaternion.cpp.

Referenced by operator[]().

Here is the caller graph for this function:

◆ operator*=()

Quaternion & Quaternion::operator*= ( const Quaternion v)

Definition at line 330 of file quaternion.cpp.

Referenced by operator[]().

Here is the caller graph for this function:

◆ operator/()

Quaternion Quaternion::operator/ ( const Quaternion v) const

Definition at line 350 of file quaternion.cpp.

Referenced by operator[]().

Here is the caller graph for this function:

◆ operator[]() [1/2]

float& Quaternion::operator[] ( uint8_t  i)
inline

Definition at line 122 of file quaternion.h.

◆ operator[]() [2/2]

const float& Quaternion::operator[] ( uint8_t  i) const
inline

Definition at line 131 of file quaternion.h.

Here is the call graph for this function:

◆ rotate()

void Quaternion::rotate ( const Vector3f v)

Definition at line 182 of file quaternion.cpp.

Referenced by SoloGimbalEKF::alignHeading(), NavEKF2_core::FuseAirspeed(), SoloGimbalEKF::fuseCompass(), NavEKF2_core::FuseDeclination(), NavEKF2_core::fuseEulerYaw(), NavEKF2_core::FuseMagnetometer(), NavEKF2_core::FuseOptFlow(), NavEKF2_core::FuseRngBcn(), NavEKF2_core::FuseSideslip(), SoloGimbalEKF::fuseVelocity(), NavEKF2_core::FuseVelPosNED(), is_nan(), SoloGimbalEKF::predictStates(), NavEKF2_core::readIMUData(), NavEKF3_core::readIMUData(), NavEKF2_core::UpdateStrapdownEquationsNED(), and NavEKF3_core::UpdateStrapdownEquationsNED().

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

◆ rotate_fast()

void Quaternion::rotate_fast ( const Vector3f v)

Definition at line 223 of file quaternion.cpp.

Referenced by is_nan().

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

◆ rotation_matrix()

void Quaternion::rotation_matrix ( Matrix3f m) const

◆ rotation_matrix_norm()

void Quaternion::rotation_matrix_norm ( Matrix3f m) const

Definition at line 48 of file quaternion.cpp.

Referenced by is_nan().

Here is the caller graph for this function:

◆ to_axis_angle()

void Quaternion::to_axis_angle ( Vector3f v)

Definition at line 189 of file quaternion.cpp.

Referenced by SITL::Calibration::_attitude_set(), NavEKF2_core::controlMagYawReset(), NavEKF3_core::controlMagYawReset(), AC_AttitudeControl::input_quaternion(), is_nan(), NavEKF2_core::readIMUData(), NavEKF3_core::readIMUData(), SITL::Aircraft::smooth_sensors(), and AC_AttitudeControl::thrust_heading_rotation_angles().

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

◆ to_euler()

void Quaternion::to_euler ( float &  roll,
float &  pitch,
float &  yaw 
) const

◆ to_vector312()

Vector3f Quaternion::to_vector312 ( void  ) const

Definition at line 280 of file quaternion.cpp.

Referenced by NavEKF2_core::fuseEulerYaw(), NavEKF3_core::fuseEulerYaw(), and is_nan().

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

Member Data Documentation

◆ q1

float Quaternion::q1

◆ q2

float Quaternion::q2

◆ q3

float Quaternion::q3

◆ q4

float Quaternion::q4

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