mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: check parameter tables for bad suffix lengths
This commit is contained in:
parent
44ee1fcd3c
commit
ec17c5806e
@ -33,12 +33,12 @@
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
// #define ENABLE_FASTSERIAL_DEBUG
|
||||
#define ENABLE_DEBUG 0
|
||||
|
||||
#ifdef ENABLE_FASTSERIAL_DEBUG
|
||||
# define serialDebug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); delay(0); } while(0)
|
||||
#if ENABLE_DEBUG
|
||||
# define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
|
||||
#else
|
||||
# define serialDebug(fmt, args ...)
|
||||
# define Debug(fmt, args ...)
|
||||
#endif
|
||||
|
||||
// some useful progmem macros
|
||||
@ -100,7 +100,7 @@ void AP_Param::erase_all(void)
|
||||
{
|
||||
struct EEPROM_header hdr;
|
||||
|
||||
serialDebug("erase_all");
|
||||
Debug("erase_all");
|
||||
|
||||
// write the header
|
||||
hdr.magic[0] = k_EEPROM_magic0;
|
||||
@ -116,7 +116,8 @@ void AP_Param::erase_all(void)
|
||||
// validate a group info table
|
||||
bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
|
||||
uint16_t * total_size,
|
||||
uint8_t group_shift)
|
||||
uint8_t group_shift,
|
||||
uint8_t prefix_length)
|
||||
{
|
||||
uint8_t type;
|
||||
int8_t max_idx = -1;
|
||||
@ -128,11 +129,11 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
|
||||
// a nested group
|
||||
const struct GroupInfo *ginfo = (const struct GroupInfo *)PGM_POINTER(&group_info[i].group_info);
|
||||
if (group_shift + _group_level_shift >= _group_bits) {
|
||||
// double nesting of groups is not allowed
|
||||
Debug("double group nesting in %S", group_info[i].name);
|
||||
return false;
|
||||
}
|
||||
if (ginfo == NULL ||
|
||||
!check_group_info(ginfo, total_size, group_shift + _group_level_shift)) {
|
||||
!check_group_info(ginfo, total_size, group_shift + _group_level_shift, prefix_length + strlen_P(group_info[i].name))) {
|
||||
return false;
|
||||
}
|
||||
continue;
|
||||
@ -140,17 +141,21 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
|
||||
#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
|
||||
Debug("idx too large (%u) in %S", idx, group_info[i].name);
|
||||
return false;
|
||||
}
|
||||
if ((int8_t)idx <= max_idx) {
|
||||
// the indexes must be in increasing order
|
||||
Debug("indexes must be in increasing order in %S", group_info[i].name);
|
||||
return false;
|
||||
}
|
||||
max_idx = (int8_t)idx;
|
||||
uint8_t size = type_size((enum ap_var_type)type);
|
||||
if (size == 0) {
|
||||
// not a valid type
|
||||
Debug("invalid type in %S", group_info[i].name);
|
||||
return false;
|
||||
}
|
||||
if (prefix_length + strlen_P(group_info[i].name) > 16) {
|
||||
Debug("suffix is too long in %S", group_info[i].name);
|
||||
return false;
|
||||
}
|
||||
(*total_size) += size + sizeof(struct Param_header);
|
||||
@ -186,7 +191,7 @@ bool AP_Param::check_var_info(void)
|
||||
}
|
||||
const struct GroupInfo *group_info = (const struct GroupInfo *)PGM_POINTER(&_var_info[i].group_info);
|
||||
if (group_info == NULL ||
|
||||
!check_group_info(group_info, &total_size, 0)) {
|
||||
!check_group_info(group_info, &total_size, 0, strlen_P(_var_info[i].name))) {
|
||||
return false;
|
||||
}
|
||||
} else {
|
||||
@ -216,7 +221,7 @@ bool AP_Param::setup(void)
|
||||
{
|
||||
struct EEPROM_header hdr;
|
||||
|
||||
serialDebug("setup %u vars", (unsigned)_num_vars);
|
||||
Debug("setup %u vars", (unsigned)_num_vars);
|
||||
|
||||
// check the header
|
||||
_storage.read_block(&hdr, 0, sizeof(hdr));
|
||||
@ -225,7 +230,7 @@ bool AP_Param::setup(void)
|
||||
hdr.revision != k_EEPROM_revision) {
|
||||
// header doesn't match. We can't recover any variables. Wipe
|
||||
// the header and setup the sentinal directly after the header
|
||||
serialDebug("bad header in setup - erasing");
|
||||
Debug("bad header in setup - erasing");
|
||||
erase_all();
|
||||
}
|
||||
|
||||
@ -447,7 +452,7 @@ uint8_t AP_Param::type_size(enum ap_var_type type)
|
||||
case AP_PARAM_MATRIX3F:
|
||||
return 3*3*4;
|
||||
}
|
||||
serialDebug("unknown type %u\n", type);
|
||||
Debug("unknown type %u\n", type);
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -481,7 +486,7 @@ bool AP_Param::scan(const AP_Param::Param_header *target, uint16_t *pofs)
|
||||
ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);
|
||||
}
|
||||
*pofs = 0xffff;
|
||||
serialDebug("scan past end of eeprom");
|
||||
Debug("scan past end of eeprom");
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -515,7 +520,7 @@ void AP_Param::copy_name_token(const ParamToken &token, char *buffer, size_t buf
|
||||
const struct AP_Param::Info *info = find_var_info_token(token, &group_element, &ginfo, &idx);
|
||||
if (info == NULL) {
|
||||
*buffer = 0;
|
||||
serialDebug("no info found");
|
||||
Debug("no info found");
|
||||
return;
|
||||
}
|
||||
strncpy_P(buffer, info->name, buffer_size);
|
||||
@ -883,7 +888,7 @@ bool AP_Param::load_all(void)
|
||||
}
|
||||
|
||||
// we didn't find the sentinal
|
||||
serialDebug("no sentinal in load_all");
|
||||
Debug("no sentinal in load_all");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -290,7 +290,8 @@ private:
|
||||
static const uint8_t _sentinal_type = 0x3F;
|
||||
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, uint8_t prefix_length);
|
||||
static bool duplicate_key(uint8_t vindex, uint8_t key);
|
||||
const struct Info * find_var_info_group(
|
||||
const struct GroupInfo * group_info,
|
||||
|
Loading…
Reference in New Issue
Block a user