Plane: removing mission_cmd in TECS and making it bool is_landing

this is reverse-thrust cleanup suggested by Tridge
This commit is contained in:
Tom Pittenger 2016-02-12 11:22:59 -08:00
parent e40bba3d13
commit 8ac6343730

View File

@ -876,11 +876,12 @@ void Plane::update_alt()
update_flight_stage(); 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) { if (auto_throttle_mode && !throttle_suppressed) {
SpdHgt_Controller->update_pitch_throttle(relative_target_altitude_cm(), SpdHgt_Controller->update_pitch_throttle(relative_target_altitude_cm(),
target_airspeed_cm, target_airspeed_cm,
flight_stage, flight_stage,
mission.get_current_nav_cmd().id, is_doing_auto_land,
auto_state.takeoff_pitch_cd, auto_state.takeoff_pitch_cd,
throttle_nudge, throttle_nudge,
tecs_hgt_afe(), tecs_hgt_afe(),