mirror of https://github.com/ArduPilot/ardupilot
Copter: do not speed up EKF failsafe if optflow works
This commit is contained in:
parent
59f2b42bd9
commit
491ac8f1a7
|
@ -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++;
|
||||
|
|
Loading…
Reference in New Issue