From 37f6b51746f4b3091f89859fd3a6267c74411e1a Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Sat, 23 Apr 2016 02:18:28 -0300 Subject: [PATCH] AP_HAL_Linux: Scheduler: set stack sizes to 256k Running the vehicles we check the stack size doesn't grow too much by enabling the DEBUG_STACK in the scheduler. Even on 64bit boards the stack is consistent around 4k. Just to be a little conservative, let it be a little bit more that that: 256kB. Since we have RT prio and we call mlock(), the memory for the stack of each thread is locked in memory. This means we are effectively taking that much memory. The default stack size varies per distro, but it's common to have 8MB for 64 bit boards and 4MB for 32 bit boards. Here is the output of ps -L -o 'comm,rtprio,rss $(pidof arducopter-quad)', showing the RSS of arducopter-quad before and after this change: Before: COMMAND RTPRIO RSS arducopter-quad 12 46960 sched-timer 15 46960 sched-uart 14 46960 sched-rcin 13 46960 sched-tonealarm 11 46960 sched-io 10 46960 After: COMMAND RTPRIO RSS arducopter-quad 12 7320 sched-timer 15 7320 sched-uart 14 7320 sched-rcin 13 7320 sched-tonealarm 11 7320 sched-io 10 7320 --- libraries/AP_HAL_Linux/Scheduler.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_Linux/Scheduler.cpp b/libraries/AP_HAL_Linux/Scheduler.cpp index bff8d09004..f76b773905 100644 --- a/libraries/AP_HAL_Linux/Scheduler.cpp +++ b/libraries/AP_HAL_Linux/Scheduler.cpp @@ -96,6 +96,7 @@ void Scheduler::init() const struct sched_table *t = &sched_table[i]; t->thread->set_rate(t->rate); + t->thread->set_stack_size(256 * 1024); t->thread->start(t->name, t->policy, t->prio); }