mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Param: allow group entries in any order
this will make the ENABLE flag more useful
This commit is contained in:
parent
57f580fdfc
commit
ac64effc74
@ -117,10 +117,20 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
|
||||
uint8_t prefix_length)
|
||||
{
|
||||
uint8_t type;
|
||||
int8_t max_idx = -1;
|
||||
uint64_t used_mask = 0;
|
||||
for (uint8_t i=0;
|
||||
(type=group_info[i].type) != AP_PARAM_NONE;
|
||||
i++) {
|
||||
uint8_t idx = group_info[i].idx;
|
||||
if (idx >= (1<<_group_level_shift)) {
|
||||
Debug("idx too large (%u) in %s", idx, group_info[i].name);
|
||||
return false;
|
||||
}
|
||||
if (used_mask & (1ULL<<idx)) {
|
||||
Debug("Duplicate group idx %u for %s", idx, group_info[i].name);
|
||||
return false;
|
||||
}
|
||||
used_mask |= (1ULL<<idx);
|
||||
if (type == AP_PARAM_GROUP) {
|
||||
// a nested group
|
||||
const struct GroupInfo *ginfo = group_info[i].group_info;
|
||||
@ -134,16 +144,6 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
|
||||
}
|
||||
continue;
|
||||
}
|
||||
uint8_t idx = group_info[i].idx;
|
||||
if (idx >= (1<<_group_level_shift)) {
|
||||
Debug("idx too large (%u) in %s", idx, group_info[i].name);
|
||||
return false;
|
||||
}
|
||||
if ((int8_t)idx <= max_idx) {
|
||||
Debug("indexes must be in increasing order in %s", group_info[i].name);
|
||||
return false;
|
||||
}
|
||||
max_idx = (int8_t)idx;
|
||||
uint8_t size = type_size((enum ap_var_type)type);
|
||||
if (size == 0) {
|
||||
Debug("invalid type in %s", group_info[i].name);
|
||||
|
Loading…
Reference in New Issue
Block a user