AP_NavEKF : Increased position gate default to reduce impact of accel errors

Flight testing with windup turns has shown that the position gate threshold
can be tripped with good GPS data causing position jerks. This increases the
initial GPS glitch rejection threshold to effectively 5m when using the
default POSNE_NOISE value of 0.5m.
This commit is contained in:
priseborough 2014-04-12 14:26:49 +10:00 committed by Andrew Tridgell
parent 188bea6bab
commit d745dc2b6f

View File

@ -39,7 +39,7 @@
#define MAGE_PNOISE_DEFAULT 0.0003f #define MAGE_PNOISE_DEFAULT 0.0003f
#define MAGB_PNOISE_DEFAULT 0.0003f #define MAGB_PNOISE_DEFAULT 0.0003f
#define VEL_GATE_DEFAULT 2 #define VEL_GATE_DEFAULT 2
#define POS_GATE_DEFAULT 5 #define POS_GATE_DEFAULT 10
#define HGT_GATE_DEFAULT 5 #define HGT_GATE_DEFAULT 5
#define MAG_GATE_DEFAULT 3 #define MAG_GATE_DEFAULT 3
#define MAG_CAL_DEFAULT 1 #define MAG_CAL_DEFAULT 1
@ -60,7 +60,7 @@
#define MAGE_PNOISE_DEFAULT 0.0003f #define MAGE_PNOISE_DEFAULT 0.0003f
#define MAGB_PNOISE_DEFAULT 0.0003f #define MAGB_PNOISE_DEFAULT 0.0003f
#define VEL_GATE_DEFAULT 2 #define VEL_GATE_DEFAULT 2
#define POS_GATE_DEFAULT 5 #define POS_GATE_DEFAULT 10
#define HGT_GATE_DEFAULT 5 #define HGT_GATE_DEFAULT 5
#define MAG_GATE_DEFAULT 3 #define MAG_GATE_DEFAULT 3
#define MAG_CAL_DEFAULT 1 #define MAG_CAL_DEFAULT 1
@ -81,7 +81,7 @@
#define MAGE_PNOISE_DEFAULT 0.0003f #define MAGE_PNOISE_DEFAULT 0.0003f
#define MAGB_PNOISE_DEFAULT 0.0003f #define MAGB_PNOISE_DEFAULT 0.0003f
#define VEL_GATE_DEFAULT 3 #define VEL_GATE_DEFAULT 3
#define POS_GATE_DEFAULT 5 #define POS_GATE_DEFAULT 10
#define HGT_GATE_DEFAULT 10 #define HGT_GATE_DEFAULT 10
#define MAG_GATE_DEFAULT 3 #define MAG_GATE_DEFAULT 3
#define MAG_CAL_DEFAULT 0 #define MAG_CAL_DEFAULT 0