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
This commit is contained in:
Andrew Tridgell 2012-02-17 15:13:00 +11:00
parent 6f080742b8
commit e656928c01
1 changed files with 13 additions and 0 deletions

View File

@ -262,6 +262,19 @@ public:
return save(); 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. /// 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. /// This allows the class to be used in many situations where the value would be legal.