From 0d615c80b421562f3f5decb4e92ac60daaa4db59 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 12 Feb 2016 13:43:16 +0100 Subject: [PATCH] attitude_estimator_q: no mavlink_log for QURT Don't try to open the mavlink_fd on QURT because the px4_ioctl leads to timeouts of the attitude_estimator_q loop. --- src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp index 100981dedc..9270b44890 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -324,9 +324,12 @@ void AttitudeEstimatorQ::task_main() while (!_task_should_exit) { int ret = px4_poll(fds, 1, 1000); +#ifndef __PX4_QURT if (_mavlink_fd < 0) { + /* TODO: This call currently stalls the thread on QURT */ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); } +#endif if (ret < 0) { // Poll error, sleep and try again