mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: force mission resume on RTL when DO_LAND_START in mission
This commit is contained in:
parent
d813a70c8d
commit
e02a9890b3
@ -467,6 +467,7 @@ void Plane::update_navigation()
|
||||
// we've reached the RTL point, see if we have a landing sequence
|
||||
if (mission.jump_to_landing_sequence()) {
|
||||
// switch from RTL -> AUTO
|
||||
mission.set_force_resume(true);
|
||||
set_mode(mode_auto, ModeReason::UNKNOWN);
|
||||
}
|
||||
|
||||
@ -479,6 +480,7 @@ void Plane::update_navigation()
|
||||
// Go directly to the landing sequence
|
||||
if (mission.jump_to_landing_sequence()) {
|
||||
// switch from RTL -> AUTO
|
||||
mission.set_force_resume(true);
|
||||
set_mode(mode_auto, ModeReason::UNKNOWN);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user