From ed3213600609d67206e4e0ed824454050dd2fb24 Mon Sep 17 00:00:00 2001 From: Josh Henderson Date: Tue, 19 Oct 2021 15:30:29 -0400 Subject: [PATCH] AP_Param: remove unused convert_parent_class() --- libraries/AP_Param/AP_Param.cpp | 29 ----------------------------- libraries/AP_Param/AP_Param.h | 4 ---- 2 files changed, 33 deletions(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 565bfabf17..f3caf9dc19 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1895,35 +1895,6 @@ void AP_Param::convert_old_parameters(const struct ConversionInfo *conversion_ta flush(); } -/* - move old class variables for a class that was sub-classed to one that isn't - For example, used when the AP_MotorsTri class changed from having its own parameter table - plus a subgroup for AP_MotorsMulticopter to just inheriting the AP_MotorsMulticopter var_info - - This does not handle nesting beyond the single level shift -*/ -void AP_Param::convert_parent_class(uint8_t param_key, void *object_pointer, - const struct AP_Param::GroupInfo *group_info) -{ - for (uint8_t i=0; group_info[i].type != AP_PARAM_NONE; i++) { - struct ConversionInfo info; - info.old_key = param_key; - info.type = (ap_var_type)group_info[i].type; - info.new_name = nullptr; - info.old_group_element = uint16_t(group_info[i].idx)<<6; - uint8_t old_value[type_size(info.type)]; - AP_Param *ap = (AP_Param *)&old_value[0]; - - if (!AP_Param::find_old_parameter(&info, ap)) { - // the parameter wasn't set in the old eeprom - continue; - } - - uint8_t *new_value = group_info[i].offset + (uint8_t *)object_pointer; - memcpy(new_value, old_value, sizeof(old_value)); - } -} - // move all parameters from a class to a new location // is_top_level: Is true if the class had its own top level key, param_key. It is false if the class was a subgroup void AP_Param::convert_class(uint16_t param_key, void *object_pointer, diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 1249e5f5f0..3153cfa35d 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -440,10 +440,6 @@ public: }; static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0); - // move old class variables for a class that was sub-classed to one that isn't - static void convert_parent_class(uint8_t param_key, void *object_pointer, - const struct AP_Param::GroupInfo *group_info); - // move all parameters from a class to a new location // is_top_level: Is true if the class had its own top level key, param_key. It is false if the class was a subgroup static void convert_class(uint16_t param_key, void *object_pointer,