From 47c4ece9eb01eb66e97df2b968a9878da284a79c Mon Sep 17 00:00:00 2001 From: tumbili Date: Fri, 26 Jun 2015 15:02:12 +0200 Subject: [PATCH] use px4_poll instead of poll --- src/modules/navigator/navigator_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index d7f971f067..e4ef373d1b 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -309,7 +309,7 @@ Navigator::task_main() const hrt_abstime mavlink_open_interval = 500000; /* wakeup source(s) */ - struct pollfd fds[8]; + px4_pollfd_struct_t fds[8]; /* Setup of loop */ fds[0].fd = _global_pos_sub; @@ -332,7 +332,7 @@ Navigator::task_main() while (!_task_should_exit) { /* wait for up to 100ms for data */ - int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); + int pret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); if (pret == 0) { /* timed out - periodic check for _task_should_exit, etc. */