From e656928c01a2f957857c529c9637f88fd9112311 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Feb 2012 15:13:00 +1100 Subject: [PATCH] AP_Param: added a set_and_save_ifchanged() method this can be used to avoid the scan() in more frequenctly saved variables, such as the MAVLink stream rates in APM --- libraries/AP_Common/AP_Param.h | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/libraries/AP_Common/AP_Param.h b/libraries/AP_Common/AP_Param.h index 0cee4be55c..c811a23b44 100644 --- a/libraries/AP_Common/AP_Param.h +++ b/libraries/AP_Common/AP_Param.h @@ -262,6 +262,19 @@ public: return save(); } + /// Combined set and save, but only does the save if the value if + /// 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. + bool set_and_save_ifchanged(T v) { + if (v == _value) { + return true; + } + set(v); + return save(); + } + /// 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.