From e2148e7e2a1b0885218608ce0180f4b5faa04865 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Mon, 25 Feb 2019 15:05:05 +1100 Subject: [PATCH] AP_NavEKF2: Update default plane optical flow param values Reduce time required to form estimate of terrain offset --- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 572f777cb2..31063b4932 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -84,8 +84,8 @@ #define MAG_CAL_DEFAULT 0 #define GLITCH_RADIUS_DEFAULT 25 #define FLOW_MEAS_DELAY 10 -#define FLOW_M_NSE_DEFAULT 0.25f -#define FLOW_I_GATE_DEFAULT 300 +#define FLOW_M_NSE_DEFAULT 0.15f +#define FLOW_I_GATE_DEFAULT 500 #define CHECK_SCALER_DEFAULT 150 #define FLOW_USE_MASK_DEFAULT 2