From 83283681648a83df39a460320fde597ae61b9f5a Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sat, 16 Nov 2024 21:21:13 -0600 Subject: [PATCH] AP_EFI: optimize DroneCAN subscription process * remove unnecessary nullptr check, these are always called from an initialized AP_DroneCAN so if it's nullptr something has gone horrifically wrong * pass in driver index instead of repeatedly calling function to get it * simplify error handling; knowing exactly which allocation failed is not super helpful and one failing likely means subsequent ones will too, as it can only fail due to being out of memory --- libraries/AP_EFI/AP_EFI_DroneCAN.cpp | 10 +++------- libraries/AP_EFI/AP_EFI_DroneCAN.h | 2 +- 2 files changed, 4 insertions(+), 8 deletions(-) diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp index 90f33cac5d..736196f63b 100644 --- a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp @@ -21,15 +21,11 @@ AP_EFI_DroneCAN::AP_EFI_DroneCAN(AP_EFI &_frontend) : } // links the DroneCAN message to this backend -void AP_EFI_DroneCAN::subscribe_msgs(AP_DroneCAN *ap_dronecan) +bool AP_EFI_DroneCAN::subscribe_msgs(AP_DroneCAN *ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } + const auto driver_index = ap_dronecan->get_driver_index(); - if (Canard::allocate_sub_arg_callback(ap_dronecan, &trampoline_status, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("status_sub"); - } + return (Canard::allocate_sub_arg_callback(ap_dronecan, &trampoline_status, driver_index) != nullptr); } // Called from frontend to update with the readings received by handler diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.h b/libraries/AP_EFI/AP_EFI_DroneCAN.h index 0512d8ea1f..2d067554ac 100644 --- a/libraries/AP_EFI/AP_EFI_DroneCAN.h +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.h @@ -13,7 +13,7 @@ public: void update() override; - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); static void trampoline_status(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ice_reciprocating_Status &msg); private: