HAL_ChibiOS: allow for blocking unbuffered uarts

this is used by AP_IOMCU to avoid a race condition where the mutex is
busy on write() causing a zero-length write and delayed output
This commit is contained in:
Andrew Tridgell 2019-08-14 10:55:47 +10:00
parent f772e4622c
commit aa49047ca5
1 changed files with 7 additions and 3 deletions

View File

@ -516,7 +516,7 @@ size_t UARTDriver::write(uint8_t c)
}
while (_writebuf.space() == 0) {
if (!_blocking_writes) {
if (!_blocking_writes || unbuffered_writes) {
_write_mutex.give();
return 0;
}
@ -536,8 +536,12 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
return 0;
}
if (!_write_mutex.take_nonblocking()) {
return 0;
if (_blocking_writes && unbuffered_writes) {
_write_mutex.take_blocking();
} else {
if (!_write_mutex.take_nonblocking()) {
return 0;
}
}
if (_blocking_writes && !unbuffered_writes) {