Browse Source

HAL_ChibiOS: wrap cacheBuffer functions

needed to avoid problem with end() method in UARTDriver shadowing with
F7 implementation of cache macros
mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
d1565a96c5
  1. 2
      libraries/AP_HAL_ChibiOS/AnalogIn.cpp
  2. 2
      libraries/AP_HAL_ChibiOS/RCOutput.cpp
  3. 2
      libraries/AP_HAL_ChibiOS/SoftSigReader.cpp
  4. 8
      libraries/AP_HAL_ChibiOS/UARTDriver.cpp
  5. 4
      libraries/AP_HAL_ChibiOS/hwdef/common/bouncebuffer.c
  6. 2
      libraries/AP_HAL_ChibiOS/hwdef/common/flash.c
  7. 2
      libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c
  8. 10
      libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c
  9. 3
      libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h

2
libraries/AP_HAL_ChibiOS/AnalogIn.cpp

@ -188,7 +188,7 @@ void AnalogIn::adccallback(ADCDriver *adcp) @@ -188,7 +188,7 @@ void AnalogIn::adccallback(ADCDriver *adcp)
{
const adcsample_t *buffer = samples;
cacheBufferInvalidate(buffer, sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS);
stm32_cacheBufferInvalidate(buffer, sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS);
for (uint8_t i = 0; i < ADC_DMA_BUF_DEPTH; i++) {
for (uint8_t j = 0; j < ADC_GRP1_NUM_CHANNELS; j++) {
sample_sum[j] += *buffer++;

2
libraries/AP_HAL_ChibiOS/RCOutput.cpp

@ -990,7 +990,7 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length) @@ -990,7 +990,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));
cacheBufferFlush(group.dma_buffer, buffer_length);
stm32_cacheBufferFlush(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);

2
libraries/AP_HAL_ChibiOS/SoftSigReader.cpp

@ -97,7 +97,7 @@ void SoftSigReader::_irq_handler(void* self, uint32_t flags) @@ -97,7 +97,7 @@ void SoftSigReader::_irq_handler(void* self, uint32_t flags)
// we need to restart the DMA as quickly as possible to prevent losing pulses, so we
// make a fixed length copy to a 2nd buffer. On the F100 this reduces the time with DMA
// disabled from 20us to under 1us
cacheBufferInvalidate(sig_reader->signal, SOFTSIG_BOUNCE_BUF_SIZE*4);
stm32_cacheBufferInvalidate(sig_reader->signal, SOFTSIG_BOUNCE_BUF_SIZE*4);
memcpy(sig_reader->signal2, sig_reader->signal, SOFTSIG_BOUNCE_BUF_SIZE*4);
//restart the DMA transfers
dmaStreamDisable(sig_reader->dma);

8
libraries/AP_HAL_ChibiOS/UARTDriver.cpp

