30#ifndef INS_MEKF_WIND_H 
   31#define INS_MEKF_WIND_H 
  101#define ins_mekf_wind_update_Q_gyro(_v) { \ 
  102  ins_mekf_wind_params.Q_gyro = _v; \ 
  103  ins_mekf_wind_update_params(); \ 
 
  106#define ins_mekf_wind_update_Q_accel(_v) { \ 
  107  ins_mekf_wind_params.Q_accel = _v; \ 
  108  ins_mekf_wind_update_params(); \ 
 
  111#define ins_mekf_wind_update_Q_rates_bias(_v) { \ 
  112  ins_mekf_wind_params.Q_rates_bias = _v; \ 
  113  ins_mekf_wind_update_params(); \ 
 
  116#define ins_mekf_wind_update_Q_accel_bias(_v) { \ 
  117  ins_mekf_wind_params.Q_accel_bias = _v; \ 
  118  ins_mekf_wind_update_params(); \ 
 
  121#define ins_mekf_wind_update_Q_baro_bias(_v) { \ 
  122  ins_mekf_wind_params.Q_baro_bias = _v; \ 
  123  ins_mekf_wind_update_params(); \ 
 
  126#define ins_mekf_wind_update_Q_wind(_v) { \ 
  127  ins_mekf_wind_params.Q_wind = _v; \ 
  128  ins_mekf_wind_update_params(); \ 
 
  131#define ins_mekf_wind_update_R_speed(_v) { \ 
  132  ins_mekf_wind_params.R_speed = _v; \ 
  133  ins_mekf_wind_update_params(); \ 
 
  136#define ins_mekf_wind_update_R_pos(_v) { \ 
  137  ins_mekf_wind_params.R_pos = _v; \ 
  138  ins_mekf_wind_update_params(); \ 
 
  141#define ins_mekf_wind_update_R_speed_z(_v) { \ 
  142  ins_mekf_wind_params.R_speed_z = _v; \ 
  143  ins_mekf_wind_update_params(); \ 
 
  146#define ins_mekf_wind_update_R_pos_z(_v) { \ 
  147  ins_mekf_wind_params.R_pos_z = _v; \ 
  148  ins_mekf_wind_update_params(); \ 
 
  151#define ins_mekf_wind_update_R_mag(_v) { \ 
  152  ins_mekf_wind_params.R_mag = _v; \ 
  153  ins_mekf_wind_update_params(); \ 
 
  156#define ins_mekf_wind_update_R_baro(_v) { \ 
  157  ins_mekf_wind_params.R_baro = _v; \ 
  158  ins_mekf_wind_update_params(); \ 
 
  161#define ins_mekf_wind_update_R_airspeed(_v) { \ 
  162  ins_mekf_wind_params.R_airspeed = _v; \ 
  163  ins_mekf_wind_update_params(); \ 
 
  166#define ins_mekf_wind_update_R_aoa(_v) { \ 
  167  ins_mekf_wind_params.R_aoa = _v; \ 
  168  ins_mekf_wind_update_params(); \ 
 
  171#define ins_mekf_wind_update_R_aos(_v) { \ 
  172  ins_mekf_wind_params.R_aos = _v; \ 
  173  ins_mekf_wind_update_params(); \ 
 
float Q_accel
accel process noise
float ins_mekf_wind_get_baro_bias(void)
void ins_mekf_wind_set_quat(struct FloatQuat *quat)
struct NedCoor_f ins_mekf_wind_get_wind_ned(void)
void ins_mekf_wind_update_incidence(float aoa, float aos)
void ins_mekf_wind_set_pos_ned(struct NedCoor_f *p)
float ins_mekf_wind_get_airspeed_norm(void)
void ins_mekf_wind_propagate_ahrs(struct FloatRates *gyro, struct FloatVect3 *accel, float dt)
AHRS-only propagation + accel correction.
void ins_mekf_wind_update_baro(float baro_alt)
float Q_wind
wind process noise
float R_aos
sideslip angle measurement noise
struct NedCoor_f ins_mekf_wind_get_accel_ned(void)
void ins_mekf_wind_update_params(void)
void ins_mekf_wind_init(void)
Init function.
void ins_mekf_wind_set_mag_h(const struct FloatVect3 *mag_h)
struct NedCoor_f ins_mekf_wind_get_pos_ned(void)
Getter/Setter functions.
float R_baro
baro measurement noise
struct FloatRates ins_mekf_wind_get_body_rates(void)
void ins_mekf_wind_propagate(struct FloatRates *gyro, struct FloatVect3 *accel, float dt)
Full INS propagation.
void ins_mekf_wind_set_speed_ned(struct NedCoor_f *s)
float R_mag
mag measurement noise
void ins_mekf_wind_update_mag(struct FloatVect3 *mag, bool attitude_only)
struct ins_mekf_wind_parameters ins_mekf_wind_params
struct FloatVect3 ins_mekf_wind_get_accel_bias(void)
bool disable_wind
disable wind estimation
struct NedCoor_f ins_mekf_wind_get_airspeed_body(void)
struct FloatQuat ins_mekf_wind_get_quat(void)
float R_aoa
angle of attack measurement noise
void ins_mekf_wind_align(struct FloatRates *gyro_bias, struct FloatQuat *quat)
void ins_mekf_wind_reset(void)
float R_pos_z
vertical pos measurement noise
float Q_rates_bias
rates bias process noise
float R_airspeed
airspeed measurement noise
float Q_baro_bias
baro bias process noise
float Q_accel_bias
accel bias process noise
float R_pos
pos measurement noise
struct FloatRates ins_mekf_wind_get_rates_bias(void)
float R_speed
speed measurement noise
struct NedCoor_f ins_mekf_wind_get_speed_ned(void)
float R_speed_z
vertical speed measurement noise
float Q_gyro
gyro process noise
void ins_mekf_wind_update_airspeed(float airspeed)
void ins_mekf_wind_update_pos_speed(struct FloatVect3 *pos, struct FloatVect3 *speed)
Paparazzi floating point algebra.
Paparazzi floating point math for geodetic calculations.
vector in North East Down coordinates Units: meters