From 46877851853e3b4b381f92f65e938a3a7f9ae7d0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 22 Jan 2017 21:42:54 +1100 Subject: [PATCH] AP_Param: fixed a bug in default file handling this fixes a bug in how default file values are handled that affects any common sub-objects. When we had a default value for something like SERVO12_FUNCTION then configured_in_defaults_file() would return true for SERVO1_FUNCTION as it shares a common default value pointer this changes the implementation to use the object pointer instead --- libraries/AP_Param/AP_Param.cpp | 70 ++++++++------------------------- libraries/AP_Param/AP_Param.h | 9 +---- 2 files changed, 19 insertions(+), 60 deletions(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 907f0bd33c..1d54163209 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -767,31 +767,6 @@ AP_Param::find(const char *name, enum ap_var_type *ptype) return nullptr; } -/* - find the def_value for a variable by name -*/ -const float * -AP_Param::find_def_value_ptr(const char *name) -{ - enum ap_var_type ptype; - AP_Param *vp = find(name, &ptype); - if (vp == nullptr) { - return nullptr; - } - uint32_t group_element; - const struct GroupInfo *ginfo; - struct GroupNesting group_nesting {}; - uint8_t gidx; - const struct AP_Param::Info *info = vp->find_var_info(&group_element, ginfo, group_nesting, &gidx); - if (info == nullptr) { - return nullptr; - } - if (ginfo != nullptr) { - return &ginfo->def_value; - } - return &info->def_value; -} - // Find a variable by index. Note that this is quite slow. // AP_Param * @@ -972,9 +947,9 @@ bool AP_Param::save(bool force_save) float v1 = cast_to_float((enum ap_var_type)phdr.type); float v2; if (ginfo != nullptr) { - v2 = get_default_value(&ginfo->def_value); + v2 = get_default_value(this, &ginfo->def_value); } else { - v2 = get_default_value(&info->def_value); + v2 = get_default_value(this, &info->def_value); } if (is_equal(v1,v2) && !force_save) { GCS_MAVLINK::send_parameter_value_all(name, (enum ap_var_type)info->type, v2); @@ -1046,10 +1021,10 @@ bool AP_Param::load(void) group_offset += group_nesting.group_ret[i]->offset; } set_value((enum ap_var_type)phdr.type, (void*)(base + ginfo->offset + group_offset), - get_default_value(&ginfo->def_value)); + get_default_value(this, &ginfo->def_value)); } else { set_value((enum ap_var_type)phdr.type, (void*)base, - get_default_value(&info->def_value)); + get_default_value(this, &info->def_value)); } return false; } @@ -1112,16 +1087,8 @@ bool AP_Param::configured_in_defaults_file(void) const return false; } - const float* def_value_ptr; - - if (ginfo != nullptr) { - def_value_ptr = &ginfo->def_value; - } else { - def_value_ptr = &info->def_value; - } - for (uint16_t i=0; iconfigured_in_storage()) { vp->set_float(value, var_type); } @@ -1846,10 +1810,10 @@ bool AP_Param::load_defaults_file(const char *filename, bool panic_on_error) /* find a default value given a pointer to a default value in flash */ -float AP_Param::get_default_value(const float *def_value_ptr) +float AP_Param::get_default_value(const AP_Param *vp, const float *def_value_ptr) { for (uint16_t i=0; i