Browse Source

AP_Param: fixed forced save of constructor override parameters

this fixes the problem where setting ATC_RAT_YAW_FILT to 20 in copter
didn't stick across reboots
master
Andrew Tridgell 9 years ago
parent
commit
1581a5e354
  1. 5
      libraries/AP_Param/AP_Param.cpp

5
libraries/AP_Param/AP_Param.cpp

@ -978,8 +978,9 @@ bool AP_Param::save(bool force_save) @@ -978,8 +978,9 @@ bool AP_Param::save(bool force_save)
GCS_MAVLINK::send_parameter_value_all(name, (enum ap_var_type)info->type, v2);
return true;
}
if (phdr.type != AP_PARAM_INT32 &&
(fabsf(v1-v2) < 0.0001f*fabsf(v1))) {
if (!force_save &&
(phdr.type != AP_PARAM_INT32 &&
(fabsf(v1-v2) < 0.0001f*fabsf(v1)))) {
// for other than 32 bit integers, we accept values within
// 0.01 percent of the current value as being the same
GCS_MAVLINK::send_parameter_value_all(name, (enum ap_var_type)info->type, v2);

Loading…
Cancel
Save