@ -426,7 +426,7 @@ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags) @@ -426,7 +426,7 @@ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
if (!uart_drv->sdef.dma_rx) {
return;
}
cacheBufferInvalidate(uart_drv->rx_bounce_buf, RX_BOUNCE_BUFSIZE);
stm32_cacheBufferInvalidate(uart_drv->rx_bounce_buf, RX_BOUNCE_BUFSIZE);
uint8_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(uart_drv->rxdma);
if (len > 0) {
if (uart_drv->half_duplex) {
@ -436,7 +436,7 @@ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags) @@ -436,7 +436,7 @@ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
}
}
cacheBufferInvalidate(uart_drv->rx_bounce_buf, len);
stm32_cacheBufferInvalidate(uart_drv->rx_bounce_buf, len);
uart_drv->_readbuf.write(uart_drv->rx_bounce_buf, len);
uart_drv->receive_timestamp_update();
@ -765,7 +765,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) @@ -765,7 +765,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);
stm32_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;
@ -917,7 +917,7 @@ void UARTDriver::_timer_tick(void) @@ -917,7 +917,7 @@ void UARTDriver::_timer_tick(void)
if (!(rxdma->stream->CR & STM32_DMA_CR_EN)) {
uint8_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(rxdma);
if (len != 0) {
cacheBufferInvalidate(rx_bounce_buf, len);
stm32_cacheBufferInvalidate(rx_bounce_buf, len);
_readbuf.write(rx_bounce_buf, len);
receive_timestamp_update();

4
libraries/AP_HAL_ChibiOS/hwdef/common/bouncebuffer.c

@ -74,7 +74,7 @@ void bouncebuffer_setup_read(struct bouncebuffer_t *bouncebuffer, uint8_t **buf, @@ -74,7 +74,7 @@ void bouncebuffer_setup_read(struct bouncebuffer_t *bouncebuffer, uint8_t **buf,
*buf = bouncebuffer->dma_buf;
#if defined(STM32H7)
osalDbgAssert((((uint32_t)*buf)&31) == 0, "bouncebuffer read align");
cacheBufferInvalidate(*buf, (size+31)&~31);
stm32_cacheBufferInvalidate(*buf, (size+31)&~31);
#endif
bouncebuffer->busy = true;
}
@ -118,7 +118,7 @@ void bouncebuffer_setup_write(struct bouncebuffer_t *bouncebuffer, const uint8_t @@ -118,7 +118,7 @@ void bouncebuffer_setup_write(struct bouncebuffer_t *bouncebuffer, const uint8_t
*buf = bouncebuffer->dma_buf;
#if defined(STM32H7)
osalDbgAssert((((uint32_t)*buf)&31) == 0, "bouncebuffer write align");
cacheBufferFlush(*buf, (size+31)&~31);
stm32_cacheBufferFlush(*buf, (size+31)&~31);
#endif
bouncebuffer->busy = true;
}

2
libraries/AP_HAL_ChibiOS/hwdef/common/flash.c

@ -379,7 +379,7 @@ bool stm32_flash_erasepage(uint32_t page) @@ -379,7 +379,7 @@ bool stm32_flash_erasepage(uint32_t page)
stm32_flash_wait_idle();
cacheBufferInvalidate(stm32_flash_getpageaddr(page), stm32_flash_getpagesize(page));
stm32_cacheBufferInvalidate(stm32_flash_getpageaddr(page), stm32_flash_getpagesize(page));
stm32_flash_lock();
#if STM32_FLASH_DISABLE_ISR

2
libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c

@ -278,6 +278,6 @@ void memory_flush_all(void) @@ -278,6 +278,6 @@ void memory_flush_all(void)
{
uint8_t i;
for (i=0; i<NUM_MEMORY_REGIONS; i++) {
cacheBufferFlush(memory_regions[i].address, memory_regions[i].size);
stm32_cacheBufferFlush(memory_regions[i].address, memory_regions[i].size);
}
}

10
libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c

@ -341,3 +341,13 @@ iomode_t palReadLineMode(ioline_t line) @@ -341,3 +341,13 @@ iomode_t palReadLineMode(ioline_t line)
return ret;
}
#endif
void stm32_cacheBufferInvalidate(const void *p, size_t size)
{
cacheBufferInvalidate(p, size);
}
void stm32_cacheBufferFlush(const void *p, size_t size)
{
cacheBufferFlush(p, size);
}

3
libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h

@ -87,6 +87,9 @@ void set_rtc_backup(uint8_t idx, const uint32_t *v, uint8_t n); @@ -87,6 +87,9 @@ void set_rtc_backup(uint8_t idx, const uint32_t *v, uint8_t n);
// get RTC backup registers starting at given idx
void get_rtc_backup(uint8_t idx, uint32_t *v, uint8_t n);
void stm32_cacheBufferInvalidate(const void *p, size_t size);
void stm32_cacheBufferFlush(const void *p, size_t size);
#ifdef __cplusplus
}
#endif

Loading…
Cancel
Save