diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 82c026cc0b..6e8588a739 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1832,6 +1832,65 @@ void AP_Param::convert_parent_class(uint8_t param_key, void *object_pointer, } } +/* + convert width of a parameter, allowing update to wider scalar values + without changing the parameter indexes +*/ +bool AP_Param::convert_parameter_width(ap_var_type old_ptype) +{ + if (configured_in_storage()) { + // already converted or set by the user + return false; + } + + uint32_t group_element = 0; + const struct GroupInfo *ginfo; + struct GroupNesting group_nesting {}; + uint8_t idx; + const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx); + + if (info == nullptr) { + return false; + } + + // remember the type + ap_var_type new_ptype; + if (ginfo != nullptr) { + new_ptype = (ap_var_type)ginfo->type; + } else { + new_ptype = (ap_var_type)info->type; + } + + // create the header we will use to scan for the variable + struct Param_header phdr; + phdr.type = old_ptype; + set_key(phdr, info->key); + phdr.group_element = group_element; + + // scan EEPROM to find the right location + uint16_t pofs; + if (!scan(&phdr, &pofs)) { + // it isn't in storage + return false; + } + + // load the old value from EEPROM + uint8_t old_value[type_size(old_ptype)]; + _storage.read_block(old_value, pofs+sizeof(phdr), sizeof(old_value)); + + AP_Param *old_ap = (AP_Param *)&old_value[0]; + + // going via float is safe as the only time we would be converting + // from AP_Int32 is when converting to float + float old_float_value = old_ap->cast_to_float(old_ptype); + set_value(new_ptype, this, old_float_value); + + // force save as the new type + save(true); + + return true; +} + /* set a parameter to a float value diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 28e38d3893..2749f99175 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -389,6 +389,13 @@ public: // convert old vehicle parameters to new object parameters static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0); + /* + convert width of a parameter, allowing update to wider scalar + values without changing the parameter indexes. This will return + true if the parameter was converted from an old parameter value + */ + bool convert_parameter_width(ap_var_type old_ptype); + // convert a single parameter with scaling enum { CONVERT_FLAG_REVERSE=1, // handle _REV -> _REVERSED conversion