Browse Source

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.
master
Lucas De Marchi 8 years ago
parent
commit
82d210144b
  1. 4
      libraries/AP_Math/AP_Math.cpp

4
libraries/AP_Math/AP_Math.cpp

@ -176,10 +176,10 @@ template <class T> @@ -176,10 +176,10 @@ template <class T>
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) {

Loading…
Cancel
Save