AP_HAL_ChibiOS: return correct value for tx_pending().

This commit is contained in:
Andy Piper 2021-08-03 18:42:07 +01:00 committed by Andrew Tridgell
parent 765bf35703
commit 5591ea2530

View File

@ -635,7 +635,7 @@ void UARTDriver::set_blocking_writes(bool blocking)
_blocking_writes = blocking;
}
bool UARTDriver::tx_pending() { return false; }
bool UARTDriver::tx_pending() { return _writebuf.available() > 0; }
/* Empty implementations of Stream virtual methods */
uint32_t UARTDriver::available() {