From 35a8f6c7b2c965d1e015d787f0fce215931ed7bb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 May 2024 12:35:57 +1000 Subject: [PATCH] AP_DroneCAN: use NEW_NOTHROW for new(std::nothrow) --- .../examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp index 949d52bfcf..a76877d0d2 100644 --- a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp @@ -120,7 +120,7 @@ void DroneCAN_sniffer::init(void) // we need to mutate the HAL to install new CAN interfaces AP_HAL::HAL& hal_mutable = AP_HAL::get_HAL_mutable(); - hal_mutable.can[driver_index] = new HAL_CANIface(driver_index); + hal_mutable.can[driver_index] = NEW_NOTHROW HAL_CANIface(driver_index); if (hal_mutable.can[driver_index] == nullptr) { AP_HAL::panic("Couldn't allocate CANManager, something is very wrong"); @@ -132,7 +132,7 @@ void DroneCAN_sniffer::init(void) debug_dronecan("Can not initialised\n"); return; } - _uavcan_iface_mgr = new CanardInterface{driver_index}; + _uavcan_iface_mgr = NEW_NOTHROW CanardInterface{driver_index}; if (_uavcan_iface_mgr == nullptr) { return; @@ -145,12 +145,12 @@ void DroneCAN_sniffer::init(void) _uavcan_iface_mgr->init(node_memory_pool, sizeof(node_memory_pool), 9); - node_status_pub = new Canard::Publisher{*_uavcan_iface_mgr}; + node_status_pub = NEW_NOTHROW Canard::Publisher{*_uavcan_iface_mgr}; if (node_status_pub == nullptr) { return; } - node_info_srv = new Canard::Server{*_uavcan_iface_mgr, *Canard::allocate_static_callback(cb_GetNodeInfoRequest)}; + node_info_srv = NEW_NOTHROW Canard::Server{*_uavcan_iface_mgr, *Canard::allocate_static_callback(cb_GetNodeInfoRequest)}; if (node_info_srv == nullptr) { return; }