AP_HAL_Linux: Use pthread_self in place of _ctx

Avoid aproblem where _ctx is initialized in a race condition.

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2020-07-06 12:26:15 -03:00 committed by Lucas De Marchi
parent 248daa85a1
commit 5746943f50
1 changed files with 3 additions and 1 deletions

View File

@ -85,7 +85,9 @@ void Thread::_poison_stack()
void *stackp;
uint32_t *p, *curr, *begin, *end;
if (pthread_getattr_np(_ctx, &attr) != 0 ||
// `pthread_self` should be used here since _ctx could be not initialized
// in a race condition.
if (pthread_getattr_np(pthread_self(), &attr) != 0 ||
pthread_attr_getstack(&attr, &stackp, &stack_size) != 0 ||
pthread_attr_getguardsize(&attr, &guard_size) != 0) {
return;