Browse Source

AP_Math: better way of handling safe_sqrt()

better to test the result, than predict it
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
8abbbe5713
  1. 7
      libraries/AP_Math/AP_Math.cpp

7
libraries/AP_Math/AP_Math.cpp

@ -24,10 +24,11 @@ float safe_asin(float v) @@ -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…
Cancel
Save