mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: shut up float comparison warning
We want to compare the value previously set in memory.
This commit is contained in:
parent
4e7b65260d
commit
85eadca7ad
@ -546,7 +546,12 @@ public:
|
||||
/// Value setter - set value, tell GCS
|
||||
///
|
||||
void set_and_notify(const T &v) {
|
||||
// We do want to compare each value, even floats, since it being the same here
|
||||
// is the result of previously setting it.
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wfloat-equal"
|
||||
if (v != _value) {
|
||||
#pragma GCC diagnostic pop
|
||||
set(v);
|
||||
notify();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user