mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
HAL_ChibiOS: added more cache flush ops
This commit is contained in:
parent
46787fe7d8
commit
f4e31ce65b
@ -985,6 +985,7 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
|
||||
up with this great method.
|
||||
*/
|
||||
dmaStreamSetPeripheral(group.dma, &(group.pwm_drv->tim->DMAR));
|
||||
cacheBufferInvalidate(group.dma_buffer, buffer_length);
|
||||
dmaStreamSetMemory0(group.dma, group.dma_buffer);
|
||||
dmaStreamSetTransactionSize(group.dma, buffer_length/sizeof(uint32_t));
|
||||
dmaStreamSetFIFO(group.dma, STM32_DMA_FCR_DMDIS | STM32_DMA_FCR_FTH_FULL);
|
||||
|
@ -52,6 +52,7 @@ bool SoftSigReader::attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan,
|
||||
dmamode |= STM32_DMA_CR_PL(0);
|
||||
dmamode |= STM32_DMA_CR_DIR_P2M | STM32_DMA_CR_PSIZE_WORD |
|
||||
STM32_DMA_CR_MSIZE_WORD | STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE;
|
||||
cacheBufferInvalidate(signal, SOFTSIG_BOUNCE_BUF_SIZE*4);
|
||||
dmaStreamSetMemory0(dma, signal);
|
||||
dmaStreamSetTransactionSize(dma, SOFTSIG_BOUNCE_BUF_SIZE);
|
||||
dmaStreamSetMode(dma, dmamode);
|
||||
@ -98,6 +99,7 @@ void SoftSigReader::_irq_handler(void* self, uint32_t flags)
|
||||
//restart the DMA transfers
|
||||
dmaStreamDisable(sig_reader->dma);
|
||||
dmaStreamSetPeripheral(sig_reader->dma, &sig_reader->_icu_drv->tim->DMAR);
|
||||
cacheBufferInvalidate(sig_reader->signal, SOFTSIG_BOUNCE_BUF_SIZE*4);
|
||||
dmaStreamSetMemory0(sig_reader->dma, sig_reader->signal);
|
||||
dmaStreamSetTransactionSize(sig_reader->dma, SOFTSIG_BOUNCE_BUF_SIZE);
|
||||
dmaStreamSetMode(sig_reader->dma, sig_reader->dmamode);
|
||||
|
@ -284,6 +284,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
dmamode |= STM32_DMA_CR_CHSEL(STM32_DMA_GETCHANNEL(sdef.dma_rx_stream_id,
|
||||
sdef.dma_rx_channel_id));
|
||||
dmamode |= STM32_DMA_CR_PL(0);
|
||||
cacheBufferInvalidate(rx_bounce_buf, RX_BOUNCE_BUFSIZE);
|
||||
dmaStreamSetMemory0(rxdma, rx_bounce_buf);
|
||||
dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE);
|
||||
dmaStreamSetMode(rxdma, dmamode | STM32_DMA_CR_DIR_P2M |
|
||||
@ -412,6 +413,7 @@ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
|
||||
uart_drv->receive_timestamp_update();
|
||||
|
||||
//restart the DMA transfers
|
||||
cacheBufferInvalidate(uart_drv->rx_bounce_buf, RX_BOUNCE_BUFSIZE);
|
||||
dmaStreamSetMemory0(uart_drv->rxdma, uart_drv->rx_bounce_buf);
|
||||
dmaStreamSetTransactionSize(uart_drv->rxdma, RX_BOUNCE_BUFSIZE);
|
||||
dmaStreamEnable(uart_drv->rxdma);
|
||||
@ -724,6 +726,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
||||
|
||||
tx_bounce_buf_ready = false;
|
||||
osalDbgAssert(txdma != nullptr, "UART TX DMA allocation failed");
|
||||
cacheBufferFlush(tx_bounce_buf, tx_len);
|
||||
dmaStreamSetMemory0(txdma, tx_bounce_buf);
|
||||
dmaStreamSetTransactionSize(txdma, tx_len);
|
||||
uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE;
|
||||
@ -875,6 +878,7 @@ void UARTDriver::_timer_tick(void)
|
||||
}
|
||||
//DMA disabled by idle interrupt never got a chance to be handled
|
||||
//we will enable it here
|
||||
cacheBufferInvalidate(rx_bounce_buf, RX_BOUNCE_BUFSIZE);
|
||||
dmaStreamSetMemory0(rxdma, rx_bounce_buf);
|
||||
dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE);
|
||||
dmaStreamEnable(rxdma);
|
||||
|
@ -32,8 +32,8 @@ UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7
|
||||
#IOMCU_UART USART6
|
||||
|
||||
# UART4 serial GPS
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
PA1 UART4_RX UART4 NODMA
|
||||
PA0 UART4_TX UART4
|
||||
PA1 UART4_RX UART4
|
||||
|
||||
PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PA3 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
Loading…
Reference in New Issue
Block a user