5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-09 17:38:32 -04:00

AP_IOMCU: correct TCIE setting and add more debug

This commit is contained in:
Andy Piper 2024-05-30 16:31:36 +01:00 committed by Randy Mackay
parent c8695dfb3a
commit 8fc35276db
2 changed files with 3 additions and 3 deletions
libraries/AP_IOMCU

View File

@ -637,8 +637,8 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1
// wait for the expected number of reply bytes or timeout // wait for the expected number of reply bytes or timeout
if (!uart.wait_timeout(count*2+4, 10)) { if (!uart.wait_timeout(count*2+4, 10)) {
debug("t=%lu timeout read page=%u offset=%u count=%u\n", debug("t=%lu timeout read page=%u offset=%u count=%u avail=%u\n",
AP_HAL::millis(), page, offset, count); AP_HAL::millis(), page, offset, count, uart.available());
protocol_fail_count++; protocol_fail_count++;
return false; return false;
} }

View File

@ -91,7 +91,7 @@ static void setup_tx_dma(hal_uart_driver* uart)
dmaStreamSetMode(uart->dmatx, uart->dmatxmode | STM32_DMA_CR_DIR_M2P | dmaStreamSetMode(uart->dmatx, uart->dmatxmode | STM32_DMA_CR_DIR_M2P |
STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE); STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
// enable transmission complete interrupt // enable transmission complete interrupt
uart->usart->SR = ~USART_SR_TC; uart->usart->SR &= ~USART_SR_TC;
uart->usart->CR1 |= USART_CR1_TCIE; uart->usart->CR1 |= USART_CR1_TCIE;
dmaStreamEnable(uart->dmatx); dmaStreamEnable(uart->dmatx);