Copter: RTL if not in AUTO mode and FS_THR_ENABLED_CONTINUE_MISSION enabled

This commit is contained in:
Lauri Juusela 2018-07-09 16:15:17 +03:00 committed by Randy Mackay
parent 59e087214f
commit a3587f844c

View File

@ -23,6 +23,8 @@ void Copter::failsafe_radio_on_event()
} else {
if (g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_RTL) {
set_mode_RTL_or_land_with_pause(MODE_REASON_RADIO_FAILSAFE);
} else if (g.failsafe_throttle == FS_THR_ENABLED_CONTINUE_MISSION) {
set_mode_RTL_or_land_with_pause(MODE_REASON_RADIO_FAILSAFE);
} else if (g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL) {
set_mode_SmartRTL_or_RTL(MODE_REASON_RADIO_FAILSAFE);
} else if (g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_LAND) {