AP_NavEKF2: Parameter changes to reduce noise on gyro bias estimates

This commit is contained in:
Paul Riseborough 2015-11-18 19:05:58 +11:00 committed by Randy Mackay
parent 2193103586
commit ff2782b790

View File

@ -21,7 +21,7 @@
#define MAG_NOISE_DEFAULT 0.05f
#define GYRO_PNOISE_DEFAULT 0.001f
#define ACC_PNOISE_DEFAULT 0.25f
#define GBIAS_PNOISE_DEFAULT 7.0E-05f
#define GBIAS_PNOISE_DEFAULT 3.5E-05f
#define ABIAS_PNOISE_DEFAULT 1.0E-04f
#define MAG_PNOISE_DEFAULT 2.5E-02f
#define VEL_GATE_DEFAULT 200
@ -93,7 +93,7 @@
#define MAG_NOISE_DEFAULT 0.05f
#define GYRO_PNOISE_DEFAULT 0.001f
#define ACC_PNOISE_DEFAULT 0.25f
#define GBIAS_PNOISE_DEFAULT 7.0E-05f
#define GBIAS_PNOISE_DEFAULT 3.5E-05f
#define ABIAS_PNOISE_DEFAULT 1.0E-04f
#define MAG_PNOISE_DEFAULT 2.5E-02f
#define VEL_GATE_DEFAULT 200