Skip to content

Commit

Permalink
AP_TECS: gain scaler K_STE2Thr multiplies by (THRmax - THRmin)
Browse files Browse the repository at this point in the history
Makes both feed forward and feed-back consistent
  • Loading branch information
nocternal authored and OXINARF committed Aug 15, 2017
1 parent 348dbda commit eebef85
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion libraries/AP_TECS/AP_TECS.cpp
Expand Up @@ -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;
Expand Down

0 comments on commit eebef85

Please sign in to comment.