mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: Fix a mixture of new/free
This commit is contained in:
parent
0ede7b7d39
commit
effdc436f2
@ -1942,7 +1942,7 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass)
|
|||||||
}
|
}
|
||||||
num_param_overrides = 0;
|
num_param_overrides = 0;
|
||||||
|
|
||||||
param_overrides = new param_override[num_defaults];
|
param_overrides = (struct param_override *)malloc(sizeof(struct param_override)*num_defaults);
|
||||||
if (param_overrides == nullptr) {
|
if (param_overrides == nullptr) {
|
||||||
AP_HAL::panic("AP_Param: Failed to allocate overrides");
|
AP_HAL::panic("AP_Param: Failed to allocate overrides");
|
||||||
return false;
|
return false;
|
||||||
@ -2037,7 +2037,7 @@ void AP_Param::load_embedded_param_defaults(bool last_pass)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
param_overrides = new param_override[num_defaults];
|
param_overrides = (struct param_override *)malloc(sizeof(struct param_override)*num_defaults);
|
||||||
if (param_overrides == nullptr) {
|
if (param_overrides == nullptr) {
|
||||||
AP_HAL::panic("AP_Param: Failed to allocate overrides");
|
AP_HAL::panic("AP_Param: Failed to allocate overrides");
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user