From 5b383bae16fee8b89a16d0cd3516b13e204d78bd Mon Sep 17 00:00:00 2001 From: Francisco Ferreira Date: Thu, 6 Sep 2018 16:23:14 +0100 Subject: [PATCH] AP_HAL_Linux: force Thread stack to have minimum size Check that Thread stack size is the minimum allowed Also add 256k to HAL-independent request stack size --- libraries/AP_HAL_Linux/Scheduler.cpp | 3 ++- libraries/AP_HAL_Linux/Thread.cpp | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_Linux/Scheduler.cpp b/libraries/AP_HAL_Linux/Scheduler.cpp index e34f61d464..2197ca8c2d 100644 --- a/libraries/AP_HAL_Linux/Scheduler.cpp +++ b/libraries/AP_HAL_Linux/Scheduler.cpp @@ -359,7 +359,8 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ } } - thread->set_stack_size(stack_size); + // Add 256k to HAL-independent requested stack size + thread->set_stack_size(256 * 1024 + stack_size); /* * We should probably store the thread handlers and join() when exiting, diff --git a/libraries/AP_HAL_Linux/Thread.cpp b/libraries/AP_HAL_Linux/Thread.cpp index 91fcfcbbb4..a9659e84cb 100644 --- a/libraries/AP_HAL_Linux/Thread.cpp +++ b/libraries/AP_HAL_Linux/Thread.cpp @@ -17,6 +17,7 @@ #include "Thread.h" #include +#include #include #include #include @@ -243,7 +244,7 @@ bool Thread::set_stack_size(size_t stack_size) return false; } - _stack_size = stack_size; + _stack_size = MAX(stack_size, (size_t) PTHREAD_STACK_MIN); return true; }