From b897f984a7d399132e8c9b77f8f1050e87ba594b Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 29 Sep 2021 13:06:41 +0530 Subject: [PATCH] AP_UAVCAN: use config error instead of panic on allocation failure --- libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp index 254c136871..7594ab08a5 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp @@ -29,6 +29,7 @@ #include #include #include "AP_UAVCAN_Clock.h" +#include extern const AP_HAL::HAL& hal; #define NODEDATA_MAGIC 0xAC01 @@ -62,8 +63,7 @@ void AP_UAVCAN_DNA_Server::subscribe_msgs(AP_UAVCAN* ap_uavcan) uavcan::Subscriber *AllocationListener; AllocationListener = new uavcan::Subscriber(*node); if (AllocationListener == nullptr) { - AP_HAL::panic("Allocation Subscriber allocation failed\n\r"); - return; + AP_BoardConfig::allocation_error("AP_UAVCAN_DNA: AllocationListener"); } const int alloc_listener_res = AllocationListener->start(AllocationCb(ap_uavcan, &trampoline_handleAllocation)); if (alloc_listener_res < 0) { @@ -77,8 +77,7 @@ void AP_UAVCAN_DNA_Server::subscribe_msgs(AP_UAVCAN* ap_uavcan) uavcan::Subscriber *NodeStatusListener; NodeStatusListener = new uavcan::Subscriber(*node); if (NodeStatusListener == nullptr) { - AP_HAL::panic("NodeStatus Subscriber allocation failed\n\r"); - return; + AP_BoardConfig::allocation_error("AP_UAVCAN_DNA: NodeStatusListener"); } const int nodestatus_listener_res = NodeStatusListener->start(NodeStatusCb(ap_uavcan, &trampoline_handleNodeStatus)); if (nodestatus_listener_res < 0) {