forked from Archive/PX4-Autopilot
HOTFIX: Fixed HoTT compile error, fixed MAVLink crash
This commit is contained in:
parent
e7bbe685b4
commit
e137d00424
|
@ -51,6 +51,7 @@
|
|||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <termios.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <unistd.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
|
|
|
@ -587,12 +587,12 @@ receive_thread(void *arg)
|
|||
struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } };
|
||||
|
||||
if (poll(fds, 1, timeout) > 0) {
|
||||
/* non-blocking read */
|
||||
size_t nread = read(uart_fd, buf, sizeof(buf));
|
||||
ASSERT(nread > 0)
|
||||
/* non-blocking read. read may return negative values */
|
||||
ssize_t nread = read(uart_fd, buf, sizeof(buf));
|
||||
|
||||
for (size_t i = 0; i < nread; i++) {
|
||||
if (mavlink_parse_char(chan, buf[i], &msg, &status)) { //parse the char
|
||||
/* if read failed, this loop won't execute */
|
||||
for (ssize_t i = 0; i < nread; i++) {
|
||||
if (mavlink_parse_char(chan, buf[i], &msg, &status)) {
|
||||
/* handle generic messages and commands */
|
||||
handle_message(&msg);
|
||||
|
||||
|
|
Loading…
Reference in New Issue