Browse Source

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.
master
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
0f4337b7b1
  1. 2
      libraries/AP_HAL_Linux/UARTDriver.cpp

2
libraries/AP_HAL_Linux/UARTDriver.cpp

@ -328,12 +328,12 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size) @@ -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;
}

Loading…
Cancel
Save