Copter: EKF failsafe action always Land if RC failsafe active

This commit is contained in:
Jonathan Challinger 2015-10-18 10:05:37 +09:00 committed by Randy Mackay
parent 6d266d2063
commit 598925f8d2

View File

@ -141,7 +141,7 @@ void Copter::failsafe_ekf_event()
switch (g.fs_ekf_action) {
case FS_EKF_ACTION_ALTHOLD:
// AltHold
if (!set_mode(ALT_HOLD)) {
if (failsafe.radio || !set_mode(ALT_HOLD)) {
set_mode_land_with_pause();
}
break;