From 18e5da78d22cbb49421e36bdda20c120978bbe63 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 May 2024 11:24:08 +1000 Subject: [PATCH] AC_CustomControl: use NEW_NOTHROW for new(std::nothrow) --- libraries/AC_CustomControl/AC_CustomControl.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_CustomControl/AC_CustomControl.cpp b/libraries/AC_CustomControl/AC_CustomControl.cpp index 903d854c12..407b9db249 100644 --- a/libraries/AC_CustomControl/AC_CustomControl.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl.cpp @@ -55,11 +55,11 @@ void AC_CustomControl::init(void) break; case CustomControlType::CONT_EMPTY: // This is template backend. Don't initialize it. // This is template backend. Don't initialize it. - // _backend = new AC_CustomControl_Empty(*this, _ahrs, _att_control, _motors, _dt); + // _backend = NEW_NOTHROW AC_CustomControl_Empty(*this, _ahrs, _att_control, _motors, _dt); // _backend_var_info[get_type()] = AC_CustomControl_Empty::var_info; break; case CustomControlType::CONT_PID: - _backend = new AC_CustomControl_PID(*this, _ahrs, _att_control, _motors, _dt); + _backend = NEW_NOTHROW AC_CustomControl_PID(*this, _ahrs, _att_control, _motors, _dt); _backend_var_info[get_type()] = AC_CustomControl_PID::var_info; break; default: