AP_IOMCU: use thread_create() API

This commit is contained in:
Andrew Tridgell 2018-07-07 10:39:24 +10:00 committed by Randy Mackay
parent 086f7e8bd4
commit 230e1f681b
2 changed files with 3 additions and 17 deletions

View File

@ -133,26 +133,13 @@ void AP_IOMCU::init(void)
if (!boardconfig || boardconfig->io_enabled() == 1) {
check_crc();
}
thread_ctx = chThdCreateFromHeap(NULL,
THD_WORKING_AREA_SIZE(1024),
"IOMCU",
183,
thread_start,
this);
if (thread_ctx == nullptr) {
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_IOMCU::thread_main, void), "IOMCU",
1024, AP_HAL::Scheduler::PRIORITY_BOOST, 1)) {
AP_HAL::panic("Unable to allocate IOMCU thread");
}
}
/*
static function to enter thread_main()
*/
void AP_IOMCU::thread_start(void *ctx)
{
((AP_IOMCU *)ctx)->thread_main();
}
/*
handle event failure
*/

View File

@ -87,7 +87,6 @@ public:
private:
AP_HAL::UARTDriver &uart;
static void thread_start(void *ctx);
void thread_main(void);
// read count 16 bit registers