mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
AP_HAL_ChibiOS: return correct value for tx_pending().
This commit is contained in:
parent
765bf35703
commit
5591ea2530
@ -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() {
|
||||
|
Loading…
Reference in New Issue
Block a user