mirror of https://github.com/ArduPilot/ardupilot
AP_DDS: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
50253834ef
commit
d5a90af9ba
|
@ -791,8 +791,8 @@ bool AP_DDS_Client::init_session()
|
||||||
}
|
}
|
||||||
|
|
||||||
// setup reliable stream buffers
|
// setup reliable stream buffers
|
||||||
input_reliable_stream = new uint8_t[DDS_BUFFER_SIZE];
|
input_reliable_stream = NEW_NOTHROW uint8_t[DDS_BUFFER_SIZE];
|
||||||
output_reliable_stream = new uint8_t[DDS_BUFFER_SIZE];
|
output_reliable_stream = NEW_NOTHROW uint8_t[DDS_BUFFER_SIZE];
|
||||||
if (input_reliable_stream == nullptr || output_reliable_stream == nullptr) {
|
if (input_reliable_stream == nullptr || output_reliable_stream == nullptr) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Allocation failed", msg_prefix);
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Allocation failed", msg_prefix);
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
bool AP_DDS_Client::udp_transport_open(uxrCustomTransport *t)
|
bool AP_DDS_Client::udp_transport_open(uxrCustomTransport *t)
|
||||||
{
|
{
|
||||||
AP_DDS_Client *dds = (AP_DDS_Client *)t->args;
|
AP_DDS_Client *dds = (AP_DDS_Client *)t->args;
|
||||||
auto *sock = new SocketAPM(true);
|
auto *sock = NEW_NOTHROW SocketAPM(true);
|
||||||
if (sock == nullptr) {
|
if (sock == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue