mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Param: avoid allocating 0 bytes if no defaults
This stopped CUAVv5 from booting. Also add some protection against having different parsers for the same file format used for counting parameters and actually using them.
This commit is contained in:
parent
7b7bdd9bf8
commit
0d1b7b90b9
@ -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,18 +2029,16 @@ 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);
|
||||
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;
|
||||
@ -2048,7 +2048,7 @@ void AP_Param::load_embedded_param_defaults(bool last_pass)
|
||||
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;
|
||||
|
Loading…
Reference in New Issue
Block a user