mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: check result code of pthread_attr_init
This commit is contained in:
parent
d5729236e2
commit
9ef23872e0
|
@ -324,7 +324,9 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_
|
|||
a->f[0] = proc;
|
||||
a->name = name;
|
||||
|
||||
pthread_attr_init(&a->attr);
|
||||
if (pthread_attr_init(&a->attr) != 0) {
|
||||
goto failed;
|
||||
}
|
||||
#if SITL_STACK_CHECKING_ENABLED
|
||||
if (pthread_attr_setstack(&a->attr, a->stack, alloc_stack) != 0) {
|
||||
AP_HAL::panic("Failed to set stack of size %u for thread %s", alloc_stack, name);
|
||||
|
|
Loading…
Reference in New Issue