mirror of https://github.com/ArduPilot/ardupilot
AP_UAVCAN: use config error instead of panic on allocation failure
This commit is contained in:
parent
224abe7933
commit
b897f984a7
|
@ -29,6 +29,7 @@
|
|||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include "AP_UAVCAN_Clock.h"
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
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<uavcan::protocol::dynamic_node_id::Allocation, AllocationCb> *AllocationListener;
|
||||
AllocationListener = new uavcan::Subscriber<uavcan::protocol::dynamic_node_id::Allocation, AllocationCb>(*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<uavcan::protocol::NodeStatus, NodeStatusCb> *NodeStatusListener;
|
||||
NodeStatusListener = new uavcan::Subscriber<uavcan::protocol::NodeStatus, NodeStatusCb>(*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) {
|
||||
|
|
Loading…
Reference in New Issue