Plane: abort landing at 90% throttle instead of 95%

This commit is contained in:
Tom Pittenger 2016-02-01 02:56:24 -08:00
parent b098466e87
commit 046741d23b

View File

@ -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