From c40e0ffb6b5f6de7bfcb4acc344fd925a65cc390 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 22 Sep 2019 16:30:41 +1000 Subject: [PATCH] Copter: fixed EKF threshold for arming when EKF failsafe is disabled by setting threshold to zero we need to disable this arming check --- ArduCopter/AP_Arming.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 5e8691ee2c..92af66d877 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -382,7 +382,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure) Vector3f mag_variance; Vector2f offset; ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance, offset); - if (mag_variance.length() >= copter.g.fs_ekf_thresh) { + if (copter.g.fs_ekf_thresh > 0 && mag_variance.length() >= copter.g.fs_ekf_thresh) { check_failed(ARMING_CHECK_NONE, display_failure, "EKF compass variance"); return false; }