mirror of https://github.com/ArduPilot/ardupilot
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:
parent
d970451331
commit
b2d4da4b0a
|
@ -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;
|
||||
|
|
|
@ -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 {
|
||||
|
|
Loading…
Reference in New Issue