AP_NavEKF2: Update default plane optical flow param values

Reduce time required to form estimate of terrain offset
This commit is contained in:
Paul Riseborough 2019-02-25 15:05:05 +11:00 committed by Andrew Tridgell
parent 35c82ef67f
commit e2148e7e2a

View File

@ -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