Browse Source

AP_HAL_ChibiOS: return correct value for tx_pending().

c415-sdk
Andy Piper 4 years ago committed by Randy Mackay
parent
commit
db00de837a
  1. 2
      libraries/AP_HAL_ChibiOS/UARTDriver.cpp

2
libraries/AP_HAL_ChibiOS/UARTDriver.cpp

@ -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…
Cancel
Save