From 82d210144b009b392889591493a6c5233025ae2e Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Tue, 24 Jan 2017 10:00:38 -0800 Subject: [PATCH] AP_Math: remove warnings from constrain_value() Return type is T which can be an integral type, float or double. By dividing by 2 we avoid float operation on the first case and do the right thing on the second and third. --- libraries/AP_Math/AP_Math.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index 0888414924..4476aec439 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -176,10 +176,10 @@ template T constrain_value(const T amt, const T low, const T high) { // the check for NaN as a float prevents propagation of floating point - // errors through any function that uses constrain_float(). The normal + // errors through any function that uses constrain_value(). The normal // float semantics already handle -Inf and +Inf if (isnan(amt)) { - return (low + high) * 0.5f; + return (low + high) / 2; } if (amt < low) {