AP_Param: fixed setting of CAM_P_G in ArduCopter

the variable CAM_P_G has the same prefix as the CAM_P group. We want
to allow for parameters having a common prefix with a group, so we
need to keep searching after we've found a group that matches the
prefix
This commit is contained in:
Andrew Tridgell 2012-02-27 10:51:57 +11:00
parent 7fe4a41c31
commit ac44b73951
1 changed files with 7 additions and 1 deletions

View File

@ -533,7 +533,13 @@ AP_Param::find(const char *name, enum ap_var_type *ptype)
continue;
}
const struct GroupInfo *group_info = (const struct GroupInfo *)PGM_POINTER(&_var_info[i].group_info);
return find_group(name + len, i, group_info, ptype);
AP_Param *ap = find_group(name + len, i, group_info, ptype);
if (ap != NULL) {
return ap;
}
// we continue looking as we want to allow top level
// parameter to have the same prefix name as group
// parameters, for example CAM_P_G
} else if (strcasecmp_P(name, _var_info[i].name) == 0) {
*ptype = (enum ap_var_type)type;
return (AP_Param *)PGM_POINTER(&_var_info[i].ptr);