From f99fa6a70330c35c344d86f0d61ed7df55d33631 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 7 Jun 2023 19:19:19 +1000 Subject: [PATCH] AP_DroneCAN: use separate tx and rx semaphores this prevents a deadlock on callback for DroneCAN receiver --- libraries/AP_DroneCAN/AP_Canard_iface.cpp | 14 ++++++++------ libraries/AP_DroneCAN/AP_Canard_iface.h | 3 ++- 2 files changed, 10 insertions(+), 7 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index 2016be1bf8..4138bec36c 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.cpp +++ b/libraries/AP_DroneCAN/AP_Canard_iface.cpp @@ -49,7 +49,8 @@ bool CanardInterface::broadcast(const Canard::Transfer &bcast_transfer) { if (!initialized) { return false; } - WITH_SEMAPHORE(_sem); + WITH_SEMAPHORE(_sem_tx); + #if AP_TEST_DRONECAN_DRIVERS if (this == &test_iface) { test_iface_sem.take_blocking(); @@ -86,7 +87,7 @@ bool CanardInterface::request(uint8_t destination_node_id, const Canard::Transfe if (!initialized) { return false; } - WITH_SEMAPHORE(_sem); + WITH_SEMAPHORE(_sem_tx); tx_transfer = { .transfer_type = req_transfer.transfer_type, @@ -112,7 +113,7 @@ bool CanardInterface::respond(uint8_t destination_node_id, const Canard::Transfe if (!initialized) { return false; } - WITH_SEMAPHORE(_sem); + WITH_SEMAPHORE(_sem_tx); tx_transfer = { .transfer_type = res_transfer.transfer_type, @@ -164,7 +165,7 @@ void CanardInterface::processTestRx() { #endif void CanardInterface::processTx(bool raw_commands_only = false) { - WITH_SEMAPHORE(_sem); + WITH_SEMAPHORE(_sem_tx); for (uint8_t iface = 0; iface < num_ifaces; iface++) { if (ifaces[iface] == NULL) { @@ -252,7 +253,7 @@ void CanardInterface::processRx() { rx_frame.iface_id = i; #endif { - WITH_SEMAPHORE(_sem); + WITH_SEMAPHORE(_sem_rx); #if DEBUG_PKTS const int16_t res = @@ -289,7 +290,8 @@ void CanardInterface::process(uint32_t duration_ms) { processRx(); processTx(); { - WITH_SEMAPHORE(_sem); + WITH_SEMAPHORE(_sem_rx); + WITH_SEMAPHORE(_sem_tx); canardCleanupStaleTransfers(&canard, AP_HAL::native_micros64()); } uint64_t now = AP_HAL::native_micros64(); diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.h b/libraries/AP_DroneCAN/AP_Canard_iface.h index d1b8a8c48c..74df8581d3 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.h +++ b/libraries/AP_DroneCAN/AP_Canard_iface.h @@ -63,7 +63,8 @@ private: uint8_t num_ifaces; HAL_EventHandle _event_handle; bool initialized; - HAL_Semaphore _sem; + HAL_Semaphore _sem_tx; + HAL_Semaphore _sem_rx; CanardTxTransfer tx_transfer; }; #endif // HAL_ENABLE_DRONECAN_DRIVERS \ No newline at end of file