HAL_ChibiOS: incorrect class of class in uart TX timeout

need to call chEvtGetAndClearEventsI() as we are in a system lock
state
This commit is contained in:
Andrew Tridgell 2022-04-04 14:57:18 +10:00 committed by Randy Mackay
parent f3c19575e9
commit eccec866f5
1 changed files with 1 additions and 1 deletions

View File

@ -1021,7 +1021,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
if (tx_len > 0) { if (tx_len > 0) {
_last_write_completed_us = AP_HAL::micros(); _last_write_completed_us = AP_HAL::micros();
} }
chEvtGetAndClearEvents(EVT_TRANSMIT_DMA_COMPLETE); chEvtGetAndClearEventsI(EVT_TRANSMIT_DMA_COMPLETE);
chSysUnlock(); chSysUnlock();
} }
// clean up pending locks // clean up pending locks