mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: avoid FPE when running fly.ArduPlane
Program received signal SIGFPE, Arithmetic exception. __expf_finite () at ../sysdeps/x86_64/fpu/e_expf.S:132 132 ../sysdeps/x86_64/fpu/e_expf.S: No such file or directory. (gdb) u
This commit is contained in:
parent
b5e206f72f
commit
85ebe923b6
@ -90,7 +90,14 @@ float Plane::liftCoeff(float alpha) const
|
||||
const float M = coefficient.mcoeff;
|
||||
const float c_lift_0 = coefficient.c_lift_0;
|
||||
const float c_lift_a0 = coefficient.c_lift_a;
|
||||
|
||||
|
||||
// clamp the value of alpha to avoid exp(90) in calculation of sigmoid
|
||||
const float max_alpha_delta = 0.8f;
|
||||
if (alpha-alpha0 > max_alpha_delta) {
|
||||
alpha = alpha0 + max_alpha_delta;
|
||||
} else if (alpha0-alpha > max_alpha_delta) {
|
||||
alpha = alpha0 - max_alpha_delta;
|
||||
}
|
||||
double sigmoid = ( 1+exp(-M*(alpha-alpha0))+exp(M*(alpha+alpha0)) ) / (1+exp(-M*(alpha-alpha0))) / (1+exp(M*(alpha+alpha0)));
|
||||
double linear = (1.0-sigmoid) * (c_lift_0 + c_lift_a0*alpha); //Lift at small AoA
|
||||
double flatPlate = sigmoid*(2*copysign(1,alpha)*pow(sin(alpha),2)*cos(alpha)); //Lift beyond stall
|
||||
|
Loading…
Reference in New Issue
Block a user