AP_HAL: use NEW_NOTHROW for new(std::nothrow)

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:11 +10:00
parent 9caf942c7e
commit 20959524b8
3 changed files with 7 additions and 6 deletions

View File

@ -16,6 +16,7 @@
#include "Device.h" #include "Device.h"
#include <stdio.h> #include <stdio.h>
#include <AP_Common/AP_Common.h>
/* /*
using checked registers allows a device check that a set of critical using checked registers allows a device check that a set of critical
@ -44,7 +45,7 @@ bool AP_HAL::Device::setup_checked_registers(uint8_t nregs, uint8_t frequency)
_checked.n_set = 0; _checked.n_set = 0;
_checked.next = 0; _checked.next = 0;
} }
_checked.regs = new struct checkreg[nregs]; _checked.regs = NEW_NOTHROW struct checkreg[nregs];
if (_checked.regs == nullptr) { if (_checked.regs == nullptr) {
return false; return false;
} }

View File

@ -116,7 +116,7 @@ public:
// gives one less byte than requested. We round up to a full // gives one less byte than requested. We round up to a full
// multiple of the object size so that we always get aligned // multiple of the object size so that we always get aligned
// elements, which makes the readptr() method possible // elements, which makes the readptr() method possible
buffer = new ByteBuffer(((_size+1) * sizeof(T))); buffer = NEW_NOTHROW ByteBuffer(((_size+1) * sizeof(T)));
external_buf = false; external_buf = false;
} }
@ -288,7 +288,7 @@ public:
// gives one less byte than requested. We round up to a full // gives one less byte than requested. We round up to a full
// multiple of the object size so that we always get aligned // multiple of the object size so that we always get aligned
// elements, which makes the readptr() method possible // elements, which makes the readptr() method possible
buffer = new ByteBuffer(((_size+1) * sizeof(T))); buffer = NEW_NOTHROW ByteBuffer(((_size+1) * sizeof(T)));
} }
~ObjectBuffer_TS(void) { ~ObjectBuffer_TS(void) {
delete buffer; delete buffer;
@ -472,7 +472,7 @@ public:
ObjectArray(uint16_t size_) { ObjectArray(uint16_t size_) {
_size = size_; _size = size_;
_head = _count = 0; _head = _count = 0;
_buffer = new T[_size]; _buffer = NEW_NOTHROW T[_size];
} }
~ObjectArray(void) { ~ObjectArray(void) {
delete[] _buffer; delete[] _buffer;

View File

@ -467,7 +467,7 @@ SOCKET_CLASS_NAME *SOCKET_CLASS_NAME::accept(uint32_t timeout_ms)
if (newfd == -1) { if (newfd == -1) {
return nullptr; return nullptr;
} }
auto *ret = new SOCKET_CLASS_NAME(false, newfd); auto *ret = NEW_NOTHROW SOCKET_CLASS_NAME(false, newfd);
if (ret != nullptr) { if (ret != nullptr) {
ret->connected = true; ret->connected = true;
ret->reuseaddress(); ret->reuseaddress();
@ -504,7 +504,7 @@ void SOCKET_CLASS_NAME::close(void)
*/ */
SOCKET_CLASS_NAME *SOCKET_CLASS_NAME::duplicate(void) SOCKET_CLASS_NAME *SOCKET_CLASS_NAME::duplicate(void)
{ {
auto *ret = new SOCKET_CLASS_NAME(datagram, fd); auto *ret = NEW_NOTHROW SOCKET_CLASS_NAME(datagram, fd);
if (ret == nullptr) { if (ret == nullptr) {
return nullptr; return nullptr;
} }