diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-01-30 00:54:55 -0800 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-01-30 00:54:55 -0800 |
commit | 3b31a6b1b9756eb191eaaafb1c137e6874079281 (patch) | |
tree | 359f2caf74e019ea452c3b0fdc17a8643bc42651 /src/modules/mavlink | |
parent | 70afb3ca3b3f1844241c9c9312579bbb2475232c (diff) | |
parent | 44cb4d96171fae0bcd5dd4bdf5cb668a039727b5 (diff) | |
download | px4-firmware-3b31a6b1b9756eb191eaaafb1c137e6874079281.tar.gz px4-firmware-3b31a6b1b9756eb191eaaafb1c137e6874079281.tar.bz2 px4-firmware-3b31a6b1b9756eb191eaaafb1c137e6874079281.zip |
Merge pull request #620 from pigeonhunter/stack_sizes
Stack sizes
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r-- | src/modules/mavlink/mavlink.c | 2 | ||||
-rw-r--r-- | src/modules/mavlink/mavlink_receiver.cpp | 2 | ||||
-rw-r--r-- | src/modules/mavlink/orb_listener.c | 2 |
3 files changed, 3 insertions, 3 deletions
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c index 20853379d..ebf01a2f4 100644 --- a/src/modules/mavlink/mavlink.c +++ b/src/modules/mavlink/mavlink.c @@ -773,7 +773,7 @@ int mavlink_main(int argc, char *argv[]) mavlink_task = task_spawn_cmd("mavlink", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - 2048, + 1200, mavlink_thread_main, (const char **)argv); diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 7b6fad658..9fc7b748a 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -871,7 +871,7 @@ receive_start(int uart) param.sched_priority = SCHED_PRIORITY_MAX - 40; (void)pthread_attr_setschedparam(&receiveloop_attr, ¶m); - pthread_attr_setstacksize(&receiveloop_attr, 3000); + pthread_attr_setstacksize(&receiveloop_attr, 1816); pthread_t thread; pthread_create(&thread, &receiveloop_attr, receive_thread, &uart); diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c index e1dabfd21..bfb824db7 100644 --- a/src/modules/mavlink/orb_listener.c +++ b/src/modules/mavlink/orb_listener.c @@ -838,7 +838,7 @@ uorb_receive_start(void) pthread_attr_init(&uorb_attr); /* Set stack size, needs less than 2k */ - pthread_attr_setstacksize(&uorb_attr, 2048); + pthread_attr_setstacksize(&uorb_attr, 1648); pthread_t thread; pthread_create(&thread, &uorb_attr, uorb_receive_thread, NULL); |