mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Param: correct fetching of flags for parameters
This was sending through the flags for the group the parameter was in, rather than the parameter itself.
This commit is contained in:
parent
108f37c67c
commit
ca5ee2bfbc
@ -853,7 +853,14 @@ AP_Param::find(const char *name, enum ap_var_type *ptype, uint16_t *flags)
|
|||||||
AP_Param *ap = find_group(name + len, i, 0, group_info, ptype);
|
AP_Param *ap = find_group(name + len, i, 0, group_info, ptype);
|
||||||
if (ap != nullptr) {
|
if (ap != nullptr) {
|
||||||
if (flags != nullptr) {
|
if (flags != nullptr) {
|
||||||
*flags = group_info->flags;
|
uint32_t group_element = 0;
|
||||||
|
const struct GroupInfo *ginfo;
|
||||||
|
struct GroupNesting group_nesting {};
|
||||||
|
uint8_t idx;
|
||||||
|
ap->find_var_info(&group_element, ginfo, group_nesting, &idx);
|
||||||
|
if (ginfo != nullptr) {
|
||||||
|
*flags = ginfo->flags;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
return ap;
|
return ap;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user