mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Math: better way of handling safe_sqrt()
better to test the result, than predict it
This commit is contained in:
parent
ccada2e9c2
commit
8abbbe5713
@ -24,10 +24,11 @@ float safe_asin(float v)
|
||||
// real input should have been zero
|
||||
float safe_sqrt(float v)
|
||||
{
|
||||
if (isnan(v) || v <= 0.0) {
|
||||
return 0.0;
|
||||
float ret = sqrt(v);
|
||||
if (isnan(ret)) {
|
||||
return 0;
|
||||
}
|
||||
return sqrt(v);
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user