diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-11-03 09:48:06 +0100 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-11-03 09:48:06 +0100 |
commit | 9ac13745f8356db60322fa92ecdff1125c76f172 (patch) | |
tree | 7b0839aa3479c2912cdccedd1b5407cf6356d102 | |
parent | 884e7c2ad5f5a79245c8d602901fda756ab6ca51 (diff) | |
download | px4-firmware-9ac13745f8356db60322fa92ecdff1125c76f172.tar.gz px4-firmware-9ac13745f8356db60322fa92ecdff1125c76f172.tar.bz2 px4-firmware-9ac13745f8356db60322fa92ecdff1125c76f172.zip |
Adjust MAVLink RX prio to ensure received data can still be processed
-rw-r--r-- | src/modules/mavlink/mavlink_receiver.cpp | 2 |
1 files changed, 1 insertions, 1 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 9247f999a..bc092c7e9 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1396,7 +1396,7 @@ MavlinkReceiver::receive_start(Mavlink *parent) struct sched_param param; (void)pthread_attr_getschedparam(&receiveloop_attr, ¶m); - param.sched_priority = SCHED_PRIORITY_MAX - 40; + param.sched_priority = SCHED_PRIORITY_MAX - 80; (void)pthread_attr_setschedparam(&receiveloop_attr, ¶m); pthread_attr_setstacksize(&receiveloop_attr, 2900); |