mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_DroneCAN: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
d5a90af9ba
commit
ed8926361f
@ -30,7 +30,7 @@ HAL_Semaphore test_iface_sem;
|
|||||||
|
|
||||||
void canard_allocate_sem_take(CanardPoolAllocator *allocator) {
|
void canard_allocate_sem_take(CanardPoolAllocator *allocator) {
|
||||||
if (allocator->semaphore == nullptr) {
|
if (allocator->semaphore == nullptr) {
|
||||||
allocator->semaphore = new HAL_Semaphore;
|
allocator->semaphore = NEW_NOTHROW HAL_Semaphore;
|
||||||
if (allocator->semaphore == nullptr) {
|
if (allocator->semaphore == nullptr) {
|
||||||
// out of memory
|
// out of memory
|
||||||
CANARD_ASSERT(0);
|
CANARD_ASSERT(0);
|
||||||
|
@ -343,7 +343,7 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters)
|
|||||||
uint8_t uid_len = sizeof(uavcan_protocol_HardwareVersion::unique_id);
|
uint8_t uid_len = sizeof(uavcan_protocol_HardwareVersion::unique_id);
|
||||||
uint8_t unique_id[sizeof(uavcan_protocol_HardwareVersion::unique_id)];
|
uint8_t unique_id[sizeof(uavcan_protocol_HardwareVersion::unique_id)];
|
||||||
|
|
||||||
mem_pool = new uint32_t[_pool_size/sizeof(uint32_t)];
|
mem_pool = NEW_NOTHROW uint32_t[_pool_size/sizeof(uint32_t)];
|
||||||
if (mem_pool == nullptr) {
|
if (mem_pool == nullptr) {
|
||||||
debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: Failed to allocate memory pool\n\r");
|
debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: Failed to allocate memory pool\n\r");
|
||||||
return;
|
return;
|
||||||
|
@ -52,7 +52,7 @@ void AP_DroneCAN_Serial::init(AP_DroneCAN *_dronecan)
|
|||||||
if (Canard::allocate_sub_arg_callback(dronecan, &handle_tunnel_targetted, dronecan->get_driver_index()) == nullptr) {
|
if (Canard::allocate_sub_arg_callback(dronecan, &handle_tunnel_targetted, dronecan->get_driver_index()) == nullptr) {
|
||||||
AP_BoardConfig::allocation_error("serial_tunnel_sub");
|
AP_BoardConfig::allocation_error("serial_tunnel_sub");
|
||||||
}
|
}
|
||||||
targetted = new Canard::Publisher<uavcan_tunnel_Targetted>(dronecan->get_canard_iface());
|
targetted = NEW_NOTHROW Canard::Publisher<uavcan_tunnel_Targetted>(dronecan->get_canard_iface());
|
||||||
if (targetted == nullptr) {
|
if (targetted == nullptr) {
|
||||||
AP_BoardConfig::allocation_error("serial_tunnel_pub");
|
AP_BoardConfig::allocation_error("serial_tunnel_pub");
|
||||||
}
|
}
|
||||||
@ -194,12 +194,12 @@ bool AP_DroneCAN_Serial::Port::init_buffers(const uint32_t size_rx, const uint32
|
|||||||
}
|
}
|
||||||
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);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user