From 1581a5e354701eba8aa2ee0dcac810033119a678 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 24 May 2016 16:55:45 +1000 Subject: [PATCH] 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 --- libraries/AP_Param/AP_Param.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 0a464cac39..766be68d3e 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -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);