From 58592506517692a0b414e2118851be3ec3ff5fdf Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 May 2024 11:24:15 +1000 Subject: [PATCH] Filter: use NEW_NOTHROW for new(std::nothrow) --- libraries/Filter/AP_Filter.cpp | 2 +- libraries/Filter/HarmonicNotchFilter.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/Filter/AP_Filter.cpp b/libraries/Filter/AP_Filter.cpp index 3e2763141a..072e0513c9 100644 --- a/libraries/Filter/AP_Filter.cpp +++ b/libraries/Filter/AP_Filter.cpp @@ -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; } diff --git a/libraries/Filter/HarmonicNotchFilter.cpp b/libraries/Filter/HarmonicNotchFilter.cpp index f332971591..835e53192a 100644 --- a/libraries/Filter/HarmonicNotchFilter.cpp +++ b/libraries/Filter/HarmonicNotchFilter.cpp @@ -205,7 +205,7 @@ void HarmonicNotchFilter::allocate_filters(uint8_t num_notches, uint32_t harm _harmonics = harmonics; if (_num_filters > 0) { - _filters = new NotchFilter[_num_filters]; + _filters = NEW_NOTHROW NotchFilter[_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))); _num_filters = 0; @@ -231,7 +231,7 @@ void HarmonicNotchFilter::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[total_notches]; + auto filters = NEW_NOTHROW NotchFilter[total_notches]; if (filters == nullptr) { _alloc_has_failed = true; return;