From cdfd337ef7d1b8c2b6be63f5707aa3457a5e3593 Mon Sep 17 00:00:00 2001 From: Tim Tuxworth Date: Tue, 19 Dec 2023 16:03:31 -0700 Subject: [PATCH] AP_TECS: fix incorrect reference to plane pitch_trim --- libraries/AP_TECS/AP_TECS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index c87bca1e026dc4..4bc63c7aca950c 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -849,7 +849,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.pitch, _DT); - const float pitch_corrected_lpf = _pitch_measured_lpf.get() - radians(aparm.pitch_trim); + 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)