mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_ChibiOS: return correct value for tx_pending().
This commit is contained in:
parent
c88d91bdc1
commit
98c03b498d
@ -635,7 +635,7 @@ void UARTDriver::set_blocking_writes(bool blocking)
|
|||||||
_blocking_writes = blocking;
|
_blocking_writes = blocking;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool UARTDriver::tx_pending() { return false; }
|
bool UARTDriver::tx_pending() { return _writebuf.available() > 0; }
|
||||||
|
|
||||||
/* Empty implementations of Stream virtual methods */
|
/* Empty implementations of Stream virtual methods */
|
||||||
uint32_t UARTDriver::available() {
|
uint32_t UARTDriver::available() {
|
||||||
|
Loading…
Reference in New Issue
Block a user