AP_Param: check dynamic param tables are avalable before adding a param

This commit is contained in:
Iampete1 2023-11-22 19:51:22 +00:00 committed by Peter Barker
parent 7e76d647dc
commit a8fcf92183
1 changed files with 5 additions and 0 deletions

View File

@ -2998,6 +2998,11 @@ bool AP_Param::load_int32(uint16_t key, uint32_t group_element, int32_t &value)
*/ */
bool AP_Param::add_param(uint8_t _key, uint8_t param_num, const char *pname, float default_value) bool AP_Param::add_param(uint8_t _key, uint8_t param_num, const char *pname, float default_value)
{ {
if (_var_info_dynamic == nullptr) {
// No dynamic tables available
return false;
}
// check for valid values // check for valid values
if (param_num == 0 || param_num > 63 || strlen(pname) > 16) { if (param_num == 0 || param_num > 63 || strlen(pname) > 16) {
return false; return false;