From 453b83c159de2977086d3d523b0cef3e05248e6f Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sat, 16 Nov 2024 21:21:13 -0600 Subject: [PATCH] AP_Proximity: 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_Proximity/AP_Proximity_DroneCAN.cpp | 10 +++------- libraries/AP_Proximity/AP_Proximity_DroneCAN.h | 2 +- 2 files changed, 4 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp index caa2b03f07..430890fda1 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp @@ -32,15 +32,11 @@ ObjectBuffer_TS AP_Proximity_DroneCAN::item //links the Proximity DroneCAN message to this backend -void AP_Proximity_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_Proximity_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, &handle_measurement, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("measurement_sub"); - } + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, driver_index) != nullptr); } //Method to find the backend relating to the node id diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h index 4ccda3610d..db9f06094e 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h @@ -23,7 +23,7 @@ public: static AP_Proximity_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg);