Browse Source

Copter: ekf failsafe can trigger in LAND

Thanks to John Ingersoll for the report and detailed fix
Resolves issue #4827
master
Randy Mackay 8 years ago
parent
commit
263f685683
  1. 2
      ArduCopter/ekf_check.cpp

2
ArduCopter/ekf_check.cpp

@ -129,7 +129,7 @@ void Copter::failsafe_ekf_event() @@ -129,7 +129,7 @@ void Copter::failsafe_ekf_event()
}
// do nothing if not in GPS flight mode and ekf-action is not land-even-stabilize
if (!mode_requires_GPS(control_mode) && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_STABILIZE)) {
if (!mode_requires_GPS(control_mode) && (control_mode != LAND) && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_STABILIZE)) {
return;
}

Loading…
Cancel
Save