mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-29 04:24:06 +08:00
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.
This commit is contained in:
parent
a844619b35
commit
0d615c80b4
@ -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…
x
Reference in New Issue
Block a user