mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
Copter: auto RTL: don't switch modes if already in auto
This commit is contained in:
parent
d31f3eb4c5
commit
09f1a3da8a
@ -166,7 +166,8 @@ bool ModeAuto::jump_to_landing_sequence_auto_RTL(ModeReason reason)
|
||||
{
|
||||
if (mission.jump_to_landing_sequence()) {
|
||||
mission.set_force_resume(true);
|
||||
if (set_mode(Mode::Number::AUTO, reason)) {
|
||||
// if not already in auto switch to auto
|
||||
if ((copter.flightmode == &copter.mode_auto) || set_mode(Mode::Number::AUTO, reason)) {
|
||||
auto_RTL = true;
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user