MAVLink app: Do not try to fill the complete buffer, just try to get a complete message

This commit is contained in:
Lorenz Meier 2015-11-03 00:16:38 +01:00
parent 8a6e9d17ba
commit c934286f6c
1 changed files with 8 additions and 6 deletions

View File

@ -1797,13 +1797,15 @@ MavlinkReceiver::receive_thread(void *arg)
while (!_mavlink->_task_should_exit) {
if (poll(&fds[0], 1, timeout) > 0) {
if (_mavlink->get_protocol() == SERIAL) {
/*
* to avoid reading very small chunks wait for data before reading
* this is designed to target ~30 bytes at a time
*/
const unsigned character_count = 20;
/* non-blocking read. read may return negative values */
if ((nread = ::read(uart_fd, buf, sizeof(buf))) < (ssize_t)sizeof(buf)) {
/*
* to avoid reading very small chunks wait for data before reading
* this is designed to target ~30 bytes at a time
*/
const unsigned character_count = 20;
if ((nread = ::read(uart_fd, buf, sizeof(buf))) < (ssize_t)character_count) {
unsigned sleeptime = (1.0f / (_mavlink->get_baudrate() / 10)) * character_count * 1000000;
usleep(sleeptime);
}