diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index 2e9a691650..b3d58306ba 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -791,8 +791,8 @@ bool AP_DDS_Client::init_session() } // setup reliable stream buffers - input_reliable_stream = new uint8_t[DDS_BUFFER_SIZE]; - output_reliable_stream = new uint8_t[DDS_BUFFER_SIZE]; + input_reliable_stream = NEW_NOTHROW uint8_t[DDS_BUFFER_SIZE]; + output_reliable_stream = NEW_NOTHROW uint8_t[DDS_BUFFER_SIZE]; if (input_reliable_stream == nullptr || output_reliable_stream == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Allocation failed", msg_prefix); return false; diff --git a/libraries/AP_DDS/AP_DDS_UDP.cpp b/libraries/AP_DDS/AP_DDS_UDP.cpp index 6593100618..6496e7ebb0 100644 --- a/libraries/AP_DDS/AP_DDS_UDP.cpp +++ b/libraries/AP_DDS/AP_DDS_UDP.cpp @@ -10,7 +10,7 @@ bool AP_DDS_Client::udp_transport_open(uxrCustomTransport *t) { AP_DDS_Client *dds = (AP_DDS_Client *)t->args; - auto *sock = new SocketAPM(true); + auto *sock = NEW_NOTHROW SocketAPM(true); if (sock == nullptr) { return false; }