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
This commit is contained in:
Thomas Watson 2024-11-16 21:21:13 -06:00 committed by Andrew Tridgell
parent d86bab9c58
commit 8328368164
2 changed files with 4 additions and 8 deletions

View File

@ -21,15 +21,11 @@ AP_EFI_DroneCAN::AP_EFI_DroneCAN(AP_EFI &_frontend) :
} }
// links the DroneCAN message to this backend // 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) { const auto driver_index = ap_dronecan->get_driver_index();
return;
}
if (Canard::allocate_sub_arg_callback(ap_dronecan, &trampoline_status, ap_dronecan->get_driver_index()) == nullptr) { return (Canard::allocate_sub_arg_callback(ap_dronecan, &trampoline_status, driver_index) != nullptr);
AP_BoardConfig::allocation_error("status_sub");
}
} }
// Called from frontend to update with the readings received by handler // Called from frontend to update with the readings received by handler

View File

@ -13,7 +13,7 @@ public:
void update() override; 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); static void trampoline_status(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ice_reciprocating_Status &msg);
private: private: