MAV'RIC
|
#include <ahrs_madgwick.hpp>
Classes | |
struct | conf_t |
Configuration for ahrs _madgwick. More... | |
Public Member Functions | |
AHRS_madgwick (const Imu &imu, const Airspeed_analog &airspeed, const conf_t &config=default_config()) | |
Init function. | |
bool | update (void) |
Main update function. | |
float | last_update_s (void) const |
Last update in seconds. | |
bool | is_healthy (void) const |
Indicates which estimate can be trusted. | |
quat_t | attitude (void) const |
Estimated attitude. | |
std::array< float, 3 > | angular_speed (void) const |
Estimated angular velocity. | |
std::array< float, 3 > | linear_acceleration (void) const |
Estimated linear acceleration. | |
Static Public Member Functions | |
static conf_t | default_config () |
Default configuration. | |
Protected Attributes | |
const Imu & | imu_ |
Reference to IMU sensors. | |
const Airspeed_analog & | airspeed_ |
Reference to the airspeed sensor. | |
quat_t | attitude_ |
Estimated attitude. | |
std::array< float, 3 > | angular_speed_ |
Estimated angular speed. | |
std::array< float, 3 > | linear_acc_ |
Estimated linear acceleration. | |
float | last_update_s_ |
Last update time. | |
float | beta_ |
2 * proportional gain (Kp) | |
float | zeta_ |
Gyro drift bias gain. | |
uint32_t | acceleration_correction_ |
Enable the correction of the parasitic accelerations ? | |
float | correction_speed_ |
Airspeed from which the correction should start. |
Disclaimer: this WIP
AHRS_madgwick::AHRS_madgwick | ( | const Imu & | imu, |
const Airspeed_analog & | airspeed, | ||
const conf_t & | config = default_config() |
||
) |
Init function.
imu | Reference to IMU structure |
airspeed | Reference to airspeed sensor |
config | Config structure |
std::array< float, 3 > AHRS_madgwick::angular_speed | ( | void | ) | const [virtual] |
quat_t AHRS_madgwick::attitude | ( | void | ) | const [virtual] |
bool AHRS_madgwick::is_healthy | ( | void | ) | const [virtual] |
Indicates which estimate can be trusted.
type | Type of estimate |
Implements AHRS.
float AHRS_madgwick::last_update_s | ( | void | ) | const [virtual] |
std::array< float, 3 > AHRS_madgwick::linear_acceleration | ( | void | ) | const [virtual] |
bool AHRS_madgwick::update | ( | void | ) | [virtual] |