AP_NavEKF: raise EKF_POS_GATE and EKF_GLITCH_RAD for planes

This weights GPS position more heavily for planes

Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
This commit is contained in:
Andrew Tridgell 2015-01-31 08:38:28 +11:00
parent 2684d55b59
commit 850af14949

View File

@ -87,12 +87,12 @@
#define MAGE_PNOISE_DEFAULT 0.0003f
#define MAGB_PNOISE_DEFAULT 0.0003f
#define VEL_GATE_DEFAULT 6
#define POS_GATE_DEFAULT 10
#define POS_GATE_DEFAULT 30
#define HGT_GATE_DEFAULT 20
#define MAG_GATE_DEFAULT 3
#define MAG_CAL_DEFAULT 0
#define GLITCH_ACCEL_DEFAULT 150
#define GLITCH_RADIUS_DEFAULT 15
#define GLITCH_RADIUS_DEFAULT 20
#define FLOW_MEAS_DELAY 25
#define FLOW_NOISE_DEFAULT 0.3f
#define FLOW_GATE_DEFAULT 3