mirror of https://github.com/ArduPilot/ardupilot
Plane: Mode: ensure flight stage is correct on successful mode change
This commit is contained in:
parent
21a9f8e3a2
commit
740b04aed3
|
@ -135,6 +135,9 @@ bool Mode::enter()
|
|||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "In landing sequence: mission reset");
|
||||
plane.mission.reset();
|
||||
}
|
||||
|
||||
// Make sure the flight stage is correct for the new mode
|
||||
plane.update_flight_stage();
|
||||
}
|
||||
|
||||
return enter_result;
|
||||
|
|
Loading…
Reference in New Issue