From 5dbe53877ab543728d4f2d288716d4989464237a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 5 Sep 2013 13:24:37 +0200 Subject: Fixed sched param setup in MAVLink app --- src/modules/mavlink/mavlink_receiver.cpp | 1 + 1 file changed, 1 insertion(+) (limited to 'src/modules/mavlink') 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, ¶m); param.sched_priority = SCHED_PRIORITY_MAX - 40; (void)pthread_attr_setschedparam(&receiveloop_attr, ¶m); -- cgit v1.2.3