mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
HAL_Linux: reduce the number of times we split up UART reads
This commit is contained in:
parent
076bb1294e
commit
c834589daa
@ -648,12 +648,12 @@ void LinuxUARTDriver::_timer_tick(void)
|
||||
uint16_t _head;
|
||||
n = BUF_SPACE(_readbuf);
|
||||
if (n > 0) {
|
||||
if (_readbuf_tail < _head) {
|
||||
uint16_t n1 = _readbuf_size - _readbuf_tail;
|
||||
if (n1 >= n) {
|
||||
// one read will do
|
||||
assert(_readbuf_tail+n <= _readbuf_size);
|
||||
_read_fd(&_readbuf[_readbuf_tail], n);
|
||||
} else {
|
||||
uint16_t n1 = _readbuf_size - _readbuf_tail;
|
||||
assert(_readbuf_tail+n1 <= _readbuf_size);
|
||||
int ret = _read_fd(&_readbuf[_readbuf_tail], n1);
|
||||
if (ret == n1 && n > n1) {
|
||||
|
Loading…
Reference in New Issue
Block a user