diff --git a/libraries/AP_HAL_ChibiOS/Device.cpp b/libraries/AP_HAL_ChibiOS/Device.cpp index 1281d2512a..6e78be6202 100644 --- a/libraries/AP_HAL_ChibiOS/Device.cpp +++ b/libraries/AP_HAL_ChibiOS/Device.cpp @@ -114,12 +114,14 @@ AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t pe break; } - thread_ctx = chThdCreateFromHeap(NULL, - THD_WORKING_AREA_SIZE(1024), - name, - thread_priority, /* Initial priority. */ - DeviceBus::bus_thread, /* Thread function. */ - this); /* Thread parameter. */ + thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(1024), + name, + thread_priority, /* Initial priority. */ + DeviceBus::bus_thread, /* Thread function. */ + this); /* Thread parameter. */ + if (thread_ctx == nullptr) { + AP_HAL::panic("Failed to create bus thread %s", name); + } } DeviceBus::callback_info *callback = new DeviceBus::callback_info; if (callback == nullptr) { diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index b21d7e87da..2600f3914d 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -460,8 +460,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ break; } } - thread_t *thread_ctx = chThdCreateFromHeap(NULL, - THD_WORKING_AREA_SIZE(stack_size), + thread_t *thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(stack_size), name, thread_priority, thread_create_trampoline, diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 47525ce533..109689d2e2 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -101,8 +101,7 @@ void UARTDriver::thread_init(void) return; } #if CH_CFG_USE_HEAP == TRUE - uart_thread_ctx = chThdCreateFromHeap(NULL, - THD_WORKING_AREA_SIZE(2048), + uart_thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(2048), "apm_uart", APM_UART_PRIORITY, uart_thread, diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c index 3932d9b8bc..6af59cc24a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c @@ -224,6 +224,31 @@ size_t mem_available(void) return totalp; } +/* + allocate a thread on any available heap + */ +thread_t *thread_create_alloc(size_t size, + const char *name, tprio_t prio, + tfunc_t pf, void *arg) +{ + thread_t *ret; + // first try default heap + ret = chThdCreateFromHeap(NULL, size, name, prio, pf, arg); + if (ret != NULL) { + return ret; + } + + // now try other heaps + uint8_t i; + for (i=1; i