UARTDriver: fix panic when using simulated latency

This would sometimes happen when initiating a connection when using
high simulated latency values when the queue would suddenly flush
to the buffer.
This commit is contained in:
Bob Long 2024-05-18 21:10:16 -05:00
parent 04fe12c29e
commit a619a9e6a8
1 changed files with 3 additions and 1 deletions

View File

@ -268,7 +268,9 @@ void UARTDriver::_flush(void)
size_t UARTDriver::_write(const uint8_t *buffer, size_t size)
{
const auto _txspace = txspace();
if (_txspace < size) {
if (_txspace < size && latencyQueueWrite.empty()) {
// If we're using a latecy queue, we don't actually care about txspace
// at this point, as we're not going to write to the device yet.
size = _txspace;
}
if (size <= 0) {