From af6d8e3c365679c386123a4da784d7db1789ea6d Mon Sep 17 00:00:00 2001 From: Francisco Ferreira Date: Sat, 2 Apr 2016 20:24:38 +0100 Subject: [PATCH] AP_Param: explicitly cast to float to avoid Clang warning /home/travis/build/ArduPilot/ardupilot/libraries/AP_Param/AP_Param.h:542:22: warning: using floating point absolute value function 'fabsf' when argument is of integer type [-Wabsolute-value] bool force = fabsf(_value - v) < FLT_EPSILON; --- libraries/AP_Param/AP_Param.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 8c0cea352e..b7bda5543d 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -539,7 +539,7 @@ public: /// Combined set and save /// bool set_and_save(const T &v) { - bool force = fabsf(_value - v) < FLT_EPSILON; + bool force = fabsf((float)(_value - v)) < FLT_EPSILON; set(v); return save(force); }