From 850af149498f155cb46229318000f438d69721ac Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 31 Jan 2015 08:38:28 +1100 Subject: [PATCH] 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 --- libraries/AP_NavEKF/AP_NavEKF.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 520d056efd..16957d3806 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -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