Skip to content
Snippets Groups Projects
Commit e656928c authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

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
parent 6f080742
No related branches found
No related tags found
No related merge requests found
......@@ -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.
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment