Skip to content

Commit a3f97d1

Browse files
committed
AP_TECS: moved justifications to commit description
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 cbc0498 commit a3f97d1

File tree

1 file changed

+1
-6
lines changed

1 file changed

+1
-6
lines changed

libraries/AP_TECS/AP_TECS.cpp

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -415,12 +415,7 @@ void AP_TECS::_update_speed(float DT)
415415
if (aparm.stall_prevention) {
416416
// when stall prevention is active we raise the minimum
417417
// airspeed based on aerodynamic load factor
418-
/*
419-
As load factor formula fixed in ArduPlane Plane::update_load_factor,
420-
here also should be changes done according to comments by Peter Hall
421-
see issue #24320 [https://github.com/ArduPilot/ardupilot/issues/24320].
422-
*/
423-
418+
424419
_TASmin *= safe_sqrt(_load_factor);
425420
}
426421

0 commit comments

Comments
 (0)