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