mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: return correct value for tx_pending().
This commit is contained in:
parent
6f53337b88
commit
f71b951cb2
|
@ -627,7 +627,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; }
|
||||
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue