mirror of https://github.com/ArduPilot/ardupilot
AP_Param: ensure we can't have duplicate keys in Parameters.h
this is O(n^2), but only at startup, and takes less than 1ms to run. It catches a very nasty coding error
This commit is contained in:
parent
fcb1b9ba95
commit
f1a389fe19
|
@ -153,6 +153,19 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo *group_info,
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check for duplicate key values
|
||||||
|
bool AP_Param::duplicate_key(uint8_t vindex, uint8_t key)
|
||||||
|
{
|
||||||
|
for (uint8_t i=vindex+1; i<_num_vars; i++) {
|
||||||
|
uint8_t key2 = PGM_UINT8(&_var_info[i].key);
|
||||||
|
if (key2 == key) {
|
||||||
|
// no duplicate keys allowed
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// validate the _var_info[] table
|
// validate the _var_info[] table
|
||||||
bool AP_Param::check_var_info(void)
|
bool AP_Param::check_var_info(void)
|
||||||
{
|
{
|
||||||
|
@ -160,6 +173,7 @@ bool AP_Param::check_var_info(void)
|
||||||
|
|
||||||
for (uint8_t i=0; i<_num_vars; i++) {
|
for (uint8_t i=0; i<_num_vars; i++) {
|
||||||
uint8_t type = PGM_UINT8(&_var_info[i].type);
|
uint8_t type = PGM_UINT8(&_var_info[i].type);
|
||||||
|
uint8_t key = PGM_UINT8(&_var_info[i].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
|
// first element can't be a group, for first() call
|
||||||
|
@ -179,6 +193,9 @@ bool AP_Param::check_var_info(void)
|
||||||
}
|
}
|
||||||
total_size += size + sizeof(struct Param_header);
|
total_size += size + sizeof(struct Param_header);
|
||||||
}
|
}
|
||||||
|
if (duplicate_key(i, key)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
if (total_size > _eeprom_size) {
|
if (total_size > _eeprom_size) {
|
||||||
serialDebug("total_size %u exceeds _eeprom_size %u",
|
serialDebug("total_size %u exceeds _eeprom_size %u",
|
||||||
|
|
|
@ -189,6 +189,7 @@ private:
|
||||||
static const uint8_t _sentinal_group = 0xFF;
|
static const uint8_t _sentinal_group = 0xFF;
|
||||||
|
|
||||||
static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size, uint8_t max_bits);
|
static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size, uint8_t max_bits);
|
||||||
|
static bool duplicate_key(uint8_t vindex, uint8_t key);
|
||||||
static bool check_var_info(void);
|
static bool check_var_info(void);
|
||||||
const struct Info *find_var_info_group(const struct GroupInfo *group_info,
|
const struct Info *find_var_info_group(const struct GroupInfo *group_info,
|
||||||
uint8_t vindex,
|
uint8_t vindex,
|
||||||
|
|
Loading…
Reference in New Issue