mirror of https://github.com/ArduPilot/ardupilot
Filter: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
db6bcdb725
commit
5859250651
|
@ -117,7 +117,7 @@ void AP_Filters::update()
|
|||
break;
|
||||
case AP_Filter::FilterType::FILTER_NOTCH:
|
||||
if (filters[i] == nullptr) {
|
||||
filters[i] = new AP_NotchFilter_params();
|
||||
filters[i] = NEW_NOTHROW AP_NotchFilter_params();
|
||||
backend_var_info[i] = AP_NotchFilter_params::var_info;
|
||||
update = true;
|
||||
}
|
||||
|
|
|
@ -205,7 +205,7 @@ void HarmonicNotchFilter<T>::allocate_filters(uint8_t num_notches, uint32_t harm
|
|||
_harmonics = harmonics;
|
||||
|
||||
if (_num_filters > 0) {
|
||||
_filters = new NotchFilter<T>[_num_filters];
|
||||
_filters = NEW_NOTHROW NotchFilter<T>[_num_filters];
|
||||
if (_filters == nullptr) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Failed to allocate %u bytes for notch filter", (unsigned int)(_num_filters * sizeof(NotchFilter<T>)));
|
||||
_num_filters = 0;
|
||||
|
@ -231,7 +231,7 @@ void HarmonicNotchFilter<T>::expand_filter_count(uint16_t total_notches)
|
|||
note that we rely on the semaphore in
|
||||
AP_InertialSensor_Backend.cpp to make this thread safe
|
||||
*/
|
||||
auto filters = new NotchFilter<T>[total_notches];
|
||||
auto filters = NEW_NOTHROW NotchFilter<T>[total_notches];
|
||||
if (filters == nullptr) {
|
||||
_alloc_has_failed = true;
|
||||
return;
|
||||
|
|
Loading…
Reference in New Issue