mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Param: added convert_parent_class()
This commit is contained in:
parent
7aee3500e1
commit
d005cbffd8
@ -1657,6 +1657,35 @@ void AP_Param::convert_old_parameters(const struct ConversionInfo *conversion_ta
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
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));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
set a parameter to a float value
|
set a parameter to a float value
|
||||||
|
@ -121,7 +121,7 @@ public:
|
|||||||
};
|
};
|
||||||
struct ConversionInfo {
|
struct ConversionInfo {
|
||||||
uint16_t old_key; // k_param_*
|
uint16_t old_key; // k_param_*
|
||||||
uint8_t old_group_element; // index in old object
|
uint32_t old_group_element; // index in old object
|
||||||
enum ap_var_type type; // AP_PARAM_*
|
enum ap_var_type type; // AP_PARAM_*
|
||||||
const char *new_name;
|
const char *new_name;
|
||||||
};
|
};
|
||||||
@ -305,6 +305,10 @@ public:
|
|||||||
};
|
};
|
||||||
static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0);
|
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);
|
||||||
|
|
||||||
/// Erase all variables in EEPROM.
|
/// Erase all variables in EEPROM.
|
||||||
///
|
///
|
||||||
static void erase_all(void);
|
static void erase_all(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user