Adjust MAVLink RX prio to ensure received data can still be processed

This commit is contained in:
Lorenz Meier 2014-11-03 09:48:06 +01:00
parent 884e7c2ad5
commit 9ac13745f8

View File

@ -1396,7 +1396,7 @@ MavlinkReceiver::receive_start(Mavlink *parent)
struct sched_param param;
(void)pthread_attr_getschedparam(&receiveloop_attr, &param);
param.sched_priority = SCHED_PRIORITY_MAX - 40;
param.sched_priority = SCHED_PRIORITY_MAX - 80;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
pthread_attr_setstacksize(&receiveloop_attr, 2900);