AP_Param: add sub-group class param conversion method

This commit is contained in:
Josh Henderson 2021-10-08 04:15:10 -04:00 committed by Andrew Tridgell
parent e33954d561
commit 9cae5d1120
2 changed files with 40 additions and 0 deletions

View File

@ -1924,6 +1924,40 @@ void AP_Param::convert_parent_class(uint8_t param_key, void *object_pointer,
}
}
// 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,
const struct AP_Param::GroupInfo *group_info,
uint16_t old_index, uint16_t old_top_element, bool is_top_level)
{
const uint8_t group_shift = is_top_level ? 0 : 6;
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)<<group_shift) + old_index;
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;
}
AP_Param *ap2 = (AP_Param *)(group_info[i].offset + (uint8_t *)object_pointer);
memcpy(ap2, ap, sizeof(old_value));
// and save
ap2->save();
}
// we need to flush here to prevent a later set_default_by_name()
// causing a save to be done on a converted parameter
flush();
}
/*
convert width of a parameter, allowing update to wider scalar values
without changing the parameter indexes

View File

@ -444,6 +444,12 @@ public:
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,
const struct AP_Param::GroupInfo *group_info,
uint16_t old_index, uint16_t old_top_element, bool is_top_level);
/*
fetch a parameter value based on the index within a group. This
is used to find the old value of a parameter that has been