mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
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:
parent
97e88501c6
commit
92cdb54176
@ -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)) {
|
||||
|
Loading…
Reference in New Issue
Block a user