AP_NavEKF: Make copter glitch accel consistent with timeout and radius

This commit is contained in:
Paul Riseborough 2015-04-15 17:28:14 +10:00 committed by Randy Mackay
parent 5d70854c08
commit dffa2e19bf
1 changed files with 2 additions and 2 deletions

View File

@ -43,8 +43,8 @@
#define HGT_GATE_DEFAULT 10
#define MAG_GATE_DEFAULT 3
#define MAG_CAL_DEFAULT 1
#define GLITCH_ACCEL_DEFAULT 150
#define GLITCH_RADIUS_DEFAULT 15
#define GLITCH_ACCEL_DEFAULT 100
#define GLITCH_RADIUS_DEFAULT 25
#define FLOW_MEAS_DELAY 10
#define FLOW_NOISE_DEFAULT 0.25f
#define FLOW_GATE_DEFAULT 3