Browse Source

Copter: speed up EKF failsafe by checking if velocity innovations > 2x FS_EKF_THRESH

master
chobits 6 years ago committed by Randy Mackay
parent
commit
6bee4216c0
  1. 4
      ArduCopter/ekf_check.cpp

4
ArduCopter/ekf_check.cpp

@ -105,7 +105,9 @@ bool Copter::ekf_over_threshold()
if (mag_variance.length() >= g.fs_ekf_thresh) { if (mag_variance.length() >= g.fs_ekf_thresh) {
over_thresh_count++; over_thresh_count++;
} }
if (vel_variance >= g.fs_ekf_thresh) { if (vel_variance >= (2.0f * g.fs_ekf_thresh)) {
over_thresh_count+=2;
} else if (vel_variance >= g.fs_ekf_thresh) {
over_thresh_count++; over_thresh_count++;
} }
if (position_variance >= g.fs_ekf_thresh) { if (position_variance >= g.fs_ekf_thresh) {

Loading…
Cancel
Save