aboutsummaryrefslogtreecommitdiff
path: root/apps/mavlink/mavlink_receiver.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-10-17 10:38:23 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-10-17 10:38:23 +0200
commit5d3d17d025fa860879b145a99ec80afb7db38edc (patch)
tree3e2e5084612f510160d27cfa4300f7b6b95c19a5 /apps/mavlink/mavlink_receiver.c
parent32e586d4b7561d1018e29aa59f572c3bac625024 (diff)
downloadpx4-firmware-5d3d17d025fa860879b145a99ec80afb7db38edc.tar.gz
px4-firmware-5d3d17d025fa860879b145a99ec80afb7db38edc.tar.bz2
px4-firmware-5d3d17d025fa860879b145a99ec80afb7db38edc.zip
Increased priority of MAVLink receiver thread
Diffstat (limited to 'apps/mavlink/mavlink_receiver.c')
-rw-r--r--apps/mavlink/mavlink_receiver.c5
1 files changed, 5 insertions, 0 deletions
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index ad46c3ede..060bff2b4 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -487,6 +487,11 @@ receive_start(int uart)
{
pthread_attr_t receiveloop_attr;
pthread_attr_init(&receiveloop_attr);
+
+ struct sched_param param;
+ param.sched_priority = SCHED_PRIORITY_MAX - 40;
+ (void)pthread_attr_setschedparam(&receiveloop_attr, &param);
+
pthread_attr_setstacksize(&receiveloop_attr, 2048);
pthread_t thread;