In Standard C, the first three file descriptors are usually standard in,
out, and error. However, ArduPilot doesn't have a concept of this and
other backends (such as LittleFS) don't bother to reject them.
Remove this logic to simplify implementation and allow use of more open
files.
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);
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
command-line has changed (if indeed this is the same command!)
Regardless, autotest server has some grandfathered binary in place in $HOME/bin/timelimit and we do want to move past it at some stage
lseek must return the current file position. Previously, the littlefs
version always returned 0, which broke terrain I/O as it checks that the
position returned is the one it seeked to. Fix to return the current
position, which is correctly returned from littlefs.
This problem was originally and incorrectly diagnosed as an issue with
littlefs seeking past the end of the file, but this functionality works
fine and fixing the incorrect return completely fixes terrain.
Terrain functionality was verified using `TERRAIN_DEBUG` on
KakuteH7Mini-Nand running sim on HW. Terrain data is correctly
downloaded from the GCS and loaded from the filesystem after reboot.