Reduced stack size for mavlink receiver.

This commit is contained in:
James Goppert
2013-01-13 18:41:03 -05:00
parent 56e15ab1f4
commit f7c31e4d80
+1 -1
View File
@@ -617,7 +617,7 @@ receive_start(int uart)
param.sched_priority = SCHED_PRIORITY_MAX - 40;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
pthread_attr_setstacksize(&receiveloop_attr, 4096);
pthread_attr_setstacksize(&receiveloop_attr, 3072);
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);