From eebef857f1a24a720a9fbdc712b6c050cd7eb191 Mon Sep 17 00:00:00 2001 From: JU Han <570818564@qq.com> Date: Sat, 12 Aug 2017 10:27:30 +0800 Subject: [PATCH] AP_TECS: gain scaler K_STE2Thr multiplies by (THRmax - THRmin) Makes both feed forward and feed-back consistent --- libraries/AP_TECS/AP_TECS.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 19d7581e80..cef7da74a0 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -608,7 +608,8 @@ void AP_TECS::_update_throttle_with_airspeed(void) else { // Calculate gain scaler from specific energy error to throttle - float K_STE2Thr = 1 / (timeConstant() * (_STEdot_max - _STEdot_min)); + // (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf) is the derivative of STEdot wrt throttle measured across the max allowed throttle range. + float K_STE2Thr = 1 / (timeConstant() * (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf)); // Calculate feed-forward throttle float ff_throttle = 0;