AP_TECS: use new pitch_trim in degrees

This commit is contained in:
Tim Tuxworth 2023-12-14 11:46:41 -07:00 committed by Andrew Tridgell
parent 4919ae8f59
commit b1c8511386
1 changed files with 1 additions and 1 deletions

View File

@ -859,7 +859,7 @@ void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge)
_pitch_demand_lpf.apply(_pitch_dem, _DT);
const float pitch_demand_hpf = _pitch_dem - _pitch_demand_lpf.get();
_pitch_measured_lpf.apply(_ahrs.get_pitch(), _DT);
const float pitch_corrected_lpf = _pitch_measured_lpf.get() - radians(0.01f * (float)aparm.pitch_trim_cd);
const float pitch_corrected_lpf = _pitch_measured_lpf.get();
const float pitch_blended = pitch_demand_hpf + pitch_corrected_lpf;
if (pitch_blended > 0.0f && _PITCHmaxf > 0.0f)