diff --git a/boards/nucleo144-f413/Makefile.features b/boards/nucleo144-f413/Makefile.features index c4943268ec..7531e5f16f 100644 --- a/boards/nucleo144-f413/Makefile.features +++ b/boards/nucleo144-f413/Makefile.features @@ -1,5 +1,6 @@ # Put defined MCU peripherals here (in alphabetical order) FEATURES_PROVIDED += periph_adc +FEATURES_PROVIDED += periph_dma FEATURES_PROVIDED += periph_gpio FEATURES_PROVIDED += periph_i2c FEATURES_PROVIDED += periph_pwm diff --git a/boards/nucleo144-f413/include/periph_conf.h b/boards/nucleo144-f413/include/periph_conf.h index 170d7520fe..d5525d06e5 100644 --- a/boards/nucleo144-f413/include/periph_conf.h +++ b/boards/nucleo144-f413/include/periph_conf.h @@ -71,6 +71,29 @@ extern "C" { #define CLOCK_USE_ALT_48MHZ (1) /** @} */ +/** + * @name DMA streams configuration + * @{ + */ +#ifdef MODULE_PERIPH_DMA +static const dma_conf_t dma_config[] = { + { .stream = 4 }, + { .stream = 14 }, + { .stream = 6 }, + { .stream = 10 }, + { .stream = 8 }, +}; + +#define DMA_0_ISR isr_dma1_stream4 +#define DMA_1_ISR isr_dma2_stream6 +#define DMA_2_ISR isr_dma1_stream6 +#define DMA_3_ISR isr_dma2_stream2 +#define DMA_4_ISR isr_dma2_stream0 + +#define DMA_NUMOF (sizeof(dma_config) / sizeof(dma_config[0])) +#endif +/** @} */ + /** * @name Timer configuration * @{ @@ -104,9 +127,9 @@ static const uart_conf_t uart_config[] = { .tx_af = GPIO_AF7, .bus = APB1, .irqn = USART3_IRQn, -#ifdef UART_USE_DMA - .dma_stream = 6, - .dma_chan = 4 +#ifdef MODULE_PERIPH_DMA + .dma = 0, + .dma_chan = 7, #endif }, { @@ -118,9 +141,9 @@ static const uart_conf_t uart_config[] = { .tx_af = GPIO_AF8, .bus = APB2, .irqn = USART6_IRQn, -#ifdef UART_USE_DMA - .dma_stream = 5, - .dma_chan = 4 +#ifdef MODULE_PERIPH_DMA + .dma = 1, + .dma_chan = 5, #endif }, { @@ -132,9 +155,9 @@ static const uart_conf_t uart_config[] = { .tx_af = GPIO_AF7, .bus = APB1, .irqn = USART2_IRQn, -#ifdef UART_USE_DMA - .dma_stream = 4, - .dma_chan = 4 +#ifdef MODULE_PERIPH_DMA + .dma = 3, + .dma_chan = 4, #endif }, }; @@ -212,7 +235,13 @@ static const spi_conf_t spi_config[] = { .cs_pin = GPIO_PIN(PORT_A, 4), .af = GPIO_AF5, .rccmask = RCC_APB2ENR_SPI1EN, - .apbbus = APB2 + .apbbus = APB2, +#ifdef MODULE_PERIPH_DMA + .tx_dma = 3, + .tx_dma_chan = 2, + .rx_dma = 4, + .rx_dma_chan = 3, +#endif } }; diff --git a/cpu/stm32_common/cpu_init.c b/cpu/stm32_common/cpu_init.c index d1a0bfc76a..c11866217a 100644 --- a/cpu/stm32_common/cpu_init.c +++ b/cpu/stm32_common/cpu_init.c @@ -3,6 +3,7 @@ * 2014 Freie Universität Berlin * 2016 TriaGnoSys GmbH * 2018 Kaspar Schleiser + * 2018 OTA keys S.A. * * * This file is subject to the terms and conditions of the GNU Lesser General @@ -24,6 +25,7 @@ * @author Nick van IJzendoorn * @author Víctor Ariño * @author Kaspar Schleiser + * @author Vincent Dupont * * @} */ @@ -47,6 +49,10 @@ void cpu_init(void) periph_clk_en(APB1, BIT_APB_PWREN); /* initialize the system clock as configured in the periph_conf.h */ stmclk_init_sysclk(); +#ifdef MODULE_PERIPH_DMA + /* initialize DMA streams */ + dma_init(); +#endif /* trigger static peripheral initialization */ periph_init(); } diff --git a/cpu/stm32_common/include/periph_cpu_common.h b/cpu/stm32_common/include/periph_cpu_common.h index 9eee755469..56eac8b6d1 100644 --- a/cpu/stm32_common/include/periph_cpu_common.h +++ b/cpu/stm32_common/include/periph_cpu_common.h @@ -218,6 +218,49 @@ typedef enum { #endif /* ndef DOXYGEN */ #endif /* ndef CPU_FAM_STM32F1 */ +#ifdef MODULE_PERIPH_DMA +/** + * @brief DMA configuration + */ +typedef struct { + int stream; /**< DMA stream */ +} dma_conf_t; + +/** + * @brief DMA type + */ +typedef unsigned dma_t; + +/** + * @brief DMA modes + */ +typedef enum { + DMA_PERIPH_TO_MEM, /**< Peripheral to memory */ + DMA_MEM_TO_PERIPH, /**< Memory to peripheral */ + DMA_MEM_TO_MEM, /**< Memory to memory */ +} dma_mode_t; + +/** + * @name DMA Increment modes + * @{ + */ +#define DMA_INC_SRC_ADDR (0x01) +#define DMA_INC_DST_ADDR (0x02) +#define DMA_INC_BOTH_ADDR (DMA_INC_SRC_ADDR | DMA_INC_DST_ADDR) +/** @} */ + +/** + * @name DMA data width + * @{ + */ +#define DMA_DATA_WIDTH_BYTE (0x00) +#define DMA_DATA_WIDTH_HALF_WORD (0x04) +#define DMA_DATA_WIDTH_WORD (0x08) +#define DMA_DATA_WIDTH_MASK (0x0C) +#define DMA_DATA_WIDTH_SHIFT (2) +/** @} */ +#endif /* MODULE_PERIPH_DMA */ + /** * @brief DAC line configuration data */ @@ -293,8 +336,8 @@ typedef struct { #endif uint8_t bus; /**< APB bus */ uint8_t irqn; /**< IRQ channel */ -#if 0 /* TODO */ - uint8_t dma_stream; /**< DMA stream used for TX */ +#ifdef MODULE_PERIPH_DMA + dma_t dma; /**< Logical DMA stream used for TX */ uint8_t dma_chan; /**< DMA channel used for TX */ #endif #ifdef MODULE_STM32_PERIPH_UART_HW_FC @@ -321,8 +364,15 @@ typedef struct { #endif uint32_t rccmask; /**< bit in the RCC peripheral enable register */ uint8_t apbbus; /**< APBx bus the device is connected to */ +#ifdef MODULE_PERIPH_DMA + dma_t tx_dma; /**< Logical DMA stream used for TX */ + uint8_t tx_dma_chan; /**< DMA channel used for TX */ + dma_t rx_dma; /**< Logical DMA stream used for RX */ + uint8_t rx_dma_chan; /**< DMA channel used for RX */ +#endif } spi_conf_t; + /** * @brief Get the actual bus clock frequency for the APB buses * @@ -372,6 +422,247 @@ void gpio_init_af(gpio_t pin, gpio_af_t af); */ void gpio_init_analog(gpio_t pin); +#ifdef MODULE_PERIPH_DMA +/** + * @brief DMA stream not defined + */ +#define DMA_STREAM_UNDEF (UINT_MAX) + +/** + * @brief Initialize DMA + */ +void dma_init(void); + +/** + * @brief Execute a DMA transfer + * + * This function blocks until the transfer is completed. This is a convenience + * function which configure, start, wait and stop a DMA transfer. + * + * @param[in] dma logical DMA stream + * @param[in] chan DMA channel + * @param[in] src source buffer + * @param[out] dst destination buffer + * @param[in] len length to transfer + * @param[in] mode DMA mode + * @param[in] flags DMA configuration + * + * @return < 0 on error, the number of transfered bytes otherwise + */ +int dma_transfer(dma_t dma, int chan, const void *src, void *dst, size_t len, + dma_mode_t mode, uint8_t flags); + +/** + * @brief Acquire a DMA stream + * + * @param[in] dma logical DMA stream + */ +void dma_acquire(dma_t dma); + +/** + * @brief Release a DMA stream + * + * @param[in] dma logical DMA stream + */ +void dma_release(dma_t dma); + +/** + * @brief Start a DMA transfer on a stream + * + * Start a DMA transfer on a given stream. The stream must be configured first + * by a @p dma_configure call. + * + * @param[in] dma logical DMA stream + */ +void dma_start(dma_t dma); + +/** + * @brief Suspend a DMA transfer on a stream + * + * @param[in] dma logical DMA stream + * + * @return the remaining number of bytes to transfer + */ +uint16_t dma_suspend(dma_t dma); + +/** + * @brief Resume a suspended DMA transfer on a stream + * + * @param[in] dma logical DMA stream + * @param[in] reamaining the remaining number of bytes to transfer + */ +void dma_resume(dma_t dma, uint16_t remaining); + +/** + * @brief Stop a DMA transfer on a stream + * + * @param[in] dma logical DMA stream + */ +void dma_stop(dma_t dma); + +/** + * @brief Wait for the end of a transfer + * + * @param[in] dma logical DMA stream + */ +void dma_wait(dma_t dma); + +/** + * @brief Configure a DMA stream for a new transfer + * + * @param[in] dma logical DMA stream + * @param[in] chan DMA channel + * @param[in] src source buffer + * @param[out] dst destination buffer + * @param[in] len length to transfer + * @param[in] mode DMA mode + * @param[in] flags DMA configuration + * + * @return < 0 on error, 0 on success + */ +int dma_configure(dma_t dma, int chan, const void *src, void *dst, size_t len, + dma_mode_t mode, uint8_t flags); + +/** + * @brief Get DMA base register + * + * For simplifying DMA stream handling, we map the DMA channels transparently to + * one integer number, such that DMA1 stream0 equals 0, DMA2 stream0 equals 8, + * DMA2 stream 7 equals 15 and so on. + * + * @param[in] stream physical DMA stream + */ +static inline DMA_TypeDef *dma_base(int stream) +{ + return (stream < 8) ? DMA1 : DMA2; +} + +/** + * @brief Power on the DMA device the given stream belongs to + * + * @param[in] stream physical DMA stream + */ +static inline void dma_poweron(int stream) +{ + if (stream < 8) { + periph_clk_en(AHB1, RCC_AHB1ENR_DMA1EN); + } + else { + periph_clk_en(AHB1, RCC_AHB1ENR_DMA2EN); + } +} + +/** + * @brief Get the DMA stream base address + * + * @param[in] stream physical DMA stream + * + * @return base address for the selected DMA stream + */ +static inline DMA_Stream_TypeDef *dma_stream(int stream) +{ + uint32_t base = (uint32_t)dma_base(stream); + + return (DMA_Stream_TypeDef *)(base + (0x10 + (0x18 * (stream & 0x7)))); +} + +/** + * @brief Select high or low DMA interrupt register based on stream number + * + * @param[in] stream physical DMA stream + * + * @return 0 for streams 0-3, 1 for streams 3-7 + */ +static inline int dma_hl(int stream) +{ + return ((stream & 0x4) >> 2); +} + +/** + * @brief Get the interrupt flag clear bit position in the DMA LIFCR register + * + * @param[in] stream physical DMA stream + */ +static inline uint32_t dma_ifc(int stream) +{ + switch (stream & 0x3) { + case 0: + return (1 << 5); + case 1: + return (1 << 11); + case 2: + return (1 << 21); + case 3: + return (1 << 27); + default: + return 0; + } +} + +/** + * @brief Enable the interrupt of a given stream + * + * @param[in] stream physical DMA stream + */ +static inline void dma_isr_enable(int stream) +{ + if (stream < 7) { + NVIC_EnableIRQ((IRQn_Type)((int)DMA1_Stream0_IRQn + stream)); + } + else if (stream == 7) { + NVIC_EnableIRQ(DMA1_Stream7_IRQn); + } + else if (stream < 13) { + NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream0_IRQn + (stream - 8))); + } + else if (stream < 16) { + NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream5_IRQn + (stream - 13))); + } +} + +/** + * @brief Disable the interrupt of a given stream + * + * @param[in] stream physical DMA stream + */ +static inline void dma_isr_disable(int stream) +{ + if (stream < 7) { + NVIC_DisableIRQ((IRQn_Type)((int)DMA1_Stream0_IRQn + stream)); + } + else if (stream == 7) { + NVIC_DisableIRQ(DMA1_Stream7_IRQn); + } + else if (stream < 13) { + NVIC_DisableIRQ((IRQn_Type)((int)DMA2_Stream0_IRQn + (stream - 8))); + } + else if (stream < 16) { + NVIC_DisableIRQ((IRQn_Type)((int)DMA2_Stream5_IRQn + (stream - 13))); + } +} + +/** + * @brief Clear the interrupt of a given stream + * + * @param[in] stream physical DMA stream + */ +static inline void dma_isr_clear(int stream) +{ + if (stream < 7) { + NVIC_ClearPendingIRQ((IRQn_Type)((int)DMA1_Stream0_IRQn + stream)); + } + else if (stream == 7) { + NVIC_ClearPendingIRQ((IRQn_Type)DMA1_Stream7_IRQn); + } + else if (stream < 13) { + NVIC_ClearPendingIRQ((IRQn_Type)((int)DMA2_Stream0_IRQn + (stream - 8))); + } + else if (stream < 16) { + NVIC_ClearPendingIRQ((IRQn_Type)((int)DMA2_Stream5_IRQn + (stream - 13))); + } +} +#endif /* MODULE_PERIPH_DMA */ + #ifdef __cplusplus } #endif diff --git a/cpu/stm32_common/periph/dma.c b/cpu/stm32_common/periph/dma.c new file mode 100644 index 0000000000..dc971b09b6 --- /dev/null +++ b/cpu/stm32_common/periph/dma.c @@ -0,0 +1,306 @@ +/* + * Copyright (C) 2017 OTA keys S.A. + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup cpu_stm32_common + * @{ + * + * @file + * @brief Low-level DMA driver implementation + * + * @author Vincent Dupont + * + * @} + */ + +#include + +#include "periph_cpu.h" +#include "periph_conf.h" +#include "mutex.h" +#include "assert.h" + +#if !(defined(CPU_FAM_STM32F2) || defined(CPU_FAM_STM32F4) || defined(CPU_FAM_STM32F7)) +#error "DMA is not supported for target CPU" +#endif + +#define DMA_STREAM_IT_MASK (DMA_LISR_FEIF0 | DMA_LISR_DMEIF0 | \ + DMA_LISR_TEIF0 | DMA_LISR_HTIF0 | \ + DMA_LISR_TCIF0) + +struct dma_ctx { + mutex_t conf_lock; + mutex_t sync_lock; + uint16_t len; +}; + +static struct dma_ctx dma_ctx[DMA_NUMOF]; + +static inline uint32_t dma_all_flags(dma_t dma) +{ + assert(dma < DMA_NUMOF); + + switch (dma_config[dma].stream & 0x3) { + case 0: /* 0 and 4 */ + return (DMA_STREAM_IT_MASK); + case 1: /* 1 and 5 */ + return (DMA_STREAM_IT_MASK << 6); + case 2: /* 2 and 6 */ + return (DMA_STREAM_IT_MASK << 16); + case 3: /* 3 and 7 */ + return (DMA_STREAM_IT_MASK << 22); + default: + return 0; + } +} + +static void dma_clear_all_flags(dma_t dma) +{ + assert(dma < DMA_NUMOF); + + DMA_TypeDef *stream = dma_base(dma_config[dma].stream); + + /* Clear all flags */ + if (dma_hl(dma_config[dma].stream) == 0) { + stream->LIFCR = dma_all_flags(dma); + } + else { + stream->HIFCR = dma_all_flags(dma); + } +} + + +void dma_init(void) +{ + for (unsigned i = 0; i < DMA_NUMOF; i++) { + mutex_init(&dma_ctx[i].conf_lock); + mutex_init(&dma_ctx[i].sync_lock); + mutex_lock(&dma_ctx[i].sync_lock); + } +} + +int dma_transfer(dma_t dma, int chan, const void *src, void *dst, size_t len, + dma_mode_t mode, uint8_t flags) +{ + int ret = dma_configure(dma, chan, src, dst, len, mode, flags); + if (ret != 0) { + return ret; + } + dma_start(dma); + dma_wait(dma); + dma_stop(dma); + + return len; +} + +void dma_acquire(dma_t dma) +{ + assert(dma < DMA_NUMOF); + + mutex_lock(&dma_ctx[dma].conf_lock); +} + +void dma_release(dma_t dma) +{ + assert(dma < DMA_NUMOF); + + mutex_unlock(&dma_ctx[dma].conf_lock); +} + +int dma_configure(dma_t dma, int chan, const void *src, void *dst, size_t len, + dma_mode_t mode, uint8_t flags) +{ + assert(src != NULL); + assert(dst != NULL); + assert(dma < DMA_NUMOF); + + int stream_n = dma_config[dma].stream; + uint32_t inc_periph; + uint32_t inc_mem; + + DMA_Stream_TypeDef *stream = dma_stream(stream_n); + dma_poweron(stream_n); + dma_clear_all_flags(dma); + + switch (mode) { + case DMA_MEM_TO_MEM: + case DMA_PERIPH_TO_MEM: + stream->PAR = (uint32_t)src; + stream->M0AR = (uint32_t)dst; + inc_periph = (flags & DMA_INC_SRC_ADDR); + inc_mem = (flags & DMA_INC_DST_ADDR) >> 1; + break; + case DMA_MEM_TO_PERIPH: + stream->PAR = (uint32_t)dst; + stream->M0AR = (uint32_t)src; + inc_periph = (flags & DMA_INC_DST_ADDR) >> 1; + inc_mem = (flags & DMA_INC_SRC_ADDR); + break; + default: + return -1; + } + + uint32_t width = (flags & DMA_DATA_WIDTH_MASK) >> DMA_DATA_WIDTH_SHIFT; + /* Set channel, data width, inc and mode */ + stream->CR = (chan & 0xF) << DMA_SxCR_CHSEL_Pos | + width << DMA_SxCR_MSIZE_Pos | width << DMA_SxCR_PSIZE_Pos | + inc_periph << DMA_SxCR_PINC_Pos | inc_mem << DMA_SxCR_MINC_Pos | + (mode & 3) << DMA_SxCR_DIR_Pos; + /* Enable interrupts */ + stream->CR |= DMA_SxCR_TCIE | DMA_SxCR_TEIE; + /* Configure FIFO */ + stream->FCR = 0; + + /* Set length */ + stream->NDTR = len; + dma_ctx[dma].len = len; + + dma_isr_enable(stream_n); + + return 0; +} + +void dma_start(dma_t dma) +{ + assert(dma < DMA_NUMOF); + + DMA_Stream_TypeDef *stream = dma_stream(dma_config[dma].stream); + + stream->CR |= DMA_SxCR_EN; +} + +uint16_t dma_suspend(dma_t dma) +{ + assert(dma < DMA_NUMOF); + + int stream_n = dma_config[dma].stream; + DMA_Stream_TypeDef *stream = dma_stream(stream_n); + uint16_t left = 0; + + if ((stream->CR & DMA_SxCR_EN) == DMA_SxCR_EN) { + dma_isr_disable(stream_n); + stream->CR &= ~(uint32_t)DMA_SxCR_EN; + while ((stream->CR & DMA_SxCR_EN) == DMA_SxCR_EN) {} + dma_clear_all_flags(dma); + left = stream->NDTR; + dma_isr_clear(stream_n); + } + return left; + +} + +void dma_resume(dma_t dma, uint16_t remaining) +{ + assert(dma < DMA_NUMOF); + + int stream_n = dma_config[dma].stream; + DMA_Stream_TypeDef *stream = dma_stream(stream_n); + + if (remaining > 0) { + dma_isr_enable(stream_n); + stream->NDTR = remaining; + stream->M0AR += dma_ctx[dma].len - remaining; + dma_ctx[dma].len = remaining; + stream->CR |= (uint32_t)DMA_SxCR_EN; + } +} + +void dma_stop(dma_t dma) +{ + assert(dma < DMA_NUMOF); + + DMA_Stream_TypeDef *stream = dma_stream(dma_config[dma].stream); + + stream->CR &= ~(uint32_t)DMA_SxCR_EN; +} + +void dma_wait(dma_t dma) +{ + assert(dma < DMA_NUMOF); + + mutex_lock(&dma_ctx[dma].sync_lock); +} + +void dma_isr_handler(dma_t dma) +{ + dma_clear_all_flags(dma); + + mutex_unlock(&dma_ctx[dma].sync_lock); + + cortexm_isr_end(); +} + +#ifdef DMA_0_ISR +void DMA_0_ISR(void) +{ + dma_isr_handler(0); +} +#endif + +#ifdef DMA_1_ISR +void DMA_1_ISR(void) +{ + dma_isr_handler(1); +} +#endif + +#ifdef DMA_2_ISR +void DMA_2_ISR(void) +{ + dma_isr_handler(2); +} +#endif + +#ifdef DMA_3_ISR +void DMA_3_ISR(void) +{ + dma_isr_handler(3); +} +#endif + +#ifdef DMA_4_ISR +void DMA_4_ISR(void) +{ + dma_isr_handler(4); +} +#endif + +#ifdef DMA_5_ISR +void DMA_5_ISR(void) +{ + dma_isr_handler(5); +} +#endif + +#ifdef DMA_6_ISR +void DMA_6_ISR(void) +{ + dma_isr_handler(6); +} +#endif + +#ifdef DMA_7_ISR +void DMA_7_ISR(void) +{ + dma_isr_handler(7); +} +#endif + +#ifdef DMA_8_ISR +void DMA_8_ISR(void) +{ + dma_isr_handler(8); +} +#endif + +#ifdef DMA_9_ISR +void DMA_9_ISR(void) +{ + dma_isr_handler(9); +} +#endif diff --git a/cpu/stm32_common/periph/spi.c b/cpu/stm32_common/periph/spi.c index 9cc5fc2a5e..8367ccbf6c 100644 --- a/cpu/stm32_common/periph/spi.c +++ b/cpu/stm32_common/periph/spi.c @@ -1,7 +1,7 @@ /* * Copyright (C) 2014 Hamburg University of Applied Sciences * 2014-2017 Freie Universität Berlin - * 2016 OTA keys S.A. + * 2016-2017 OTA keys S.A. * * This file is subject to the terms and conditions of the GNU Lesser * General Public License v2.1. See the file LICENSE in the top level @@ -152,24 +152,65 @@ void spi_release(spi_t bus) mutex_unlock(&locks[bus]); } -void spi_transfer_bytes(spi_t bus, spi_cs_t cs, bool cont, - const void *out, void *in, size_t len) +static inline void _wait_for_end(spi_t bus) +{ + /* make sure the transfer is completed before continuing, see reference + * manual(s) -> section 'Disabling the SPI' */ + while (!(dev(bus)->SR & SPI_SR_TXE)) {} + while (dev(bus)->SR & SPI_SR_BSY) {} +} + +#ifdef MODULE_PERIPH_DMA +static void _transfer_dma(spi_t bus, const void *out, void *in, size_t len) +{ + uint8_t tmp = 0; + dma_acquire(spi_config[bus].tx_dma); + dma_acquire(spi_config[bus].rx_dma); + + if (!out) { + dma_configure(spi_config[bus].tx_dma, spi_config[bus].tx_dma_chan, &tmp, + (void *)&(dev(bus)->DR), len, DMA_MEM_TO_PERIPH, 0); + } + else { + dma_configure(spi_config[bus].tx_dma, spi_config[bus].tx_dma_chan, out, + (void *)&(dev(bus)->DR), len, DMA_MEM_TO_PERIPH, DMA_INC_SRC_ADDR); + } + if (!in) { + dma_configure(spi_config[bus].rx_dma, spi_config[bus].rx_dma_chan, + (void *)&(dev(bus)->DR), &tmp, len, DMA_PERIPH_TO_MEM, 0); + } + else { + dma_configure(spi_config[bus].rx_dma, spi_config[bus].rx_dma_chan, + (void *)&(dev(bus)->DR), in, len, DMA_PERIPH_TO_MEM, DMA_INC_DST_ADDR); + } + dev(bus)->CR2 |= SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN; + + dma_start(spi_config[bus].rx_dma); + dma_start(spi_config[bus].tx_dma); + + dma_wait(spi_config[bus].rx_dma); + dma_wait(spi_config[bus].tx_dma); + + dev(bus)->CR2 &= ~(SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + + dma_stop(spi_config[bus].tx_dma); + dma_stop(spi_config[bus].rx_dma); + + dma_release(spi_config[bus].tx_dma); + dma_release(spi_config[bus].rx_dma); + + _wait_for_end(bus); +} +#endif + +static void _transfer_no_dma(spi_t bus, const void *out, void *in, size_t len) { const uint8_t *outbuf = out; uint8_t *inbuf = in; - /* make sure at least one input or one output buffer is given */ - assert(outbuf || inbuf); - /* we need to recast the data register to uint_8 to force 8-bit access */ volatile uint8_t *DR = (volatile uint8_t*)&(dev(bus)->DR); - /* active the given chip select line */ - dev(bus)->CR1 |= (SPI_CR1_SPE); /* this pulls the HW CS line low */ - if ((cs != SPI_HWCS_MASK) && (cs != SPI_CS_UNDEF)) { - gpio_clear((gpio_t)cs); - } - /* transfer data, use shortpath if only sending data */ if (!inbuf) { for (size_t i = 0; i < len; i++) { @@ -200,10 +241,32 @@ void spi_transfer_bytes(spi_t bus, spi_cs_t cs, bool cont, } } - /* make sure the transfer is completed before continuing, see reference - * manual(s) -> section 'Disabling the SPI' */ - while (!(dev(bus)->SR & SPI_SR_TXE)) {} - while (dev(bus)->SR & SPI_SR_BSY) {} + _wait_for_end(bus); +} + +void spi_transfer_bytes(spi_t bus, spi_cs_t cs, bool cont, + const void *out, void *in, size_t len) +{ + /* make sure at least one input or one output buffer is given */ + assert(out || in); + + /* active the given chip select line */ + dev(bus)->CR1 |= (SPI_CR1_SPE); /* this pulls the HW CS line low */ + if ((cs != SPI_HWCS_MASK) && (cs != SPI_CS_UNDEF)) { + gpio_clear((gpio_t)cs); + } + +#ifdef MODULE_PERIPH_DMA + if (spi_config[bus].tx_dma != DMA_STREAM_UNDEF + && spi_config[bus].rx_dma != DMA_STREAM_UNDEF) { + _transfer_dma(bus, out, in, len); + } + else { +#endif + _transfer_no_dma(bus, out, in, len); +#ifdef MODULE_PERIPH_DMA + } +#endif /* release the chip select if not specified differently */ if ((!cont) && (cs != SPI_CS_UNDEF)) { diff --git a/cpu/stm32_common/periph/uart.c b/cpu/stm32_common/periph/uart.c index 2c67d35d79..54adaea1d0 100644 --- a/cpu/stm32_common/periph/uart.c +++ b/cpu/stm32_common/periph/uart.c @@ -118,24 +118,21 @@ int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg) return UART_OK; } -void uart_write(uart_t uart, const uint8_t *data, size_t len) +static inline void send_byte(uart_t uart, uint8_t byte) { - assert(uart < UART_NUMOF); - - for (size_t i = 0; i < len; i++) { #if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32L0) \ || defined(CPU_FAM_STM32F3) || defined(CPU_FAM_STM32L4) \ || defined(CPU_FAM_STM32F7) - while (!(dev(uart)->ISR & USART_ISR_TXE)) {} - dev(uart)->TDR = data[i]; + while (!(dev(uart)->ISR & USART_ISR_TXE)) {} + dev(uart)->TDR = byte; #else - while (!(dev(uart)->SR & USART_SR_TXE)) {} - dev(uart)->DR = data[i]; + while (!(dev(uart)->SR & USART_SR_TXE)) {} + dev(uart)->DR = byte; #endif - } +} - /* make sure the function is synchronous by waiting for the transfer to - * finish */ +static inline void wait_for_tx_complete(uart_t uart) +{ #if defined(CPU_FAM_STM32F0) || defined(CPU_FAM_STM32L0) \ || defined(CPU_FAM_STM32F3) || defined(CPU_FAM_STM32L4) \ || defined(CPU_FAM_STM32F7) @@ -145,6 +142,57 @@ void uart_write(uart_t uart, const uint8_t *data, size_t len) #endif } +void uart_write(uart_t uart, const uint8_t *data, size_t len) +{ + assert(uart < UART_NUMOF); + +#ifdef MODULE_PERIPH_DMA + if (!len) { + return; + } + if (uart_config[uart].dma != DMA_STREAM_UNDEF) { + if (irq_is_in()) { + uint16_t todo = 0; + if (dev(uart)->CR3 & USART_CR3_DMAT) { + /* DMA transfer for UART on-going */ + todo = dma_suspend(uart_config[uart].dma); + } + if (todo) { + dma_stop(uart_config[uart].dma); + dev(uart)->CR3 &= ~USART_CR3_DMAT; + } + for (unsigned i = 0; i < len; i++) { + send_byte(uart, data[i]); + } + if (todo > 0) { + wait_for_tx_complete(uart); + dev(uart)->CR3 |= USART_CR3_DMAT; + dma_resume(uart_config[uart].dma, todo); + } + } + else { + dma_acquire(uart_config[uart].dma); + dev(uart)->CR3 |= USART_CR3_DMAT; + dma_transfer(uart_config[uart].dma, uart_config[uart].dma_chan, data, + (void *)&dev(uart)->DR, len, DMA_MEM_TO_PERIPH, DMA_INC_SRC_ADDR); + dma_release(uart_config[uart].dma); + + /* make sure the function is synchronous by waiting for the transfer to + * finish */ + wait_for_tx_complete(uart); + dev(uart)->CR3 &= ~USART_CR3_DMAT; + } + return; + } +#endif + for (size_t i = 0; i < len; i++) { + send_byte(uart, data[i]); + } + /* make sure the function is synchronous by waiting for the transfer to + * finish */ + wait_for_tx_complete(uart); +} + void uart_poweron(uart_t uart) { assert(uart < UART_NUMOF); diff --git a/cpu/stm32f2/include/periph_cpu.h b/cpu/stm32f2/include/periph_cpu.h index 56d50efd57..a45254b11e 100644 --- a/cpu/stm32f2/include/periph_cpu.h +++ b/cpu/stm32f2/include/periph_cpu.h @@ -76,101 +76,6 @@ typedef enum { } adc_res_t; /** @} */ -/** - * @brief Power on the DMA device the given stream belongs to - * - * @param[in] stream logical DMA stream - */ -static inline void dma_poweron(int stream) -{ - if (stream < 8) { - periph_clk_en(AHB1, RCC_AHB1ENR_DMA1EN); - } else { - periph_clk_en(AHB1, RCC_AHB1ENR_DMA2EN); - } -} - -/** - * @brief Get DMA base register - * - * For simplifying DMA stream handling, we map the DMA channels transparently to - * one integer number, such that DMA1 stream0 equals 0, DMA2 stream0 equals 8, - * DMA2 stream 7 equals 15 and so on. - * - * @param[in] stream logical DMA stream - */ -static inline DMA_TypeDef *dma_base(int stream) -{ - return (stream < 8) ? DMA1 : DMA2; -} - -/** - * @brief Get the DMA stream base address - * - * @param[in] stream logical DMA stream - * - * @return base address for the selected DMA stream - */ -static inline DMA_Stream_TypeDef *dma_stream(int stream) -{ - uint32_t base = (uint32_t)dma_base(stream); - return (DMA_Stream_TypeDef *)(base + (0x10 + (0x18 * (stream & 0x7)))); -} - -/** - * @brief Select high or low DMA interrupt register based on stream number - * - * @param[in] stream logical DMA stream - * - * @return 0 for streams 0-3, 1 for streams 3-7 - */ -static inline int dma_hl(int stream) -{ - return ((stream & 0x4) >> 2); -} - -/** - * @brief Get the interrupt flag clear bit position in the DMA LIFCR register - * - * @param[in] stream logical DMA stream - */ -static inline uint32_t dma_ifc(int stream) -{ - switch (stream & 0x3) { - case 0: /* 0 and 4 */ - return (1 << 5); - case 1: /* 1 and 5 */ - return (1 << 11); - case 2: /* 2 and 6 */ - return (1 << 21); - case 3: /* 3 and 7 */ - return (1 << 27); - default: - return 0; - } -} - -/** - * @brief Enable DMA interrupts - * - * @param[in] stream logical DMA stream - */ -static inline void dma_isr_enable(int stream) -{ - if (stream < 7) { - NVIC_EnableIRQ((IRQn_Type)((int)DMA1_Stream0_IRQn + stream)); - } - else if (stream == 7) { - NVIC_EnableIRQ(DMA1_Stream7_IRQn); - } - else if (stream < 13) { - NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream0_IRQn + (stream - 8))); - } - else if (stream < 16) { - NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream5_IRQn + (stream - 13))); - } -} - #ifdef __cplusplus } #endif diff --git a/cpu/stm32f4/include/periph_cpu.h b/cpu/stm32f4/include/periph_cpu.h index 736356e1e6..7f86e972d1 100644 --- a/cpu/stm32f4/include/periph_cpu.h +++ b/cpu/stm32f4/include/periph_cpu.h @@ -89,98 +89,6 @@ typedef struct { uint8_t chan; /**< CPU ADC channel connected to the pin */ } adc_conf_t; -/** - * @brief Power on the DMA device the given stream belongs to - * - * @param[in] stream logical DMA stream - */ -static inline void dma_poweron(int stream) -{ - if (stream < 8) { - periph_clk_en(AHB1, RCC_AHB1ENR_DMA1EN); - } - else { - periph_clk_en(AHB1, RCC_AHB1ENR_DMA2EN); - } -} - -/** - * @brief Get DMA base register - * - * For simplifying DMA stream handling, we map the DMA channels transparently to - * one integer number, such that DMA1 stream0 equals 0, DMA2 stream0 equals 8, - * DMA2 stream 7 equals 15 and so on. - * - * @param[in] stream logical DMA stream - */ -static inline DMA_TypeDef *dma_base(int stream) -{ - return (stream < 8) ? DMA1 : DMA2; -} - -/** - * @brief Get the DMA stream base address - * - * @param[in] stream logical DMA stream - * - * @return base address for the selected DMA stream - */ -static inline DMA_Stream_TypeDef *dma_stream(int stream) -{ - uint32_t base = (uint32_t)dma_base(stream); - - return (DMA_Stream_TypeDef *)(base + (0x10 + (0x18 * (stream & 0x7)))); -} - -/** - * @brief Select high or low DMA interrupt register based on stream number - * - * @param[in] stream logical DMA stream - * - * @return 0 for streams 0-3, 1 for streams 3-7 - */ -static inline int dma_hl(int stream) -{ - return ((stream & 0x4) >> 2); -} - -/** - * @brief Get the interrupt flag clear bit position in the DMA LIFCR register - * - * @param[in] stream logical DMA stream - */ -static inline uint32_t dma_ifc(int stream) -{ - switch (stream & 0x3) { - case 0: - return (1 << 5); - case 1: - return (1 << 11); - case 2: - return (1 << 21); - case 3: - return (1 << 27); - default: - return 0; - } -} - -static inline void dma_isr_enable(int stream) -{ - if (stream < 7) { - NVIC_EnableIRQ((IRQn_Type)((int)DMA1_Stream0_IRQn + stream)); - } - else if (stream == 7) { - NVIC_EnableIRQ(DMA1_Stream7_IRQn); - } - else if (stream < 13) { - NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream0_IRQn + (stream - 8))); - } - else if (stream < 16) { - NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream5_IRQn + (stream - 13))); - } -} - #ifdef __cplusplus } #endif diff --git a/tests/periph_dma/Makefile b/tests/periph_dma/Makefile new file mode 100644 index 0000000000..9b750d5074 --- /dev/null +++ b/tests/periph_dma/Makefile @@ -0,0 +1,5 @@ +include ../Makefile.tests_common + +FEATURES_REQUIRED = periph_dma + +include $(RIOTBASE)/Makefile.include diff --git a/tests/periph_dma/main.c b/tests/periph_dma/main.c new file mode 100644 index 0000000000..c297ce8b9a --- /dev/null +++ b/tests/periph_dma/main.c @@ -0,0 +1,27 @@ +/* + * Copyright (C) 2018 OTA keys S.A. + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup tests + * @{ + * + * @file + * @brief Dummy test application for DMA peripheral + * + * @author Vincent Dupont + * @} + */ + +#include + +int main(void) +{ + puts("DMA dummy test app"); + + return 0; +}