In general when there the pitch and roll exist the formula for the aerodynamic load factor should be as follows:
aerodynamic_load_factor = cosf(radians(_ahrs.pitch))/cosf(radians(demanded_roll));
which in case of turns (in the horizontal plane) becomes
aerodynamic_load_factor = 1.0f/cosf(radians(demanded_roll));
formulas can be obtained from equations of balanced spiral:
liftForce * cos(roll) = gravityForce * cos(pitch);
liftForce * sin(roll) = gravityForce * lateralAcceleration / gravityAcceleration; // as mass = gravityForce/gravityAcceleration
see issue #24320 [#24320].
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);
These changes also require changes in ardupilot/libraries/AP_TECS/AP_TECS.cpp
Line 418 (according to the comments by Peter Hall): _TASmin *= _load_factor; should be changed to _TASmin *= safe_sqrt(_load_factor);
See details here: #24320
Updated the forward throttle battery voltage compensation feature to
disable the throttle entirely when the sag-compensated voltage drops
below the new parameter FWD_THR_CUTOFF_V.
Key changes:
- Added new parameter FWD_THR_CUTOFF_V to control the voltage threshold
for this feature. The default value of 0 matches the original behavior
of never cutting the throttle due to low voltage.
- Modified forward throttle battery voltage compensation logic in the
servos code to cut off the throttle in auto-throttle modes if the
resting voltage estimate of the FWD_BAT_IDX battery is under
FWD_THR_CUTOFF_V.
../../ArduPlane/quadplane.cpp:4260:15: warning: Value stored to 'approach_speed' during its initialization is never read [deadcode.DeadStores]
float approach_speed = cruise_speed;
^~~~~~~~~~~~~~ ~~~~~~~~~~~~
1 warning generated.
57a3bc1397 changed the code from "internal" to "in-flight
It seems the old value of "1" was no longer valid
It also changed things to that the learning system saved the offsets.