HOTFIX: Fixed HoTT compile error, fixed MAVLink crash

This commit is contained in:
Lorenz Meier 2013-01-31 17:31:58 +01:00
parent e7bbe685b4
commit e137d00424
2 changed files with 6 additions and 5 deletions

View File

@ -51,6 +51,7 @@
#include <stdio.h> #include <stdio.h>
#include <string.h> #include <string.h>
#include <termios.h> #include <termios.h>
#include <sys/ioctl.h>
#include <unistd.h> #include <unistd.h>
#include <systemlib/systemlib.h> #include <systemlib/systemlib.h>

View File

@ -587,12 +587,12 @@ receive_thread(void *arg)
struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } }; struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } };
if (poll(fds, 1, timeout) > 0) { if (poll(fds, 1, timeout) > 0) {
/* non-blocking read */ /* non-blocking read. read may return negative values */
size_t nread = read(uart_fd, buf, sizeof(buf)); ssize_t nread = read(uart_fd, buf, sizeof(buf));
ASSERT(nread > 0)
for (size_t i = 0; i < nread; i++) { /* if read failed, this loop won't execute */
if (mavlink_parse_char(chan, buf[i], &msg, &status)) { //parse the char for (ssize_t i = 0; i < nread; i++) {
if (mavlink_parse_char(chan, buf[i], &msg, &status)) {
/* handle generic messages and commands */ /* handle generic messages and commands */
handle_message(&msg); handle_message(&msg);