Browse Source

Plane: update flight stage on successful restart_landing_sequence()

master
Tom Pittenger 9 years ago
parent
commit
9aa25cb7a0
  1. 5
      ArduPlane/landing.cpp

5
ArduPlane/landing.cpp

@ -296,6 +296,11 @@ bool Plane::restart_landing_sequence() @@ -296,6 +296,11 @@ bool Plane::restart_landing_sequence()
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unable to restart landing sequence");
success = false;
}
if (success) {
// exit landing stages if we're no longer executing NAV_LAND
update_flight_stage();
}
return success;
}

Loading…
Cancel
Save