AP_HAL_Linux: Scheduler: increase stack for scheduler threads

RPI-based boards that use RCInput_RPI need more stack space otherwise we
end up with stack corruption. This leads to crash particularly when also
using GPIO_RPI since it may change what that driver is poking on memory.

This increases stack size to 1M which is overkill for most of other
boards with a more controllable stack usage. However this exposes that
on multiple different HWs a single point for stack size decision may not
be the best.  This can be improved in future.
This commit is contained in:
Lucas De Marchi 2017-05-22 13:43:41 -07:00 committed by Randy Mackay
parent 5fad98078f
commit c1984451e7
1 changed files with 1 additions and 1 deletions

View File

@ -106,7 +106,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->set_stack_size(1024 * 1024);
t->thread->start(t->name, t->policy, t->prio); t->thread->start(t->name, t->policy, t->prio);
} }