mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: 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
453b83c159
commit
2f1a8d1ef4
|
@ -14,15 +14,11 @@ extern const AP_HAL::HAL& hal;
|
||||||
AP_RCProtocol_DroneCAN::Registry AP_RCProtocol_DroneCAN::registry;
|
AP_RCProtocol_DroneCAN::Registry AP_RCProtocol_DroneCAN::registry;
|
||||||
AP_RCProtocol_DroneCAN *AP_RCProtocol_DroneCAN::_singleton;
|
AP_RCProtocol_DroneCAN *AP_RCProtocol_DroneCAN::_singleton;
|
||||||
|
|
||||||
void AP_RCProtocol_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
bool AP_RCProtocol_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_rcinput, ap_dronecan->get_driver_index()) == nullptr) {
|
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_rcinput, driver_index) != nullptr);
|
||||||
AP_BoardConfig::allocation_error("rc_sub");
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_RCProtocol_DroneCAN* AP_RCProtocol_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id)
|
AP_RCProtocol_DroneCAN* AP_RCProtocol_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id)
|
||||||
|
|
|
@ -18,7 +18,7 @@ public:
|
||||||
_singleton = this;
|
_singleton = this;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
static bool subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
||||||
|
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue