From c6e45dd536380f6cdfdbd20277f999e6aa2fbe0e Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 27 Aug 2020 00:40:51 +0530 Subject: [PATCH] AP_Param: add set_and_save_ifchanged for Vector3f params --- libraries/AP_Param/AP_Param.h | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 055a7dba3c..3d42ac1345 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -887,6 +887,23 @@ public: save(force); } + /// Combined set and save, but only does the save if the value is + /// different from the current ram value, thus saving us a + /// scan(). This should only be used where we have not set() the + /// value separately, as otherwise the value in EEPROM won't be + /// updated correctly. + void set_and_save_ifchanged(const T &v) { +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wfloat-equal" + if (_value == v) { +#pragma GCC diagnostic pop + return; + } + set(v); + save(true); + } + + /// Conversion to T returns a reference to the value. /// /// This allows the class to be used in many situations where the value would be legal.