mirror of https://github.com/ArduPilot/ardupilot
FastSerial: added tx_pending() method
this allows the caller to wait for the tx buffer to drain
This commit is contained in:
parent
d4056213ad
commit
b7e807cd58
|
@ -165,6 +165,11 @@ public:
|
|||
_nonblocking_writes = !blocking;
|
||||
}
|
||||
|
||||
// return true if there are bytes pending transmission
|
||||
bool tx_pending(void) {
|
||||
return (_txBuffer->head != _txBuffer->tail);
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
/// Bit mask for initialized ports
|
||||
|
|
Loading…
Reference in New Issue