|
|
|
@ -296,14 +296,20 @@ size_t UARTDriver::write(uint8_t c)
@@ -296,14 +296,20 @@ size_t UARTDriver::write(uint8_t c)
|
|
|
|
|
if (!_initialised) { |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
if (!_write_mutex.take_nonblocking()) { |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
while (_writebuf.space() == 0) { |
|
|
|
|
if (_nonblocking_writes) { |
|
|
|
|
_write_mutex.give(); |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
hal.scheduler->delay(1); |
|
|
|
|
} |
|
|
|
|
return _writebuf.write(&c, 1); |
|
|
|
|
size_t ret = _writebuf.write(&c, 1); |
|
|
|
|
_write_mutex.give(); |
|
|
|
|
return ret; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
@ -314,6 +320,9 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
@@ -314,6 +320,9 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
|
|
|
|
|
if (!_initialised) { |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
if (!_write_mutex.take_nonblocking()) { |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
if (!_nonblocking_writes) { |
|
|
|
|
/*
|
|
|
|
|
use the per-byte delay loop in write() above for blocking writes |
|
|
|
@ -323,10 +332,13 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
@@ -323,10 +332,13 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
|
|
|
|
|
if (write(*buffer++) != 1) break; |
|
|
|
|
ret++; |
|
|
|
|
} |
|
|
|
|
_write_mutex.give(); |
|
|
|
|
return ret; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return _writebuf.write(buffer, size); |
|
|
|
|
size_t ret = _writebuf.write(buffer, size); |
|
|
|
|
_write_mutex.give(); |
|
|
|
|
return ret; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|