mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: Reduce impact of altimeter flow disturbance error on Copter alt hold
This increase in assumed altimeter noise and reduction in accel noise has been flight tested by L.Hall with noticeable reduction in the immediate response to Baro errors during moving flight. This increases the time constant of response to baro errors such that the pilot can more easily compensate.
This commit is contained in:
parent
e692e30988
commit
1cf626692c
|
@ -18,7 +18,7 @@
|
||||||
#define VELNE_NOISE_DEFAULT 0.5f
|
#define VELNE_NOISE_DEFAULT 0.5f
|
||||||
#define VELD_NOISE_DEFAULT 0.7f
|
#define VELD_NOISE_DEFAULT 0.7f
|
||||||
#define POSNE_NOISE_DEFAULT 1.0f
|
#define POSNE_NOISE_DEFAULT 1.0f
|
||||||
#define ALT_NOISE_DEFAULT 2.0f
|
#define ALT_NOISE_DEFAULT 5.0f
|
||||||
#define MAG_NOISE_DEFAULT 0.05f
|
#define MAG_NOISE_DEFAULT 0.05f
|
||||||
#define GYRO_PNOISE_DEFAULT 0.005f
|
#define GYRO_PNOISE_DEFAULT 0.005f
|
||||||
#define ACC_PNOISE_DEFAULT 0.25f
|
#define ACC_PNOISE_DEFAULT 0.25f
|
||||||
|
|
Loading…
Reference in New Issue