Browse Source

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;
master
Francisco Ferreira 9 years ago
parent
commit
af6d8e3c36
  1. 2
      libraries/AP_Param/AP_Param.h

2
libraries/AP_Param/AP_Param.h

@ -539,7 +539,7 @@ public: @@ -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);
}

Loading…
Cancel
Save