mirror of https://github.com/ArduPilot/ardupilot
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.
This commit is contained in:
parent
b7fba78087
commit
79638db36b
|
@ -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…
Reference in New Issue