AP_Param: shut up float comparison warning

We want to compare the value previously set in memory.
This commit is contained in:
Lucas De Marchi 2017-01-31 10:24:47 -08:00
parent 4e7b65260d
commit 85eadca7ad

View File

@ -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();
}