Browse Source

AP_NavEKF3: Update default plane optical flow param values

Reduce time required to form estimate of terrain offset
master
Paul Riseborough 6 years ago committed by Andrew Tridgell
parent
commit
d3e9281846
  1. 4
      libraries/AP_NavEKF3/AP_NavEKF3.cpp

4
libraries/AP_NavEKF3/AP_NavEKF3.cpp

@ -81,8 +81,8 @@
#define MAG_CAL_DEFAULT 0 #define MAG_CAL_DEFAULT 0
#define GLITCH_RADIUS_DEFAULT 25 #define GLITCH_RADIUS_DEFAULT 25
#define FLOW_MEAS_DELAY 10 #define FLOW_MEAS_DELAY 10
#define FLOW_M_NSE_DEFAULT 0.25f #define FLOW_M_NSE_DEFAULT 0.15f
#define FLOW_I_GATE_DEFAULT 300 #define FLOW_I_GATE_DEFAULT 500
#define CHECK_SCALER_DEFAULT 100 #define CHECK_SCALER_DEFAULT 100
#define FLOW_USE_MASK_DEFAULT 2 #define FLOW_USE_MASK_DEFAULT 2

Loading…
Cancel
Save