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
This commit is contained in:
Lucas De Marchi 2016-04-23 02:18:28 -03:00
parent b2d4da4b0a
commit 37f6b51746

View File

@ -96,6 +96,7 @@ void Scheduler::init()
const struct sched_table *t = &sched_table[i]; const struct sched_table *t = &sched_table[i];
t->thread->set_rate(t->rate); t->thread->set_rate(t->rate);
t->thread->set_stack_size(256 * 1024);
t->thread->start(t->name, t->policy, t->prio); t->thread->start(t->name, t->policy, t->prio);
} }