AP_Param: make check_var_info void

Given all the callers die anyway, make it void
This commit is contained in:
Peter Barker 2023-01-06 16:12:24 +11:00 committed by Andrew Tridgell
parent e2535d1197
commit 7f9714d722
2 changed files with 17 additions and 29 deletions

View File

@ -49,8 +49,10 @@ AP_Param *AP_Param::_singleton;
#define ENABLE_DEBUG 0 #define ENABLE_DEBUG 0
#if ENABLE_DEBUG #if ENABLE_DEBUG
# define FATAL(fmt, args ...) AP_HAL::panic(fmt, args);
# define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) # define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
#else #else
# define FATAL(fmt, args ...) AP_HAL::panic("Bad parameter table");
# define Debug(fmt, args ...) # define Debug(fmt, args ...)
#endif #endif
@ -208,7 +210,7 @@ bool AP_Param::check_frame_type(uint16_t flags)
} }
// validate a group info table // validate a group info table
bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info, void AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
uint16_t * total_size, uint16_t * total_size,
uint8_t group_shift, uint8_t group_shift,
uint8_t prefix_length) uint8_t prefix_length)
@ -220,45 +222,37 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
i++) { i++) {
uint8_t idx = group_info[i].idx; uint8_t idx = group_info[i].idx;
if (idx >= (1<<_group_level_shift)) { if (idx >= (1<<_group_level_shift)) {
Debug("idx too large (%u) in %s", idx, group_info[i].name); FATAL("idx too large (%u) in %s", idx, group_info[i].name);
return false;
} }
if (group_shift != 0 && idx == 0) { if (group_shift != 0 && idx == 0) {
// treat idx 0 as 63 for duplicates. See group_id() // treat idx 0 as 63 for duplicates. See group_id()
idx = 63; idx = 63;
} }
if (used_mask & (1ULL<<idx)) { if (used_mask & (1ULL<<idx)) {
Debug("Duplicate group idx %u for %s", idx, group_info[i].name); FATAL("Duplicate group idx %u for %s", idx, group_info[i].name);
return false;
} }
used_mask |= (1ULL<<idx); used_mask |= (1ULL<<idx);
if (type == AP_PARAM_GROUP) { if (type == AP_PARAM_GROUP) {
// a nested group // a nested group
if (group_shift + _group_level_shift >= _group_bits) { if (group_shift + _group_level_shift >= _group_bits) {
Debug("double group nesting in %s", group_info[i].name); FATAL("double group nesting in %s", group_info[i].name);
return false;
} }
const struct GroupInfo *ginfo = get_group_info(group_info[i]); const struct GroupInfo *ginfo = get_group_info(group_info[i]);
if (ginfo == nullptr) { if (ginfo == nullptr) {
continue; continue;
} }
if (!check_group_info(ginfo, total_size, group_shift + _group_level_shift, prefix_length + strlen(group_info[i].name))) { check_group_info(ginfo, total_size, group_shift + _group_level_shift, prefix_length + strlen(group_info[i].name));
return false;
}
continue; continue;
} }
uint8_t size = type_size((enum ap_var_type)type); uint8_t size = type_size((enum ap_var_type)type);
if (size == 0) { if (size == 0) {
Debug("invalid type in %s", group_info[i].name); FATAL("invalid type in %s", group_info[i].name);
return false;
} }
if (prefix_length + strlen(group_info[i].name) > 16) { if (prefix_length + strlen(group_info[i].name) > 16) {
Debug("suffix is too long in %s", group_info[i].name); FATAL("suffix is too long in %s", group_info[i].name);
return false;
} }
(*total_size) += size + sizeof(struct Param_header); (*total_size) += size + sizeof(struct Param_header);
} }
return true;
} }
// check for duplicate key values // check for duplicate key values
@ -297,7 +291,7 @@ const struct AP_Param::GroupInfo *AP_Param::get_group_info(const struct Info &in
} }
// validate the _var_info[] table // validate the _var_info[] table
bool AP_Param::check_var_info(void) void AP_Param::check_var_info(void)
{ {
uint16_t total_size = sizeof(struct EEPROM_header); uint16_t total_size = sizeof(struct EEPROM_header);
@ -307,39 +301,33 @@ bool AP_Param::check_var_info(void)
uint16_t key = info.key; uint16_t key = info.key;
if (type == AP_PARAM_GROUP) { if (type == AP_PARAM_GROUP) {
if (i == 0) { if (i == 0) {
// first element can't be a group, for first() call FATAL("first element can't be a group, for first() call");
return false;
} }
const struct GroupInfo *group_info = get_group_info(info); const struct GroupInfo *group_info = get_group_info(info);
if (group_info == nullptr) { if (group_info == nullptr) {
continue; continue;
} }
if (!check_group_info(group_info, &total_size, 0, strlen(info.name))) { check_group_info(group_info, &total_size, 0, strlen(info.name));
return false;
}
} else { } else {
uint8_t size = type_size((enum ap_var_type)type); uint8_t size = type_size((enum ap_var_type)type);
if (size == 0) { if (size == 0) {
// not a valid type - the top level list can't contain // not a valid type - the top level list can't contain
// AP_PARAM_NONE // AP_PARAM_NONE
return false; FATAL("AP_PARAM_NONE at top level");
} }
total_size += size + sizeof(struct Param_header); total_size += size + sizeof(struct Param_header);
} }
if (duplicate_key(i, key)) { if (duplicate_key(i, key)) {
return false; FATAL("duplicate key");
} }
if (type != AP_PARAM_GROUP && (info.flags & AP_PARAM_FLAG_POINTER)) { if (type != AP_PARAM_GROUP && (info.flags & AP_PARAM_FLAG_POINTER)) {
// only groups can be pointers FATAL("only groups can be pointers");
return false;
} }
} }
// we no longer check if total_size is larger than _eeprom_size, // we no longer check if total_size is larger than _eeprom_size,
// as we allow for more variables than could fit, relying on not // as we allow for more variables than could fit, relying on not
// saving default values // saving default values
return true;
} }

View File

@ -493,7 +493,7 @@ public:
float cast_to_float(enum ap_var_type type) const; float cast_to_float(enum ap_var_type type) const;
// check var table for consistency // check var table for consistency
static bool check_var_info(void); static void check_var_info(void);
// return true if the parameter is configured // return true if the parameter is configured
bool configured(void) const; bool configured(void) const;
@ -617,7 +617,7 @@ private:
#endif #endif
static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size, static void check_group_info(const struct GroupInfo *group_info, uint16_t *total_size,
uint8_t max_bits, uint8_t prefix_length); uint8_t max_bits, uint8_t prefix_length);
static bool duplicate_key(uint16_t vindex, uint16_t key); static bool duplicate_key(uint16_t vindex, uint16_t key);