mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Adjust MAVLink RX prio to ensure received data can still be processed
This commit is contained in:
parent
884e7c2ad5
commit
9ac13745f8
@ -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);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user