Plane: Throttle based landing aborts should ask the landing library

Throttle based aborts should be requesting a go around from AP_Landing.
This was missed in the initial port.
This commit is contained in:
Michael du Breuil 2017-07-15 00:07:10 -07:00 committed by Tom Pittenger
parent e092a83ca2
commit f87a69dcf2

View File

@ -955,11 +955,11 @@ void Plane::update_flight_stage(void)
} else if (auto_state.takeoff_complete == false) {
set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_TAKEOFF);
} else if (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND) {
if (landing.is_commanded_go_around() || flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
// abort mode is sticky, it must complete while executing NAV_LAND
set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND);
} else if (landing.get_abort_throttle_enable() && channel_throttle->get_control_in() >= 90) {
} else if (landing.get_abort_throttle_enable() && channel_throttle->get_control_in() >= 90 &&
landing.request_go_around()) {
gcs().send_text(MAV_SEVERITY_INFO,"Landing aborted via throttle");
set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND);
} else {