From f7c31e4d804c81659dcf79684807fbc8bfad5365 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 13 Jan 2013 18:41:03 -0500 Subject: [PATCH] Reduced stack size for mavlink receiver. --- apps/mavlink/mavlink_receiver.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c index 850b366a3b..e686790f30 100644 --- a/apps/mavlink/mavlink_receiver.c +++ b/apps/mavlink/mavlink_receiver.c @@ -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);