Paparazzi UAS
v5.8.2_stable-0-g6260b7c
Paparazzi is a free software Unmanned Aircraft System.
|
Interface for extended vertical filter (in float). More...
Go to the source code of this file.
Data Structures | |
struct | VffExtended |
Macros | |
#define | VFF_STATE_SIZE 4 |
Functions | |
void | vff_init_zero (void) |
void | vff_init (float z, float zdot, float accel_bias, float baro_offset) |
void | vff_propagate (float accel, float dt) |
Propagate the filter in time. More... | |
void | vff_update_baro (float z_meas) |
void | vff_update_z (float z_meas) |
void | vff_update_offset (float offset) |
void | vff_update_baro_conf (float z_meas, float conf) |
void | vff_update_z_conf (float z_meas, float conf) |
void | vff_realign (float z_meas) |
Variables | |
struct VffExtended | vff |
Interface for extended vertical filter (in float).
Definition in file vf_extended_float.h.
struct VffExtended |
Definition at line 35 of file vf_extended_float.h.
Data Fields | ||
---|---|---|
float | bias | accel bias estimate in m/s^2 |
float | offset | baro offset estimate |
float | P[VFF_STATE_SIZE][VFF_STATE_SIZE] | covariance matrix |
float | z | z-position estimate in m (NED, z-down) |
float | z_meas | last z measurement in m |
float | z_meas_baro | last z measurement from baro in m |
float | zdot | z-velocity estimate in m/s (NED, z-down) |
float | zdotdot | z-acceleration in m/s^2 (NED, z-down) |
#define VFF_STATE_SIZE 4 |
Definition at line 33 of file vf_extended_float.h.
Referenced by vff_init().
void vff_init | ( | float | z, |
float | zdot, | ||
float | accel_bias, | ||
float | baro_offset | ||
) |
Definition at line 85 of file vf_extended_float.c.
References VffExtended::bias, DefaultPeriodic, VffExtended::offset, VffExtended::P, register_periodic_telemetry(), vff, VFF_EXTENDED_INIT_PXX, VFF_STATE_SIZE, VffExtended::z, and VffExtended::zdot.
Referenced by vff_init_zero(), and vff_realign().
void vff_init_zero | ( | void | ) |
Definition at line 80 of file vf_extended_float.c.
void vff_propagate | ( | float | accel, |
float | dt | ||
) |
Propagate the filter in time.
F = [ 1 dt -dt^2/2 0 0 1 -dt 0 0 0 1 0 0 0 0 1 ];
B = [ dt^2/2 dt 0 0]';
Q = [ Qzz 0 0 0 0 Qzdotzdot 0 0 0 0 Qbiasbias 0 0 0 0 0 Qoffoff ];
Qzz = VFF_EXTENDED_ACCEL_NOISE * DT_VFILTER * DT_VFILTER / 2. Qzdotzdot = VFF_EXTENDED_ACCEL_NOISE * DT_VFILTER
Xk1 = F * Xk0 + B * accel;
Pk1 = F * Pk0 * F' + Q;
F = [ 1 dt -dt^2/2 0 1 -dt 0 0 1 ];
B = [ dt^2/2 dt 0]';
Q = [ 0.01 0 0 0 0.01 0 0 0 0.001 ];
Xk1 = F * Xk0 + B * accel;
Pk1 = F * Pk0 * F' + Q;
Definition at line 127 of file vf_extended_float.c.
void vff_realign | ( | float | z_meas | ) |
Definition at line 347 of file vf_extended_float.c.
void vff_update_baro | ( | float | z_meas | ) |
Definition at line 216 of file vf_extended_float.c.
References R_BARO, and update_baro_conf().
Referenced by baro_cb().
void vff_update_baro_conf | ( | float | z_meas, |
float | conf | ||
) |
Definition at line 221 of file vf_extended_float.c.
References update_baro_conf().
void vff_update_offset | ( | float | offset | ) |
Definition at line 341 of file vf_extended_float.c.
References R_OFFSET, and update_offset_conf().
void vff_update_z | ( | float | z_meas | ) |
Definition at line 279 of file vf_extended_float.c.
References R_ALT, and update_alt_conf().
void vff_update_z_conf | ( | float | z_meas, |
float | conf | ||
) |
Definition at line 284 of file vf_extended_float.c.
struct VffExtended vff |
Definition at line 66 of file vf_extended_float.c.