AP_RPM: 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 2f1a8d1ef4
commit e82e6629d2
2 changed files with 4 additions and 8 deletions

View File

@ -34,15 +34,11 @@ AP_RPM_DroneCAN::AP_RPM_DroneCAN(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_
} }
// Subscribe to incoming rpm messages // Subscribe to incoming rpm messages
void AP_RPM_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) bool AP_RPM_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, &handle_rpm, ap_dronecan->get_driver_index()) == nullptr) { return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_rpm, driver_index) != nullptr);
AP_BoardConfig::allocation_error("rpm_sub");
}
} }
// Receive new CAN message // Receive new CAN message

View File

@ -27,7 +27,7 @@ public:
AP_RPM_DroneCAN(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state); AP_RPM_DroneCAN(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state);
// Subscribe to incoming rpm messages // Subscribe to incoming rpm messages
static void subscribe_msgs(AP_DroneCAN* ap_dronecan); static bool subscribe_msgs(AP_DroneCAN* ap_dronecan);
// update state // update state
void update(void) override; void update(void) override;