mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_HAL_Linux: Thread: make sure pointer is aligned
Implementation of alloca() is very much architecture and compiler dependent. Avoid the case in which it could return a non-aligned pointer, which would mean Thread::_poison_stack() would do the wrong thing.
This commit is contained in:
parent
7e49d0c53f
commit
359417d544
@ -55,6 +55,12 @@ bool Thread::_run()
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* Round up to the specified alignment */
|
||||||
|
static inline void *align_to(void *p, size_t align)
|
||||||
|
{
|
||||||
|
return (void *)(((uintptr_t)p + align - 1) & ~(align - 1));
|
||||||
|
}
|
||||||
|
|
||||||
void Thread::_poison_stack()
|
void Thread::_poison_stack()
|
||||||
{
|
{
|
||||||
pthread_attr_t attr;
|
pthread_attr_t attr;
|
||||||
@ -75,7 +81,7 @@ void Thread::_poison_stack()
|
|||||||
* protects the end */
|
* protects the end */
|
||||||
end = (uint32_t *)stackp;
|
end = (uint32_t *)stackp;
|
||||||
begin = end + stack_size;
|
begin = end + stack_size;
|
||||||
curr = (uint32_t *)alloca(sizeof(uint32_t));
|
curr = (uint32_t *)align_to(alloca(sizeof(uint32_t)), alignof(uint32_t));
|
||||||
|
|
||||||
/* if curr is closer to @end, the stack actually grows from low to high
|
/* if curr is closer to @end, the stack actually grows from low to high
|
||||||
* virtual address: this is because this function should be executing very
|
* virtual address: this is because this function should be executing very
|
||||||
@ -92,6 +98,10 @@ void Thread::_poison_stack()
|
|||||||
} else {
|
} else {
|
||||||
end += guard_size;
|
end += guard_size;
|
||||||
|
|
||||||
|
/* we aligned curr to the up boundary, make sure this didn't cause us
|
||||||
|
* to lose some bytes */
|
||||||
|
curr--;
|
||||||
|
|
||||||
for (p = end; p < curr; p++) {
|
for (p = end; p < curr; p++) {
|
||||||
*p = STACK_POISON;
|
*p = STACK_POISON;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user