AP_Param: enable variables to be marked as enable variables

used to hide unused subtrees of variables
This commit is contained in:
Andrew Tridgell 2015-12-29 22:43:25 +11:00
parent 37b2e23322
commit 29cb0dcf2c
2 changed files with 48 additions and 1 deletions

View File

@ -1277,6 +1277,42 @@ AP_Param *AP_Param::next_scalar(ParamToken *token, enum ap_var_type *ptype)
AP_Param *ap;
enum ap_var_type type;
while ((ap = next(token, &type)) != NULL && type > AP_PARAM_FLOAT) ;
if (ap != NULL && type == AP_PARAM_INT8) {
/*
check if this is an enable variable. To do that we need to
find the info structures for the variable
*/
uint32_t group_element;
const struct GroupInfo *ginfo;
const struct GroupInfo *ginfo0;
uint8_t idx;
const struct AP_Param::Info *info = ap->find_var_info_token(*token, &group_element, ginfo, ginfo0, &idx);
if (info && ginfo &&
(ginfo->flags & AP_PARAM_FLAG_ENABLE) &&
((AP_Int8 *)ap)->get() == 0) {
/*
this is a disabled parameter tree, include this
parameter but not others below it. We need to keep
looking until we go past the parameters in this object
*/
ParamToken token2 = *token;
enum ap_var_type type2;
AP_Param *ap2;
while ((ap2 = next(&token2, &type2)) != NULL) {
if (token2.key != token->key) {
break;
}
if (ginfo0 != NULL && (token->group_element & 0x3F) != (token2.group_element & 0x3F)) {
break;
}
// update the returned token so the next() call goes from this point
*token = token2;
}
}
}
if (ap != NULL && ptype != NULL) {
*ptype = type;
}

View File

@ -35,9 +35,17 @@
/*
flags for variables in var_info and group tables
*/
// a nested offset is for subgroups that are not subclasses
#define AP_PARAM_FLAG_NESTED_OFFSET 1
// a pointer variable is for dynamically allocated objects
#define AP_PARAM_FLAG_POINTER 2
// an enable variable allows a whole subtree of variables to be made
// invisible
#define AP_PARAM_FLAG_ENABLE 4
// a variant of offsetof() to work around C++ restrictions.
// this can only be used when the offset of a variable in a object
// is constant and known at compile time
@ -47,7 +55,10 @@
#define AP_CLASSTYPE(class, element) ((uint8_t)(((const class *) 1)->element.vtype))
// declare a group var_info line
#define AP_GROUPINFO(name, idx, class, element, def) { AP_CLASSTYPE(class, element), idx, name, AP_VAROFFSET(class, element), {def_value : def} }
#define AP_GROUPINFO_FLAGS(name, idx, class, element, def, flags) { AP_CLASSTYPE(class, element), idx, name, AP_VAROFFSET(class, element), {def_value : def}, flags }
// declare a group var_info line
#define AP_GROUPINFO(name, idx, class, element, def) AP_GROUPINFO_FLAGS(name, idx, class, element, def, 0)
// declare a nested group entry in a group var_info
#define AP_NESTEDGROUPINFO(class, idx) { AP_PARAM_GROUP, idx, "", 0, { group_info : class::var_info }, 0 }