AP_IOMCU: fixed race condition on thread startup

thread_ctx may not be set for first trigger_event()
This commit is contained in:
Andrew Tridgell 2018-01-08 14:52:11 +11:00
parent b62773bbad
commit 82b5b94e24

View File

@ -140,6 +140,8 @@ void AP_IOMCU::event_failed(uint8_t event)
*/
void AP_IOMCU::thread_main(void)
{
thread_ctx = chThdGetSelfX();
// uart runs at 1.5MBit
uart.begin(1500*1000, 256, 256);
uart.set_blocking_writes(false);