diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index e03619a0be..c59dc0c30a 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1938,17 +1938,19 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass) } free(mutable_filename); - if (param_overrides != nullptr) { - free(param_overrides); - } + delete[] param_overrides; num_param_overrides = 0; - param_overrides = (struct param_override *)malloc(sizeof(struct param_override)*num_defaults); + param_overrides = new param_override[num_defaults]; if (param_overrides == nullptr) { AP_HAL::panic("AP_Param: Failed to allocate overrides"); return false; } + if (num_defaults == 0) { + return true; + } + saveptr = nullptr; mutable_filename = strdup(filename); if (mutable_filename == nullptr) { @@ -2027,28 +2029,26 @@ bool AP_Param::count_embedded_param_defaults(uint16_t &count) */ void AP_Param::load_embedded_param_defaults(bool last_pass) { - if (param_overrides != nullptr) { - free(param_overrides); - param_overrides = nullptr; - } - + delete[] param_overrides; + param_overrides = nullptr; num_param_overrides = 0; + uint16_t num_defaults = 0; if (!count_embedded_param_defaults(num_defaults)) { return; } - param_overrides = (struct param_override *)malloc(sizeof(struct param_override)*num_defaults); + param_overrides = new param_override[num_defaults]; if (param_overrides == nullptr) { AP_HAL::panic("AP_Param: Failed to allocate overrides"); return; } - + const volatile char *ptr = param_defaults_data.data; uint16_t length = param_defaults_data.length; uint16_t idx = 0; - while (length) { + while (idx < num_defaults && length) { char line[100]; char *pname; float value;