From 8abbbe57139bfa335cdeefb86aecdb5a71c5bd90 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 5 Mar 2012 22:40:37 +1100 Subject: [PATCH] AP_Math: better way of handling safe_sqrt() better to test the result, than predict it --- libraries/AP_Math/AP_Math.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index f4896ef38b..e0af504ea3 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -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; }