|
MAV'RIC
|
Interface for the estimated Attitude and Heading Reference System. More...
#include <ahrs.hpp>

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. | |
Interface for the estimated Attitude and Heading Reference System.
| enum AHRS::ahrs_state_t |
The calibration level of the filter.
| virtual std::array<float,3> AHRS::angular_speed | ( | void | ) | const [pure virtual] |
Estimated angular velocity.
Implemented in INS_AHRS_groundtruth, AHRS_madgwick, AHRS_ekf, and AHRS_qfilter.

| virtual quat_t AHRS::attitude | ( | void | ) | const [pure virtual] |
Estimated attitude.
Implemented in INS_AHRS_groundtruth, AHRS_madgwick, AHRS_ekf, and AHRS_qfilter.

| virtual bool AHRS::is_healthy | ( | void | ) | const [pure virtual] |
Indicates which estimate can be trusted.
| type | Type of estimate |
Implemented in INS_AHRS_groundtruth, AHRS_madgwick, AHRS_ekf, and AHRS_qfilter.

| virtual float AHRS::last_update_s | ( | void | ) | const [pure virtual] |
Last update in seconds.
Implemented in AHRS_madgwick, AHRS_ekf, AHRS_qfilter, and INS_AHRS_groundtruth.

| virtual std::array<float,3> AHRS::linear_acceleration | ( | void | ) | const [pure virtual] |
Estimated linear acceleration.
Implemented in INS_AHRS_groundtruth, AHRS_madgwick, AHRS_ekf, and AHRS_qfilter.

| virtual bool AHRS::update | ( | void | ) | [pure virtual] |
Main update function.
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.


1.7.6.1