Browse Source

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.
sbg
Julian Oes 9 years ago
parent
commit
0d615c80b4
  1. 3
      src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp

3
src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp

@ -324,9 +324,12 @@ void AttitudeEstimatorQ::task_main() @@ -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

Loading…
Cancel
Save