mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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;
This commit is contained in:
parent
71692044f8
commit
af6d8e3c36
@ -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…
Reference in New Issue
Block a user