aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-09-05 13:24:37 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-09-05 13:24:37 +0200
commit5dbe53877ab543728d4f2d288716d4989464237a (patch)
treead62966f0c1171d5794c125cd45f744473e187f1 /src/modules/mavlink
parentaa785b0d2b339a8fcc730e11b63264b1ff8d146d (diff)
downloadpx4-firmware-5dbe53877ab543728d4f2d288716d4989464237a.tar.gz
px4-firmware-5dbe53877ab543728d4f2d288716d4989464237a.tar.bz2
px4-firmware-5dbe53877ab543728d4f2d288716d4989464237a.zip
Fixed sched param setup in MAVLink app
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp1
1 files changed, 1 insertions, 0 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index af43542da..4674f7a24 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -747,6 +747,7 @@ receive_start(int uart)
fcntl(uart, F_SETFL, flags | O_NONBLOCK);
struct sched_param param;
+ (void)pthread_attr_getschedparam(&receiveloop_attr, &param);
param.sched_priority = SCHED_PRIORITY_MAX - 40;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);