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
This commit is contained in:
Francisco Ferreira 2018-09-06 16:23:14 +01:00
parent e278a09668
commit 5b383bae16
No known key found for this signature in database
GPG Key ID: F63C20A6773E787E
2 changed files with 4 additions and 2 deletions

View File

@ -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,

View File

@ -17,6 +17,7 @@
#include "Thread.h"
#include <alloca.h>
#include <limits.h>
#include <sys/types.h>
#include <stdio.h>
#include <unistd.h>
@ -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;
}