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