diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 0b1b0a8090..741c60ee68 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -650,7 +650,7 @@ AP_Param::find_object(const char *name) // Save the variable to EEPROM, if supported // -bool AP_Param::save(void) +bool AP_Param::save(bool force_save) { uint32_t group_element = 0; const struct GroupInfo *ginfo; @@ -703,7 +703,7 @@ bool AP_Param::save(void) } else { v2 = PGM_FLOAT(&info->def_value); } - if (v1 == v2) { + if (v1 == v2 && !force_save) { return true; } if (phdr.type != AP_PARAM_INT32 && diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index b51ef83b86..29362eee54 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -164,9 +164,11 @@ public: /// Save the current value of the variable to EEPROM. /// + /// @param force_save If true then force save even if default + /// /// @return True if the variable was saved successfully. /// - bool save(void); + bool save(bool force_save=false); /// Load the variable from EEPROM. /// @@ -369,8 +371,9 @@ public: /// Combined set and save /// bool set_and_save(const T &v) { + bool force = (_value != v); set(v); - return save(); + return save(force); } /// Combined set and save, but only does the save if the value if @@ -383,7 +386,7 @@ public: return true; } set(v); - return save(); + return save(true); } /// Conversion to T returns a reference to the value. @@ -464,8 +467,9 @@ public: /// Combined set and save /// bool set_and_save(const T &v) { + bool force = (_value != v); set(v); - return save(); + return save(force); } /// Conversion to T returns a reference to the value.