mirror of https://github.com/ArduPilot/ardupilot
AP_Param: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
a5672b0105
commit
6bd2be548b
|
@ -2391,7 +2391,7 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass)
|
|||
num_param_overrides = 0;
|
||||
num_read_only = 0;
|
||||
|
||||
param_overrides = new param_override[num_defaults];
|
||||
param_overrides = NEW_NOTHROW param_override[num_defaults];
|
||||
if (param_overrides == nullptr) {
|
||||
AP_HAL::panic("AP_Param: Failed to allocate overrides");
|
||||
return false;
|
||||
|
@ -2486,7 +2486,7 @@ void AP_Param::load_param_defaults(const volatile char *ptr, int32_t length, boo
|
|||
return;
|
||||
}
|
||||
|
||||
param_overrides = new param_override[num_defaults];
|
||||
param_overrides = NEW_NOTHROW param_override[num_defaults];
|
||||
if (param_overrides == nullptr) {
|
||||
AP_HAL::panic("AP_Param: Failed to allocate overrides");
|
||||
return;
|
||||
|
@ -2882,7 +2882,7 @@ void AP_Param::add_default(AP_Param *ap, float v)
|
|||
}
|
||||
|
||||
// add to list
|
||||
defaults_list *new_item = new defaults_list;
|
||||
defaults_list *new_item = NEW_NOTHROW defaults_list;
|
||||
if (new_item == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue