From 8ac6343730fd1b2378ad48c265db97c5624999db Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 12 Feb 2016 11:22:59 -0800 Subject: [PATCH] Plane: removing mission_cmd in TECS and making it bool is_landing this is reverse-thrust cleanup suggested by Tridge --- ArduPlane/ArduPlane.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 8f5a73755b..b78501abfe 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -876,11 +876,12 @@ void Plane::update_alt() update_flight_stage(); + bool is_doing_auto_land = (control_mode == AUTO) && (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND); if (auto_throttle_mode && !throttle_suppressed) { SpdHgt_Controller->update_pitch_throttle(relative_target_altitude_cm(), target_airspeed_cm, flight_stage, - mission.get_current_nav_cmd().id, + is_doing_auto_land, auto_state.takeoff_pitch_cd, throttle_nudge, tecs_hgt_afe(),