mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-22 06:14:14 +08:00
Reduced stack size for mavlink receiver.
This commit is contained in:
@@ -617,7 +617,7 @@ receive_start(int uart)
|
||||
param.sched_priority = SCHED_PRIORITY_MAX - 40;
|
||||
(void)pthread_attr_setschedparam(&receiveloop_attr, ¶m);
|
||||
|
||||
pthread_attr_setstacksize(&receiveloop_attr, 4096);
|
||||
pthread_attr_setstacksize(&receiveloop_attr, 3072);
|
||||
|
||||
pthread_t thread;
|
||||
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
|
||||
|
||||
Reference in New Issue
Block a user