AP_TemperatureSensor: 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 fbeab64be2
commit 4ffffa7af7
2 changed files with 4 additions and 8 deletions

View File

@ -53,15 +53,11 @@ AP_TemperatureSensor_DroneCAN::AP_TemperatureSensor_DroneCAN(AP_TemperatureSenso
}
// Subscript to incoming temperature messages
void AP_TemperatureSensor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
bool AP_TemperatureSensor_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_temperature, ap_dronecan->get_driver_index()) == nullptr) {
AP_BoardConfig::allocation_error("temp_sub");
}
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, driver_index) != nullptr);
}
void AP_TemperatureSensor_DroneCAN::handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_device_Temperature &msg)

View File

@ -28,7 +28,7 @@ class AP_TemperatureSensor_DroneCAN : public AP_TemperatureSensor_Backend {
public:
AP_TemperatureSensor_DroneCAN(AP_TemperatureSensor &front, AP_TemperatureSensor::TemperatureSensor_State &state, AP_TemperatureSensor_Params &params);
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
static bool subscribe_msgs(AP_DroneCAN* ap_dronecan);
// Don't do anything in update, but still need to override the pure virtual method.
void update(void) override {};