AP_HAL_Linux: Thread: allow to set stack size

This allows the code that is creating the thread to set the size of the
stack.
This commit is contained in:
Lucas De Marchi 2016-04-23 02:16:54 -03:00
parent d970451331
commit b2d4da4b0a
2 changed files with 21 additions and 0 deletions

View File

@ -154,6 +154,12 @@ bool Thread::start(const char *name, int policy, int prio)
}
}
if (_stack_size) {
if (pthread_attr_setstacksize(&attr, _stack_size) != 0) {
return false;
}
}
r = pthread_create(&_ctx, &attr, &Thread::_run_trampoline, this);
if (r != 0) {
AP_HAL::panic("Failed to create thread '%s': %s",
@ -186,6 +192,17 @@ bool PeriodicThread::set_rate(uint32_t rate_hz)
return true;
}
bool Thread::set_stack_size(size_t stack_size)
{
if (_started) {
return false;
}
_stack_size = stack_size;
return true;
}
bool PeriodicThread::_run()
{
uint64_t next_run_usec = AP_HAL::micros64() + _period_usec;

View File

@ -44,6 +44,8 @@ public:
size_t get_stack_usage();
bool set_stack_size(size_t stack_size);
protected:
static void *_run_trampoline(void *arg);
@ -64,6 +66,8 @@ protected:
uint32_t *start;
uint32_t *end;
} _stack_debug;
size_t _stack_size;
};
class PeriodicThread : public Thread {