From 046741d23b05adc2268309722eeff9b509b00bd1 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Mon, 1 Feb 2016 02:56:24 -0800 Subject: [PATCH] Plane: abort landing at 90% throttle instead of 95% --- ArduPlane/ArduPlane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index bce2f2bfbf..8f5a73755b 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -905,7 +905,7 @@ void Plane::update_flight_stage(void) set_flight_stage(AP_SpdHgtControl::FLIGHT_TAKEOFF); } else if (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND) { - if ((g.land_abort_throttle_enable && channel_throttle->control_in > 95) || + if ((g.land_abort_throttle_enable && channel_throttle->control_in >= 90) || auto_state.commanded_go_around || flight_stage == AP_SpdHgtControl::FLIGHT_LAND_ABORT){ // abort mode is sticky, it must complete while executing NAV_LAND