AP_TECS: Remove duplicate setting of flare pitch upper limit

This commit is contained in:
Paul Riseborough 2022-11-29 10:29:32 +11:00 committed by Peter Barker
parent dab61bf3ef
commit 93ae6f1739
1 changed files with 0 additions and 7 deletions

View File

@ -1262,13 +1262,6 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
_PITCHminf = MAX(_land_pitch_min, _PITCHminf);
}
if (_landing.is_flaring()) {
// ensure we don't violate the limits for flare pitch
if (_land_pitch_max != 0) {
_PITCHmaxf = MIN(_land_pitch_max, _PITCHmaxf);
}
}
if (flight_stage == AP_FixedWing::FlightStage::TAKEOFF || flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {
if (!_flags.reached_speed_takeoff && _TAS_state >= _TAS_dem_adj) {
// we have reached our target speed in takeoff, allow for