From 3dfa1f28794e206f80a2140af06016dcb9467e0c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 7 Jul 2018 10:16:31 +1000 Subject: [PATCH] HAL_PX4: implement thread_create() API --- libraries/AP_HAL_PX4/Scheduler.cpp | 64 ++++++++++++++++++++++++++++++ libraries/AP_HAL_PX4/Scheduler.h | 7 ++++ 2 files changed, 71 insertions(+) diff --git a/libraries/AP_HAL_PX4/Scheduler.cpp b/libraries/AP_HAL_PX4/Scheduler.cpp index 668d141c81..0f41e2f35a 100644 --- a/libraries/AP_HAL_PX4/Scheduler.cpp +++ b/libraries/AP_HAL_PX4/Scheduler.cpp @@ -446,4 +446,68 @@ void PX4Scheduler::restore_interrupts(void *state) irqrestore((irqstate_t)(uintptr_t)state); } +/* + trampoline for thread create +*/ +void *PX4Scheduler::thread_create_trampoline(void *ctx) +{ + AP_HAL::MemberProc *t = (AP_HAL::MemberProc *)ctx; + (*t)(); + free(t); + return nullptr; +} + +/* + create a new thread +*/ +bool PX4Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_t stack_size, priority_base base, int8_t priority) +{ + // take a copy of the MemberProc, it is freed after thread exits + AP_HAL::MemberProc *tproc = (AP_HAL::MemberProc *)malloc(sizeof(proc)); + if (!tproc) { + return false; + } + *tproc = proc; + + uint8_t thread_priority = APM_IO_PRIORITY; + static const struct { + priority_base base; + uint8_t p; + } priority_map[] = { + { PRIORITY_BOOST, APM_MAIN_PRIORITY_BOOST}, + { PRIORITY_MAIN, APM_MAIN_PRIORITY}, + { PRIORITY_SPI, APM_SPI_PRIORITY}, + { PRIORITY_I2C, APM_I2C_PRIORITY}, + { PRIORITY_CAN, APM_CAN_PRIORITY}, + { PRIORITY_TIMER, APM_TIMER_PRIORITY}, + { PRIORITY_RCIN, APM_TIMER_PRIORITY}, + { PRIORITY_IO, APM_IO_PRIORITY}, + { PRIORITY_UART, APM_UART_PRIORITY}, + { PRIORITY_STORAGE, APM_STORAGE_PRIORITY}, + }; + for (uint8_t i=0; i