From ba0a3430908ac9fb5c601e2ed3b61662feb90a7e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 8 Mar 2015 08:14:58 +0100 Subject: MAVLink app: Adjust stack size of receiver thread --- src/modules/mavlink/mavlink_receiver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'src/modules/mavlink') diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index d46dba317..e3f274b8b 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1548,7 +1548,7 @@ MavlinkReceiver::receive_start(Mavlink *parent) param.sched_priority = SCHED_PRIORITY_MAX - 80; (void)pthread_attr_setschedparam(&receiveloop_attr, ¶m); - pthread_attr_setstacksize(&receiveloop_attr, 2100); + pthread_attr_setstacksize(&receiveloop_attr, 1800); pthread_t thread; pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent); -- cgit v1.2.3