mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: 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
e82e6629d2
commit
fbeab64be2
|
@ -13,14 +13,11 @@ extern const AP_HAL::HAL& hal;
|
||||||
#define debug_range_finder_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { hal.console->printf(fmt, ##args); }} while (0)
|
#define debug_range_finder_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { hal.console->printf(fmt, ##args); }} while (0)
|
||||||
|
|
||||||
//links the rangefinder uavcan message to this backend
|
//links the rangefinder uavcan message to this backend
|
||||||
void AP_RangeFinder_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
bool AP_RangeFinder_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||||
{
|
{
|
||||||
if (ap_dronecan == nullptr) {
|
const auto driver_index = ap_dronecan->get_driver_index();
|
||||||
return;
|
|
||||||
}
|
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, driver_index) != nullptr);
|
||||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, ap_dronecan->get_driver_index()) == nullptr) {
|
|
||||||
AP_BoardConfig::allocation_error("measurement_sub");
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
//Method to find the backend relating to the node id
|
//Method to find the backend relating to the node id
|
||||||
|
|
|
@ -16,7 +16,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 AP_RangeFinder_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new);
|
static AP_RangeFinder_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new);
|
||||||
static AP_RangeFinder_Backend* detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
|
static AP_RangeFinder_Backend* detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue