Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix mavlink shell #17065

Merged
merged 4 commits into from
Mar 15, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion boards/cuav/x7pro/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
16 changes: 14 additions & 2 deletions src/modules/mavlink/mavlink_shell.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand All @@ -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) {
Expand Down Expand Up @@ -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]);
Expand Down