mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Copter: RTL if not in AUTO mode and FS_THR_ENABLED_CONTINUE_MISSION enabled
This commit is contained in:
parent
59e087214f
commit
a3587f844c
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user