Browse Source

AP_Param: shut up float comparison warning

We want to compare the value previously set in memory.
master
Lucas De Marchi 8 years ago
parent
commit
85eadca7ad
  1. 7
      libraries/AP_Param/AP_Param.h

7
libraries/AP_Param/AP_Param.h

@ -542,11 +542,16 @@ public:
set(v); set(v);
} }
} }
/// Value setter - set value, tell GCS /// Value setter - set value, tell GCS
/// ///
void set_and_notify(const T &v) { 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) { if (v != _value) {
#pragma GCC diagnostic pop
set(v); set(v);
notify(); notify();
} }

Loading…
Cancel
Save