AP_TECS: Corrected formula for _TASmin according to fix in formula for the load factor

To connect loadFactor to airspeed we can use formula of balancing between lift force and gravity force:
liftForce = loadFactor * gravityForce; on the other hand lift force can be expressed as
liftForce = 0.5 * lifCoefficient * airDensity * sq(airspeed) * referenceArea; minimum airseepd is at loadFactor = 1
and lift force only balances the gravit force, so gravity force (which is same as lift force at minimum airspeed) with minimum airspeed can be expressed as
gravityForce = 0.5 * lifCoefficient * airDensity * sq(airspeed_min) * referenceArea; substituting gravit force in previous formula gives us
0.5 * lifCoefficient * airDensity * sq(airspeed) * referenceArea = loadFactor * 0.5 * lifCoefficient * airDensity * sq(airspeed_min) * referenceArea;
from where we get:
loadFactor = sq(airspeed / airspeed_min); and_TASmin should be
_TASmin *= safe_sqrt(_load_factor);
This commit is contained in:
abaghiyan 2023-08-05 00:37:31 +04:00 committed by Andrew Tridgell
parent 26cbdd9a4c
commit 9893017f3c

View File

@ -415,9 +415,9 @@ void AP_TECS::_update_speed(float DT)
// when stall prevention is active we raise the minimum // when stall prevention is active we raise the minimum
// airspeed based on aerodynamic load factor // airspeed based on aerodynamic load factor
if (is_positive(aparm.airspeed_stall)) { if (is_positive(aparm.airspeed_stall)) {
_TASmin = MAX(_TASmin, aparm.airspeed_stall*EAS2TAS*_load_factor); _TASmin = MAX(_TASmin, aparm.airspeed_stall*EAS2TAS*sqrtf(_load_factor));
} else { } else {
_TASmin *= _load_factor; _TASmin *= sqrtf(_load_factor);
} }
} }