From 42078f27949af3b6bca7150cc57991dfd660f24b Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Tue, 28 Feb 2012 15:54:40 -0800 Subject: [PATCH] AP_Param: Make nested group recursion disableable by macro * Eliminates recursive calls inside AP_Param. This is important to Pat @ Galois, but not the project in general. Recursion depth on these functions is bounded structurally using existing nested group constructors (can't create loops in finite space) and checked at init time --- libraries/AP_Common/AP_Param.cpp | 9 ++++++++- libraries/AP_Common/AP_Param.h | 3 +++ 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Common/AP_Param.cpp b/libraries/AP_Common/AP_Param.cpp index 363e9d784a..d94d5a7f60 100644 --- a/libraries/AP_Common/AP_Param.cpp +++ b/libraries/AP_Common/AP_Param.cpp @@ -118,6 +118,7 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo *group_info, for (uint8_t i=0; (type=PGM_UINT8(&group_info[i].type)) != AP_PARAM_NONE; i++) { +#ifdef AP_NESTED_GROUPS_ENABLED if (type == AP_PARAM_GROUP) { // a nested group const struct GroupInfo *ginfo = (const struct GroupInfo *)PGM_POINTER(&group_info[i].group_info); @@ -131,6 +132,7 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo *group_info, } continue; } +#endif // AP_NESTED_GROUPS_ENABLED uint8_t idx = PGM_UINT8(&group_info[i].idx); if (idx >= (1<<_group_level_shift)) { // passed limit on table size @@ -234,6 +236,7 @@ const struct AP_Param::Info *AP_Param::find_by_header_group(struct Param_header for (uint8_t i=0; (type=PGM_UINT8(&group_info[i].type)) != AP_PARAM_NONE; i++) { +#ifdef AP_NESTED_GROUPS_ENABLED if (type == AP_PARAM_GROUP) { // a nested group if (group_shift + _group_level_shift >= _group_bits) { @@ -250,6 +253,7 @@ const struct AP_Param::Info *AP_Param::find_by_header_group(struct Param_header } continue; } +#endif // AP_NESTED_GROUPS_ENABLED if (GROUP_ID(group_info, group_base, i, group_shift) == phdr.group_element) { // found a group element *ptr = (void*)(PGM_POINTER(&_var_info[vindex].ptr) + PGM_UINT16(&group_info[i].offset)); @@ -298,6 +302,7 @@ const struct AP_Param::Info *AP_Param::find_var_info_group(const struct GroupInf (type=PGM_UINT8(&group_info[i].type)) != AP_PARAM_NONE; i++) { uintptr_t ofs = PGM_POINTER(&group_info[i].offset); +#ifdef AP_NESTED_GROUPS_ENABLED if (type == AP_PARAM_GROUP) { const struct GroupInfo *ginfo = (const struct GroupInfo *)PGM_POINTER(&group_info[i].group_info); // a nested group @@ -316,7 +321,9 @@ const struct AP_Param::Info *AP_Param::find_var_info_group(const struct GroupInf if (info != NULL) { return info; } - } else if ((uintptr_t)this == base + ofs) { + } else // Forgive the poor formatting - if continues below. +#endif // AP_NESTED_GROUPS_ENABLED + if ((uintptr_t)this == base + ofs) { *group_element = GROUP_ID(group_info, group_base, i, group_shift); *group_ret = &group_info[i]; *idx = 0; diff --git a/libraries/AP_Common/AP_Param.h b/libraries/AP_Common/AP_Param.h index 3bc2bd4329..3fa0ca1196 100644 --- a/libraries/AP_Common/AP_Param.h +++ b/libraries/AP_Common/AP_Param.h @@ -20,6 +20,7 @@ #include #define AP_MAX_NAME_SIZE 15 +#define AP_NESTED_GROUPS_ENABLED // a varient of offsetof() to work around C++ restrictions. // this can only be used when the offset of a variable in a object @@ -33,7 +34,9 @@ #define AP_GROUPINFO(name, idx, class, element) { AP_CLASSTYPE(class, element), idx, name, AP_VAROFFSET(class, element) } // declare a nested group entry in a group var_info +#ifdef AP_NESTED_GROUPS_ENABLED #define AP_NESTEDGROUPINFO(class, idx) { AP_PARAM_GROUP, idx, "", 0, class::var_info } +#endif #define AP_GROUPEND { AP_PARAM_NONE, 0xFF, "" }