From 491ac8f1a769321ef8b21e7f6c77badd19018876 Mon Sep 17 00:00:00 2001 From: chobits Date: Thu, 3 Oct 2019 14:15:01 +0800 Subject: [PATCH] Copter: do not speed up EKF failsafe if optflow works --- ArduCopter/ekf_check.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index b53df9c767..8204a4f82d 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -110,7 +110,7 @@ bool Copter::ekf_over_threshold() if (mag_variance.length() >= g.fs_ekf_thresh) { over_thresh_count++; } - if (vel_variance >= (2.0f * g.fs_ekf_thresh)) { + if (!optflow.healthy() && (vel_variance >= (2.0f * g.fs_ekf_thresh))) { over_thresh_count += 2; } else if (vel_variance >= g.fs_ekf_thresh) { over_thresh_count++;