mirror of https://github.com/ArduPilot/ardupilot
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:
parent
f3c19575e9
commit
eccec866f5
|
@ -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
|
||||||
|
|
Loading…
Reference in New Issue