mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: fixed parameter save bug
This bug affected parameters where the defaults are overridden in the object constructor. For example, a PID object may have a default value for PID_D of 0.0, but have a constructor based default of 0.2. If the user tries to set the value to exactly 0.0, then the set wouldn't happen, as the value matches the value in the object default var_info[] table. This change ensures we force a save to eeprom if the value is changing from the current value, regardless of the var_info[] default. Thanks to Tom Coyle for finding this bug!
This commit is contained in:
parent
109c1ca792
commit
26b7de668a
@ -650,7 +650,7 @@ AP_Param::find_object(const char *name)
|
|||||||
|
|
||||||
// Save the variable to EEPROM, if supported
|
// Save the variable to EEPROM, if supported
|
||||||
//
|
//
|
||||||
bool AP_Param::save(void)
|
bool AP_Param::save(bool force_save)
|
||||||
{
|
{
|
||||||
uint32_t group_element = 0;
|
uint32_t group_element = 0;
|
||||||
const struct GroupInfo *ginfo;
|
const struct GroupInfo *ginfo;
|
||||||
@ -703,7 +703,7 @@ bool AP_Param::save(void)
|
|||||||
} else {
|
} else {
|
||||||
v2 = PGM_FLOAT(&info->def_value);
|
v2 = PGM_FLOAT(&info->def_value);
|
||||||
}
|
}
|
||||||
if (v1 == v2) {
|
if (v1 == v2 && !force_save) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
if (phdr.type != AP_PARAM_INT32 &&
|
if (phdr.type != AP_PARAM_INT32 &&
|
||||||
|
@ -164,9 +164,11 @@ public:
|
|||||||
|
|
||||||
/// Save the current value of the variable to EEPROM.
|
/// 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.
|
/// @return True if the variable was saved successfully.
|
||||||
///
|
///
|
||||||
bool save(void);
|
bool save(bool force_save=false);
|
||||||
|
|
||||||
/// Load the variable from EEPROM.
|
/// Load the variable from EEPROM.
|
||||||
///
|
///
|
||||||
@ -369,8 +371,9 @@ public:
|
|||||||
/// Combined set and save
|
/// Combined set and save
|
||||||
///
|
///
|
||||||
bool set_and_save(const T &v) {
|
bool set_and_save(const T &v) {
|
||||||
|
bool force = (_value != v);
|
||||||
set(v);
|
set(v);
|
||||||
return save();
|
return save(force);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Combined set and save, but only does the save if the value if
|
/// Combined set and save, but only does the save if the value if
|
||||||
@ -383,7 +386,7 @@ public:
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
set(v);
|
set(v);
|
||||||
return save();
|
return save(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Conversion to T returns a reference to the value.
|
/// Conversion to T returns a reference to the value.
|
||||||
@ -464,8 +467,9 @@ public:
|
|||||||
/// Combined set and save
|
/// Combined set and save
|
||||||
///
|
///
|
||||||
bool set_and_save(const T &v) {
|
bool set_and_save(const T &v) {
|
||||||
|
bool force = (_value != v);
|
||||||
set(v);
|
set(v);
|
||||||
return save();
|
return save(force);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Conversion to T returns a reference to the value.
|
/// Conversion to T returns a reference to the value.
|
||||||
|
Loading…
Reference in New Issue
Block a user