Plane: force mission resume on RTL when DO_LAND_START in mission

This commit is contained in:
Gone4Dirt 2020-02-23 09:54:30 +00:00 committed by Andrew Tridgell
parent db364257d8
commit f7ac15800b
1 changed files with 2 additions and 0 deletions

View File

@ -462,6 +462,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);
}
@ -474,6 +475,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);
}