mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_TECS: gain scaler K_STE2Thr multiplies by (THRmax - THRmin)
Makes both feed forward and feed-back consistent
This commit is contained in:
parent
348dbdaf22
commit
eebef857f1
@ -608,7 +608,8 @@ void AP_TECS::_update_throttle_with_airspeed(void)
|
|||||||
else
|
else
|
||||||
{
|
{
|
||||||
// Calculate gain scaler from specific energy error to throttle
|
// 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
|
// Calculate feed-forward throttle
|
||||||
float ff_throttle = 0;
|
float ff_throttle = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user