AP_Baro: 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 cd1118acb4
commit def199e61f
2 changed files with 6 additions and 11 deletions

View File

@ -21,18 +21,13 @@ AP_Baro_DroneCAN::AP_Baro_DroneCAN(AP_Baro &baro) :
AP_Baro_Backend(baro)
{}
void AP_Baro_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
bool AP_Baro_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
{
if (ap_dronecan == nullptr) {
return;
}
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_pressure, ap_dronecan->get_driver_index()) == nullptr) {
AP_BoardConfig::allocation_error("pressure_sub");
}
const auto driver_index = ap_dronecan->get_driver_index();
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, ap_dronecan->get_driver_index()) == nullptr) {
AP_BoardConfig::allocation_error("temperature_sub");
}
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_pressure, driver_index) != nullptr)
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, driver_index) != nullptr)
;
}
AP_Baro_Backend* AP_Baro_DroneCAN::probe(AP_Baro &baro)

View File

@ -15,7 +15,7 @@ public:
void update() override;
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
static bool subscribe_msgs(AP_DroneCAN* ap_dronecan);
static AP_Baro_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new);
static AP_Baro_Backend* probe(AP_Baro &baro);