mirror of https://github.com/ArduPilot/ardupilot
Rover: enter Hold on failure to enter RTL fs action
This commit is contained in:
parent
f3b794f698
commit
9d7eb188d1
|
@ -72,7 +72,9 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on)
|
|||
case 0:
|
||||
break;
|
||||
case 1:
|
||||
set_mode(mode_rtl, MODE_REASON_FAILSAFE);
|
||||
if (!set_mode(mode_rtl, MODE_REASON_FAILSAFE)) {
|
||||
set_mode(mode_hold, MODE_REASON_FAILSAFE);
|
||||
}
|
||||
break;
|
||||
case 2:
|
||||
set_mode(mode_hold, MODE_REASON_FAILSAFE);
|
||||
|
|
Loading…
Reference in New Issue