mirror of https://github.com/ArduPilot/ardupilot
AP_Param: simplify g2 object conversion
This commit is contained in:
parent
b7dd432409
commit
f2e9e84278
|
@ -2072,6 +2072,20 @@ void AP_Param::convert_class(uint16_t param_key, void *object_pointer,
|
|||
flush();
|
||||
}
|
||||
|
||||
void AP_Param::convert_g2_objects(const void *g2, const G2ObjectConversion g2_conversions[], uint8_t num_conversions)
|
||||
{
|
||||
// Find G2's Top Level Key
|
||||
ConversionInfo info;
|
||||
if (!find_top_level_key_by_pointer(g2, info.old_key)) {
|
||||
return;
|
||||
}
|
||||
for (uint8_t i=0; i<num_conversions; i++) {
|
||||
const auto &c { g2_conversions[i] };
|
||||
convert_class(info.old_key, c.object_pointer, c.var_info, c.old_index, c.old_top_element, false);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
convert width of a parameter, allowing update to wider scalar values
|
||||
without changing the parameter indexes
|
||||
|
|
|
@ -472,6 +472,14 @@ public:
|
|||
// convert old vehicle parameters to new object parameters with scaling - assumes we use the same scaling factor for all values in the table
|
||||
static void convert_old_parameters_scaled(const ConversionInfo *conversion_table, uint8_t table_size, float scaler, uint8_t flags);
|
||||
|
||||
struct G2ObjectConversion {
|
||||
void *object_pointer;
|
||||
const struct AP_Param::GroupInfo *var_info;
|
||||
uint16_t old_index; // Old parameter index in g
|
||||
uint16_t old_top_element; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
|
||||
};
|
||||
static void convert_g2_objects(const void *g2, const G2ObjectConversion g2_conversions[], uint8_t num_conversions);
|
||||
|
||||
/*
|
||||
convert width of a parameter, allowing update to wider scalar
|
||||
values without changing the parameter indexes. This will return
|
||||
|
|
Loading…
Reference in New Issue