Browse Source

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
mission-4.1.18
Francisco Ferreira 7 years ago
parent
commit
5b383bae16
No known key found for this signature in database
GPG Key ID: F63C20A6773E787E
  1. 3
      libraries/AP_HAL_Linux/Scheduler.cpp
  2. 3
      libraries/AP_HAL_Linux/Thread.cpp

3
libraries/AP_HAL_Linux/Scheduler.cpp

@ -359,7 +359,8 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ @@ -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,

3
libraries/AP_HAL_Linux/Thread.cpp

@ -17,6 +17,7 @@ @@ -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) @@ -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;
}

Loading…
Cancel
Save