Plane: Fix a fly away when aborting a landing

DO_LAND_START -> LAND waypoints in sequence would cause a perpetual abort state
due to the sticky nature of the abort states. If we restart a landing on
purpose while doing an abort, then we can move onto trying to land again.
This commit is contained in:
Michael du Breuil 2017-06-15 19:00:54 -07:00 committed by Andrew Tridgell
parent 97e88501c6
commit 92cdb54176

View File

@ -401,6 +401,11 @@ void Plane::do_land(const AP_Mission::Mission_Command& cmd)
landing.do_land(cmd, relative_altitude);
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
// if we were in an abort we need to explicitly move out of the abort state, as it's sticky
set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_LAND);
}
#if GEOFENCE_ENABLED == ENABLED
if (g.fence_autoenable == 1) {
if (! geofence_set_enabled(false, AUTO_TOGGLED)) {