Skip to content

Commit 9893017

Browse files
abaghiyantridge
authored andcommitted
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);
1 parent 26cbdd9 commit 9893017

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

libraries/AP_TECS/AP_TECS.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -415,9 +415,9 @@ void AP_TECS::_update_speed(float DT)
415415
// when stall prevention is active we raise the minimum
416416
// airspeed based on aerodynamic load factor
417417
if (is_positive(aparm.airspeed_stall)) {
418-
_TASmin = MAX(_TASmin, aparm.airspeed_stall*EAS2TAS*_load_factor);
418+
_TASmin = MAX(_TASmin, aparm.airspeed_stall*EAS2TAS*sqrtf(_load_factor));
419419
} else {
420-
_TASmin *= _load_factor;
420+
_TASmin *= sqrtf(_load_factor);
421421
}
422422
}
423423

0 commit comments

Comments
 (0)