AP_Param: expose the stable key for use by AP_OSD

add support for finding parameters by name and returning the token
This commit is contained in:
Andy Piper 2020-05-10 15:04:03 +01:00 committed by Peter Barker
parent 88d8cdadb7
commit 7aa98d55eb
2 changed files with 26 additions and 0 deletions

View File

@ -909,6 +909,26 @@ AP_Param::find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token
return ap;
}
// by-name equivalent of find_by_index()
AP_Param* AP_Param::find_by_name(const char* name, enum ap_var_type *ptype, ParamToken *token)
{
AP_Param *ap;
uint16_t count = 0;
for (ap = AP_Param::first(token, ptype);
ap && *ptype != AP_PARAM_GROUP && *ptype != AP_PARAM_NONE;
ap = AP_Param::next_scalar(token, ptype)) {
int32_t ret = strncasecmp(name, _var_info[token->key].name, AP_MAX_NAME_SIZE);
if (ret >= 0) {
char buf[AP_MAX_NAME_SIZE];
ap->copy_name_token(*token, buf, AP_MAX_NAME_SIZE);
if (strncasecmp(name, buf, AP_MAX_NAME_SIZE) == 0) {
break;
}
}
count++;
}
return ap;
}
/*
Find a variable by pointer, returning key. This is used for loading pointer variables

View File

@ -314,6 +314,9 @@ public:
///
static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token);
// by-name equivalent of find_by_index()
static AP_Param* find_by_name(const char* name, enum ap_var_type *ptype, ParamToken *token);
/// Find a variable by pointer
///
///
@ -474,6 +477,9 @@ public:
// return true if the parameter is read-only
bool is_read_only(void) const;
// return the persistent top level key for the ParamToken key
static uint16_t get_persistent_key(uint16_t key) { return _var_info[key].key; }
// count of parameters in tree
static uint16_t count_parameters(void);