diff --git a/boards/cuav/x7pro/default.cmake b/boards/cuav/x7pro/default.cmake index a2d03d6a63..879d961ec5 100644 --- a/boards/cuav/x7pro/default.cmake +++ b/boards/cuav/x7pro/default.cmake @@ -37,7 +37,7 @@ px4_add_board( imu/invensense/icm20649 imu/invensense/icm20689 irlock - lights/blinkm + #lights/blinkm lights/rgbled lights/rgbled_ncp5623c lights/rgbled_pwm diff --git a/src/modules/mavlink/mavlink_shell.cpp b/src/modules/mavlink/mavlink_shell.cpp index afad6a0779..6203e0f28e 100644 --- a/src/modules/mavlink/mavlink_shell.cpp +++ b/src/modules/mavlink/mavlink_shell.cpp @@ -84,8 +84,6 @@ int MavlinkShell::start() * keeps (duplicates) the first 3 fd's when creating a new task, all others are not inherited. * This means we need to temporarily change the first 3 fd's of the current task (or at least * the first 2 if stdout=stderr). - * And we hope :-) that during the temporary phase, no other thread from the same task writes to - * stdout (as it would end up in the pipe). */ if (pipe(p1) != 0) { @@ -105,6 +103,16 @@ int MavlinkShell::start() _shell_fds[0] = p2[0]; _shell_fds[1] = p1[1]; + /* + * Ensure that during the temporary phase no other thread from the same task writes to + * stdout (as it would end up in the pipe). + */ +#ifdef __PX4_NUTTX + sched_lock(); +#endif /* __PX4_NUTTX */ + fflush(stdout); + fflush(stderr); + int fd_backups[2]; //we don't touch stderr, we will redirect it to stdout in the startup of the shell task for (int i = 0; i < 2; ++i) { @@ -140,6 +148,10 @@ int MavlinkShell::start() close(fd_backups[i]); } +#ifdef __PX4_NUTTX + sched_unlock(); +#endif /* __PX4_NUTTX */ + //close unused pipe fd's close(_shell_fds[0]); close(_shell_fds[1]);