From 0f4337b7b12c7b98339d886364684a4cab849b48 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 24 Oct 2019 21:56:32 +1100 Subject: [PATCH] AP_HAL_Linux: release mutex lock before calling write(c) It instantly tries to take it, but we're still holding it, leading to instant failure. This mirrors the same code in AP_HAL_ChibiOS. --- libraries/AP_HAL_Linux/UARTDriver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index a7e19ba953..a71573da43 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -328,12 +328,12 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size) /* use the per-byte delay loop in write() above for blocking writes */ + _write_mutex.give(); size_t ret = 0; while (size--) { if (write(*buffer++) != 1) break; ret++; } - _write_mutex.give(); return ret; }