mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: read in larger chunks
This commit is contained in:
parent
655f57ad01
commit
deb0b9c197
|
@ -400,18 +400,19 @@ void UARTDriver::_timer_tick(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_readbuffer.space() == 0) {
|
uint32_t space = _readbuffer.space();
|
||||||
|
if (space == 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
ssize_t nread;
|
char buf[space];
|
||||||
char c;
|
ssize_t nread = 0;
|
||||||
if (!_use_send_recv) {
|
if (!_use_send_recv) {
|
||||||
int fd = _console?0:_fd;
|
int fd = _console?0:_fd;
|
||||||
nread = ::read(fd, &c, 1);
|
nread = ::read(fd, buf, space);
|
||||||
} else {
|
} else {
|
||||||
if (_select_check(_fd)) {
|
if (_select_check(_fd)) {
|
||||||
nread = recv(_fd, &c, 1, MSG_DONTWAIT);
|
nread = recv(_fd, buf, space, MSG_DONTWAIT);
|
||||||
if (nread <= 0) {
|
if (nread <= 0) {
|
||||||
// the socket has reached EOF
|
// the socket has reached EOF
|
||||||
close(_fd);
|
close(_fd);
|
||||||
|
@ -424,8 +425,8 @@ void UARTDriver::_timer_tick(void)
|
||||||
nread = 0;
|
nread = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (nread == 1) {
|
if (nread > 0) {
|
||||||
_readbuffer.write((uint8_t *)&c, 1);
|
_readbuffer.write((uint8_t *)buf, nread);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue