mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: 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:
parent
5874337df7
commit
cd1118acb4
|
@ -13,21 +13,15 @@ extern const AP_HAL::HAL& hal;
|
|||
AP_Airspeed_DroneCAN::DetectedModules AP_Airspeed_DroneCAN::_detected_modules[];
|
||||
HAL_Semaphore AP_Airspeed_DroneCAN::_sem_registry;
|
||||
|
||||
void AP_Airspeed_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
bool AP_Airspeed_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
{
|
||||
if (ap_dronecan == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_airspeed, ap_dronecan->get_driver_index()) == nullptr) {
|
||||
AP_BoardConfig::allocation_error("airspeed_sub");
|
||||
}
|
||||
const auto driver_index = ap_dronecan->get_driver_index();
|
||||
|
||||
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_airspeed, driver_index) != nullptr)
|
||||
#if AP_AIRSPEED_HYGROMETER_ENABLE
|
||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_hygrometer, ap_dronecan->get_driver_index()) == nullptr) {
|
||||
AP_BoardConfig::allocation_error("hygrometer_sub");
|
||||
}
|
||||
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_hygrometer, driver_index) != nullptr)
|
||||
#endif
|
||||
;
|
||||
}
|
||||
|
||||
AP_Airspeed_Backend* AP_Airspeed_DroneCAN::probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid)
|
||||
|
|
|
@ -26,7 +26,7 @@ public:
|
|||
bool get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) override;
|
||||
#endif
|
||||
|
||||
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
||||
static bool subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
||||
|
||||
static AP_Airspeed_Backend* probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid);
|
||||
|
||||
|
|
Loading…
Reference in New Issue