MAV'RIC
Public Types | Public Member Functions
AHRS Class Reference

Interface for the estimated Attitude and Heading Reference System. More...

#include <ahrs.hpp>

Inheritance diagram for AHRS:
Inheritance graph
[legend]

List of all members.

Public Types

enum  ahrs_state_t { AHRS_INITIALISING = 0, AHRS_LEVELING = 1, AHRS_CONVERGING = 2, AHRS_READY = 3 }
 The calibration level of the filter. More...

Public Member Functions

virtual bool update (void)=0
 Main update function.
virtual float last_update_s (void) const =0
 Last update in seconds.
virtual bool is_healthy (void) const =0
 Indicates which estimate can be trusted.
virtual quat_t attitude (void) const =0
 Estimated attitude.
virtual std::array< float, 3 > angular_speed (void) const =0
 Estimated angular velocity.
virtual std::array< float, 3 > linear_acceleration (void) const =0
 Estimated linear acceleration.
virtual float yaw () const
 Gets the yaw angle from the ahrs quaternion.

Detailed Description

Interface for the estimated Attitude and Heading Reference System.


Member Enumeration Documentation

The calibration level of the filter.

Enumerator:
AHRS_INITIALISING 

Calibration level: Not initialised.

AHRS_LEVELING 

Calibration level: No calibration, attitude estimation correction by accelero/magneto measurements.

AHRS_CONVERGING 

Calibration level: leveling, correction of gyro biais.

AHRS_READY 

Calibration level: leveled.


Member Function Documentation

virtual std::array<float,3> AHRS::angular_speed ( void  ) const [pure virtual]

Estimated angular velocity.

Returns:
3D angular velocity

Implemented in INS_AHRS_groundtruth, AHRS_madgwick, AHRS_ekf, and AHRS_qfilter.

Here is the caller graph for this function:

virtual quat_t AHRS::attitude ( void  ) const [pure virtual]

Estimated attitude.

Returns:
quaternion

Implemented in INS_AHRS_groundtruth, AHRS_madgwick, AHRS_ekf, and AHRS_qfilter.

Here is the caller graph for this function:

virtual bool AHRS::is_healthy ( void  ) const [pure virtual]

Indicates which estimate can be trusted.

Parameters:
typeType of estimate
Returns:
boolean

Implemented in INS_AHRS_groundtruth, AHRS_madgwick, AHRS_ekf, and AHRS_qfilter.

Here is the caller graph for this function:

virtual float AHRS::last_update_s ( void  ) const [pure virtual]

Last update in seconds.

Returns:
time

Implemented in AHRS_madgwick, AHRS_ekf, AHRS_qfilter, and INS_AHRS_groundtruth.

Here is the caller graph for this function:

virtual std::array<float,3> AHRS::linear_acceleration ( void  ) const [pure virtual]

Estimated linear acceleration.

Returns:
3D linear acceleration

Implemented in INS_AHRS_groundtruth, AHRS_madgwick, AHRS_ekf, and AHRS_qfilter.

Here is the caller graph for this function:

virtual bool AHRS::update ( void  ) [pure virtual]

Main update function.

Returns:
Success

Implemented in AHRS_madgwick, AHRS_ekf, AHRS_qfilter, and INS_AHRS_groundtruth.

virtual float AHRS::yaw ( ) const [inline, virtual]

Gets the yaw angle from the ahrs quaternion.

Returns:
yaw

Here is the call graph for this function:

Here is the caller graph for this function:


The documentation for this class was generated from the following file:
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines