mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Networking: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
242a3741e3
commit
4d5aa1b8e3
@ -148,26 +148,26 @@ void AP_Networking::init()
|
|||||||
/*
|
/*
|
||||||
when we are a PPP/Ethernet gateway we bring up the ethernet first
|
when we are a PPP/Ethernet gateway we bring up the ethernet first
|
||||||
*/
|
*/
|
||||||
backend = new AP_Networking_ChibiOS(*this);
|
backend = NEW_NOTHROW AP_Networking_ChibiOS(*this);
|
||||||
backend_PPP = new AP_Networking_PPP(*this);
|
backend_PPP = NEW_NOTHROW AP_Networking_PPP(*this);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#if AP_NETWORKING_BACKEND_PPP
|
#if AP_NETWORKING_BACKEND_PPP
|
||||||
if (backend == nullptr && AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_PPP, 0)) {
|
if (backend == nullptr && AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_PPP, 0)) {
|
||||||
backend = new AP_Networking_PPP(*this);
|
backend = NEW_NOTHROW AP_Networking_PPP(*this);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_NETWORKING_BACKEND_CHIBIOS
|
#if AP_NETWORKING_BACKEND_CHIBIOS
|
||||||
if (backend == nullptr) {
|
if (backend == nullptr) {
|
||||||
backend = new AP_Networking_ChibiOS(*this);
|
backend = NEW_NOTHROW AP_Networking_ChibiOS(*this);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if AP_NETWORKING_BACKEND_SITL
|
#if AP_NETWORKING_BACKEND_SITL
|
||||||
if (backend == nullptr) {
|
if (backend == nullptr) {
|
||||||
backend = new AP_Networking_SITL(*this);
|
backend = NEW_NOTHROW AP_Networking_SITL(*this);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -127,7 +127,7 @@ bool AP_Networking_ChibiOS::init()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
thisif = new netif;
|
thisif = NEW_NOTHROW netif;
|
||||||
if (thisif == nullptr) {
|
if (thisif == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -96,7 +96,7 @@ bool AP_Networking_PPP::init()
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
pppif = new netif;
|
pppif = NEW_NOTHROW netif;
|
||||||
if (pppif == nullptr) {
|
if (pppif == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -115,7 +115,7 @@ void AP_Networking::Port::thread_create(AP_HAL::MemberProc proc)
|
|||||||
*/
|
*/
|
||||||
void AP_Networking::Port::udp_client_init(void)
|
void AP_Networking::Port::udp_client_init(void)
|
||||||
{
|
{
|
||||||
sock = new SocketAPM(true);
|
sock = NEW_NOTHROW SocketAPM(true);
|
||||||
if (sock == nullptr) {
|
if (sock == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -133,7 +133,7 @@ void AP_Networking::Port::udp_client_init(void)
|
|||||||
*/
|
*/
|
||||||
void AP_Networking::Port::udp_server_init(void)
|
void AP_Networking::Port::udp_server_init(void)
|
||||||
{
|
{
|
||||||
sock = new SocketAPM(true);
|
sock = NEW_NOTHROW SocketAPM(true);
|
||||||
if (sock == nullptr) {
|
if (sock == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -151,7 +151,7 @@ void AP_Networking::Port::udp_server_init(void)
|
|||||||
*/
|
*/
|
||||||
void AP_Networking::Port::tcp_server_init(void)
|
void AP_Networking::Port::tcp_server_init(void)
|
||||||
{
|
{
|
||||||
listen_sock = new SocketAPM(false);
|
listen_sock = NEW_NOTHROW SocketAPM(false);
|
||||||
if (listen_sock == nullptr) {
|
if (listen_sock == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -165,7 +165,7 @@ void AP_Networking::Port::tcp_server_init(void)
|
|||||||
*/
|
*/
|
||||||
void AP_Networking::Port::tcp_client_init(void)
|
void AP_Networking::Port::tcp_client_init(void)
|
||||||
{
|
{
|
||||||
sock = new SocketAPM(false);
|
sock = NEW_NOTHROW SocketAPM(false);
|
||||||
if (sock != nullptr) {
|
if (sock != nullptr) {
|
||||||
sock->set_blocking(true);
|
sock->set_blocking(true);
|
||||||
thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::Port::tcp_client_loop, void));
|
thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::Port::tcp_client_loop, void));
|
||||||
@ -286,7 +286,7 @@ void AP_Networking::Port::tcp_client_loop(void)
|
|||||||
hal.scheduler->delay_microseconds(100);
|
hal.scheduler->delay_microseconds(100);
|
||||||
}
|
}
|
||||||
if (sock == nullptr) {
|
if (sock == nullptr) {
|
||||||
sock = new SocketAPM(false);
|
sock = NEW_NOTHROW SocketAPM(false);
|
||||||
if (sock == nullptr) {
|
if (sock == nullptr) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
@ -444,12 +444,12 @@ bool AP_Networking::Port::init_buffers(const uint32_t size_rx, const uint32_t si
|
|||||||
}
|
}
|
||||||
WITH_SEMAPHORE(sem);
|
WITH_SEMAPHORE(sem);
|
||||||
if (readbuffer == nullptr) {
|
if (readbuffer == nullptr) {
|
||||||
readbuffer = new ByteBuffer(size_rx);
|
readbuffer = NEW_NOTHROW ByteBuffer(size_rx);
|
||||||
} else {
|
} else {
|
||||||
readbuffer->set_size_best(size_rx);
|
readbuffer->set_size_best(size_rx);
|
||||||
}
|
}
|
||||||
if (writebuffer == nullptr) {
|
if (writebuffer == nullptr) {
|
||||||
writebuffer = new ByteBuffer(size_tx);
|
writebuffer = NEW_NOTHROW ByteBuffer(size_tx);
|
||||||
} else {
|
} else {
|
||||||
writebuffer->set_size_best(size_tx);
|
writebuffer->set_size_best(size_tx);
|
||||||
}
|
}
|
||||||
|
@ -43,7 +43,7 @@ void AP_Networking::test_UDP_client(void)
|
|||||||
startup_wait();
|
startup_wait();
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP_client: starting");
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP_client: starting");
|
||||||
const char *dest = param.test_ipaddr.get_str();
|
const char *dest = param.test_ipaddr.get_str();
|
||||||
auto *sock = new SocketAPM(true);
|
auto *sock = NEW_NOTHROW SocketAPM(true);
|
||||||
if (sock == nullptr) {
|
if (sock == nullptr) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UDP_client: failed to create socket");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UDP_client: failed to create socket");
|
||||||
return;
|
return;
|
||||||
@ -75,7 +75,7 @@ void AP_Networking::test_TCP_client(void)
|
|||||||
startup_wait();
|
startup_wait();
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_client: starting");
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_client: starting");
|
||||||
const char *dest = param.test_ipaddr.get_str();
|
const char *dest = param.test_ipaddr.get_str();
|
||||||
auto *sock = new SocketAPM(false);
|
auto *sock = NEW_NOTHROW SocketAPM(false);
|
||||||
if (sock == nullptr) {
|
if (sock == nullptr) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_client: failed to create socket");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_client: failed to create socket");
|
||||||
return;
|
return;
|
||||||
@ -107,7 +107,7 @@ void AP_Networking::test_TCP_discard(void)
|
|||||||
startup_wait();
|
startup_wait();
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_discard: starting");
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_discard: starting");
|
||||||
const char *dest = param.test_ipaddr.get_str();
|
const char *dest = param.test_ipaddr.get_str();
|
||||||
auto *sock = new SocketAPM(false);
|
auto *sock = NEW_NOTHROW SocketAPM(false);
|
||||||
if (sock == nullptr) {
|
if (sock == nullptr) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_discard: failed to create socket");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_discard: failed to create socket");
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user