Copter: do not speed up EKF failsafe if optflow works

This commit is contained in:
chobits 2019-10-03 14:15:01 +08:00 committed by Randy Mackay
parent db7836ad48
commit 5a0fe4e322

View File

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