mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: allocate threads from any heap
this fixes a failure on MatekF405-Wing where it fails to allocate the SPI thread for the IMU
This commit is contained in:
parent
6b88b2ba97
commit
f04efe7985
|
@ -113,12 +113,14 @@ AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t pe
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
thread_ctx = chThdCreateFromHeap(NULL,
|
thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(1024),
|
||||||
THD_WORKING_AREA_SIZE(1024),
|
|
||||||
name,
|
name,
|
||||||
thread_priority, /* Initial priority. */
|
thread_priority, /* Initial priority. */
|
||||||
DeviceBus::bus_thread, /* Thread function. */
|
DeviceBus::bus_thread, /* Thread function. */
|
||||||
this); /* Thread parameter. */
|
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;
|
DeviceBus::callback_info *callback = new DeviceBus::callback_info;
|
||||||
if (callback == nullptr) {
|
if (callback == nullptr) {
|
||||||
|
|
|
@ -461,8 +461,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
thread_t *thread_ctx = chThdCreateFromHeap(NULL,
|
thread_t *thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(stack_size),
|
||||||
THD_WORKING_AREA_SIZE(stack_size),
|
|
||||||
name,
|
name,
|
||||||
thread_priority,
|
thread_priority,
|
||||||
thread_create_trampoline,
|
thread_create_trampoline,
|
||||||
|
|
|
@ -101,8 +101,7 @@ void UARTDriver::thread_init(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#if CH_CFG_USE_HEAP == TRUE
|
#if CH_CFG_USE_HEAP == TRUE
|
||||||
uart_thread_ctx = chThdCreateFromHeap(NULL,
|
uart_thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(2048),
|
||||||
THD_WORKING_AREA_SIZE(2048),
|
|
||||||
"apm_uart",
|
"apm_uart",
|
||||||
APM_UART_PRIORITY,
|
APM_UART_PRIORITY,
|
||||||
uart_thread,
|
uart_thread,
|
||||||
|
|
|
@ -207,4 +207,35 @@ size_t mem_available(void)
|
||||||
return totalp;
|
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;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if defined(CCM_RAM_SIZE_KB)
|
||||||
|
ret = chThdCreateFromHeap(&ccm_heap, size, name, prio, pf, arg);
|
||||||
|
if (ret != NULL) {
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(DTCM_RAM_SIZE_KB)
|
||||||
|
ret = chThdCreateFromHeap(&dtcm_heap, size, name, prio, pf, arg);
|
||||||
|
if (ret != NULL) {
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
#endif // CH_CFG_USE_HEAP
|
#endif // CH_CFG_USE_HEAP
|
||||||
|
|
|
@ -32,6 +32,7 @@ void show_stack_usage(void);
|
||||||
size_t mem_available(void);
|
size_t mem_available(void);
|
||||||
void *malloc_ccm(size_t size);
|
void *malloc_ccm(size_t size);
|
||||||
void *malloc_dma(size_t size);
|
void *malloc_dma(size_t size);
|
||||||
|
thread_t *thread_create_alloc(size_t size, const char *name, tprio_t prio, tfunc_t pf, void *arg);
|
||||||
|
|
||||||
// flush all dcache
|
// flush all dcache
|
||||||
void memory_flush_all(void);
|
void memory_flush_all(void);
|
||||||
|
|
Loading…
Reference in New Issue