aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/hott_telemetry/hott_telemetry_main.c1
-rw-r--r--apps/mavlink/mavlink_receiver.c10
2 files changed, 6 insertions, 5 deletions
diff --git a/apps/hott_telemetry/hott_telemetry_main.c b/apps/hott_telemetry/hott_telemetry_main.c
index d67ab06a9..31c9247aa 100644
--- a/apps/hott_telemetry/hott_telemetry_main.c
+++ b/apps/hott_telemetry/hott_telemetry_main.c
@@ -51,6 +51,7 @@
#include <stdio.h>
#include <string.h>
#include <termios.h>
+#include <sys/ioctl.h>
#include <unistd.h>
#include <systemlib/systemlib.h>
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index 9491ce7e3..86732d07c 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -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);