mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Param: allow group entries as duplicates
otherwise this breaks heli attitude control object
This commit is contained in:
parent
b6155d2cb6
commit
224b2e2dda
@ -126,11 +126,6 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
|
||||
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;
|
||||
@ -144,6 +139,11 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
|
||||
}
|
||||
continue;
|
||||
}
|
||||
if (used_mask & (1ULL<<idx)) {
|
||||
Debug("Duplicate group idx %u for %s", idx, group_info[i].name);
|
||||
return false;
|
||||
}
|
||||
used_mask |= (1ULL<<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