mirror of https://github.com/ArduPilot/ardupilot
AP_Param: remove unused old_top_element param from convert_class
This commit is contained in:
parent
9af383f634
commit
dd628b025f
|
@ -2031,7 +2031,7 @@ void AP_Param::convert_old_parameters_scaled(const struct ConversionInfo *conver
|
||||||
// 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
|
// 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,
|
void AP_Param::convert_class(uint16_t param_key, void *object_pointer,
|
||||||
const struct AP_Param::GroupInfo *group_info,
|
const struct AP_Param::GroupInfo *group_info,
|
||||||
uint16_t old_index, uint16_t old_top_element, bool is_top_level)
|
uint16_t old_index, bool is_top_level)
|
||||||
{
|
{
|
||||||
const uint8_t group_shift = is_top_level ? 0 : 6;
|
const uint8_t group_shift = is_top_level ? 0 : 6;
|
||||||
|
|
||||||
|
@ -2081,7 +2081,7 @@ void AP_Param::convert_g2_objects(const void *g2, const G2ObjectConversion g2_co
|
||||||
}
|
}
|
||||||
for (uint8_t i=0; i<num_conversions; i++) {
|
for (uint8_t i=0; i<num_conversions; i++) {
|
||||||
const auto &c { g2_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_class(info.old_key, c.object_pointer, c.var_info, c.old_index, false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -476,7 +476,6 @@ public:
|
||||||
void *object_pointer;
|
void *object_pointer;
|
||||||
const struct AP_Param::GroupInfo *var_info;
|
const struct AP_Param::GroupInfo *var_info;
|
||||||
uint16_t old_index; // Old parameter index in g
|
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);
|
static void convert_g2_objects(const void *g2, const G2ObjectConversion g2_conversions[], uint8_t num_conversions);
|
||||||
|
|
||||||
|
@ -501,7 +500,7 @@ public:
|
||||||
// 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
|
// 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,
|
static void convert_class(uint16_t param_key, void *object_pointer,
|
||||||
const struct AP_Param::GroupInfo *group_info,
|
const struct AP_Param::GroupInfo *group_info,
|
||||||
uint16_t old_index, uint16_t old_top_element, bool is_top_level);
|
uint16_t old_index, bool is_top_level);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
fetch a parameter value based on the index within a group. This
|
fetch a parameter value based on the index within a group. This
|
||||||
|
|
Loading…
Reference in New Issue