summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f40xxx_dma.h72
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h8
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_allocateheap.c2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_dma.c558
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_dma.h16
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c610
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c662
8 files changed, 1335 insertions, 595 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 95d8d02b1..a81a10e8d 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2245,3 +2245,5 @@
6.13 2012-xx-xx Gregory Nutt <gnutt@nuttx.org>
+ * arch/arm/src/stm32/stm32f40xxx_dma.c: Add DMA support for the STM32 F4
+ family (untested on initial check-in) \ No newline at end of file
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_dma.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_dma.h
index 3f97b3fd2..786530599 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_dma.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_dma.h
@@ -270,52 +270,32 @@
/* Register Bitfield Definitions ****************************************************/
-#define DMA_STREAM_MASK 0x3f
-#define DMA_STREAM_FEIF_BIT (1 << 0) /* Bit 0: Stream FIFO error interrupt flag */
-#define DMA_STREAM_DMEIF_BIT (1 << 2) /* Bit 2: Stream direct mode error interrupt flag */
-#define DMA_STREAM_TEIF_BIT (1 << 3) /* Bit 3: Stream Transfer Error flag */
-#define DMA_STREAM_HTIF_BIT (1 << 4) /* Bit 4: Stream Half Transfer flag */
-#define DMA_STREAM_TCIF_BIT (1 << 5) /* Bit 5: Stream Transfer Complete flag */
-
-/* DMA interrupt status register */
-
-#define DMA_LISR_STREAM0_SHIFT (0) /* Bits 0-5: DMA Stream 0 interrupt status */
-#define DMA_LISR_STREAM0_MASK (DMA_STREAM_MASK << DMA_LISR_STREAM0_SHIFT)
-#define DMA_LISR_STREAM1_SHIFT (6) /* Bits 6-11: DMA Stream 1 interrupt status */
-#define DMA_LISR_STREAM1_MASK (DMA_STREAM_MASK << DMA_LISR_STREAM1_SHIFT)
-#define DMA_LISR_STREAM2_SHIFT (16) /* Bits 16-21: DMA Stream 2 interrupt status */
-#define DMA_LISR_STREAM2_MASK (DMA_STREAM_MASK << DMA_LISR_STREAM2_SHIFT)
-#define DMA_LISR_STREAM3_SHIFT (22) /* Bits 22-27: DMA Stream 3 interrupt status */
-#define DMA_LISR_STREAM3_MASK (DMA_STREAM_MASK << DMA_LISR_STREAM3_SHIFT)
-
-#define DMA_HISR_STREAM4_SHIFT (0) /* Bits 0-5: DMA Stream 4 interrupt status */
-#define DMA_HISR_STREAM4_MASK (DMA_STREAM_MASK << DMA_HISR_STREAM4_SHIFT)
-#define DMA_HISR_STREAM5_SHIFT (6) /* Bits 6-11: DMA Stream 5 interrupt status */
-#define DMA_HISR_STREAM5_MASK (DMA_STREAM_MASK << DMA_HISR_STREAM5_SHIFT)
-#define DMA_HISR_STREAM6_SHIFT (16) /* Bits 16-21: DMA Stream 6 interrupt status */
-#define DMA_HISR_STREAM6_MASK (DMA_STREAM_MASK << DMA_HISR_STREAM6_SHIFT)
-#define DMA_HISR_STREAM7_SHIFT (22) /* Bits 22-27: DMA Stream 7 interrupt status */
-#define DMA_HISR_STREAM7_MASK (DMA_STREAM_MASK << DMA_HISR_STREAM7_SHIFT)
-
-/* DMA interrupt flag clear register */
-
-#define DMA_LICR_STREAM0_SHIFT (0) /* Bits 0-5: DMA Stream 0 interrupt flag clear */
-#define DMA_LICR_STREAM0_MASK (DMA_STREAM_MASK << DMA_LICR_STREAM0_SHIFT)
-#define DMA_LICR_STREAM1_SHIFT (6) /* Bits 6-11: DMA Stream 1 interrupt flag clear */
-#define DMA_LICR_STREAM1_MASK (DMA_STREAM_MASK << DMA_LICR_STREAM1_SHIFT)
-#define DMA_LICR_STREAM2_SHIFT (16) /* Bits 16-21: DMA Stream 2 interrupt flag clear */
-#define DMA_LICR_STREAM2_MASK (DMA_STREAM_MASK << DMA_LICR_STREAM2_SHIFT)
-#define DMA_LICR_STREAM3_SHIFT (22) /* Bits 22-27: DMA Stream 3 interrupt flag clear */
-#define DMA_LICR_STREAM3_MASK (DMA_STREAM_MASK << DMA_LICR_STREAM3_SHIFT)
-
-#define DMA_HICR_STREAM4_SHIFT (0) /* Bits 0-5: DMA Stream 4 interrupt flag clear */
-#define DMA_HICR_STREAM4_MASK (DMA_STREAM_MASK << DMA_HICR_STREAM4_SHIFT)
-#define DMA_HICR_STREAM5_SHIFT (6) /* Bits 6-11: DMA Stream 5 interrupt flag clear */
-#define DMA_HICR_STREAM5_MASK (DMA_STREAM_MASK << DMA_HICR_STREAM5_SHIFT)
-#define DMA_HICR_STREAM6_SHIFT (16) /* Bits 16-21: DMA Stream 6 interrupt flag clear */
-#define DMA_HICR_STREAM6_MASK (DMA_STREAM_MASK << DMA_HICR_STREAM6_SHIFT)
-#define DMA_HICR_STREAM7_SHIFT (22) /* Bits 22-27: DMA Stream 7 interrupt flag clear */
-#define DMA_HICR_STREAM7_MASK (DMA_STREAM_MASK << DMA_HICR_STREAM7_SHIFT)
+#define DMA_STREAM_MASK 0x3f
+#define DMA_STREAM_FEIF_BIT (1 << 0) /* Bit 0: Stream FIFO error interrupt flag */
+#define DMA_STREAM_DMEIF_BIT (1 << 2) /* Bit 2: Stream direct mode error interrupt flag */
+#define DMA_STREAM_TEIF_BIT (1 << 3) /* Bit 3: Stream Transfer Error flag */
+#define DMA_STREAM_HTIF_BIT (1 << 4) /* Bit 4: Stream Half Transfer flag */
+#define DMA_STREAM_TCIF_BIT (1 << 5) /* Bit 5: Stream Transfer Complete flag */
+
+/* DMA interrupt status register and interrupt flag clear register field defintions */
+
+#define DMA_INT_STREAM0_SHIFT (0) /* Bits 0-5: DMA Stream 0 interrupt */
+#define DMA_INT_STREAM0_MASK (DMA_STREAM_MASK << DMA_INT_STREAM0_SHIFT)
+#define DMA_INT_STREAM1_SHIFT (6) /* Bits 6-11: DMA Stream 1 interrupt */
+#define DMA_INT_STREAM1_MASK (DMA_STREAM_MASK << DMA_INT_STREAM1_SHIFT)
+#define DMA_INT_STREAM2_SHIFT (16) /* Bits 16-21: DMA Stream 2 interrupt */
+#define DMA_INT_STREAM2_MASK (DMA_STREAM_MASK << DMA_INT_STREAM2_SHIFT)
+#define DMA_INT_STREAM3_SHIFT (22) /* Bits 22-27: DMA Stream 3 interrupt */
+#define DMA_INT_STREAM3_MASK (DMA_STREAM_MASK << DMA_INT_STREAM3_SHIFT)
+
+#define DMA_INT_STREAM4_SHIFT (0) /* Bits 0-5: DMA Stream 4 interrupt */
+#define DMA_INT_STREAM4_MASK (DMA_STREAM_MASK << DMA_INT_STREAM4_SHIFT)
+#define DMA_INT_STREAM5_SHIFT (6) /* Bits 6-11: DMA Stream 5 interrupt */
+#define DMA_INT_STREAM5_MASK (DMA_STREAM_MASK << DMA_INT_STREAM5_SHIFT)
+#define DMA_INT_STREAM6_SHIFT (16) /* Bits 16-21: DMA Stream 6 interrupt */
+#define DMA_INT_STREAM6_MASK (DMA_STREAM_MASK << DMA_INT_STREAM6_SHIFT)
+#define DMA_INT_STREAM7_SHIFT (22) /* Bits 22-27: DMA Stream 7 interrupt */
+#define DMA_INT_STREAM7_MASK (DMA_STREAM_MASK << DMA_INT_STREAM7_SHIFT)
/* DMA stream configuration register */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
index 9ae4220c1..b6b21072a 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
@@ -62,12 +62,12 @@
* The driver will then automatically configre PA11 as the CAN1 RX pin.
*/
-/* Additional effort is required to select specific GPIO options such as frequency,
- * open-drain/push-pull, and pull-up/down!
+/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!!
+ * Additional effort is required to select specific GPIO options such as frequency,
+ * open-drain/push-pull, and pull-up/down! Just the basics are defined for most
+ * pins in this file.
*/
-#warning "Missing logic"
-
/* CAN */
#define GPIO_CAN1_RX_1 (GPIO_ALT|GPIO_AF9|GPIO_PORTA|GPIO_PIN11)
diff --git a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
index 576db4047..b097a9644 100644
--- a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
+++ b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
@@ -43,6 +43,8 @@
#include <debug.h>
#include <nuttx/arch.h>
+#include <nuttx/mm.h>
+
#include <arch/board/board.h>
#include "chip.h"
diff --git a/nuttx/arch/arm/src/stm32/stm32_dma.c b/nuttx/arch/arm/src/stm32/stm32_dma.c
index db492b6b8..a37e284ff 100644
--- a/nuttx/arch/arm/src/stm32/stm32_dma.c
+++ b/nuttx/arch/arm/src/stm32/stm32_dma.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_dma.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,572 +39,40 @@
#include <nuttx/config.h>
-#include <stdint.h>
-#include <stdbool.h>
-#include <semaphore.h>
-#include <debug.h>
-#include <errno.h>
-
-#include <nuttx/irq.h>
-#include <nuttx/arch.h>
-#include <arch/irq.h>
-
-#include "up_arch.h"
-#include "up_internal.h"
-#include "os_internal.h"
#include "chip.h"
-#include "stm32_dma.h"
-#include "stm32_internal.h"
-
-/* Only for the STM32F10xx family for now */
-
-#ifdef CONFIG_STM32_STM32F10XX
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
-#define DMA1_NCHANNELS 7
-#if STM32_NDMA > 1
-# define DMA2_NCHANNELS 5
-# define DMA_NCHANNELS (DMA1_NCHANNELS+DMA2_NCHANNELS)
-#else
-# define DMA_NCHANNELS DMA1_NCHANNELS
-#endif
-
-#ifndef CONFIG_DMA_PRI
-# define CONFIG_DMA_PRI NVIC_SYSH_PRIORITY_DEFAULT
-#endif
-
-/* Convert the DMA channel base address to the DMA register block address */
-
-#define DMA_BASE(ch) (ch & 0xfffffc00)
-
/****************************************************************************
* Private Types
****************************************************************************/
-/* This structure descibes one DMA channel */
-
-struct stm32_dma_s
-{
- uint8_t chan; /* DMA channel number (0-6) */
- uint8_t irq; /* DMA channel IRQ number */
- sem_t sem; /* Used to wait for DMA channel to become available */
- uint32_t base; /* DMA register channel base address */
- dma_callback_t callback; /* Callback invoked when the DMA completes */
- void *arg; /* Argument passed to callback function */
-};
-
/****************************************************************************
* Private Data
****************************************************************************/
-/* This array describes the state of each DMA */
-
-static struct stm32_dma_s g_dma[DMA_NCHANNELS] =
-{
- {
- .chan = 0,
- .irq = STM32_IRQ_DMA1CH1,
- .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(0),
- },
- {
- .chan = 1,
- .irq = STM32_IRQ_DMA1CH2,
- .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(1),
- },
- {
- .chan = 2,
- .irq = STM32_IRQ_DMA1CH3,
- .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(2),
- },
- {
- .chan = 3,
- .irq = STM32_IRQ_DMA1CH4,
- .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(3),
- },
- {
- .chan = 4,
- .irq = STM32_IRQ_DMA1CH5,
- .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(4),
- },
- {
- .chan = 5,
- .irq = STM32_IRQ_DMA1CH6,
- .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(5),
- },
- {
- .chan = 6,
- .irq = STM32_IRQ_DMA1CH7,
- .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(6),
- },
-#if STM32_NDMA > 1
- {
- .chan = 0,
- .irq = STM32_IRQ_DMA2CH1,
- .base = STM32_DMA2_BASE + STM32_DMACHAN_OFFSET(0),
- },
- {
- .chan = 1,
- .irq = STM32_IRQ_DMA2CH2,
- .base = STM32_DMA2_BASE + STM32_DMACHAN_OFFSET(1),
- },
- {
- .chan = 2,
- .irq = STM32_IRQ_DMA2CH3,
- .base = STM32_DMA2_BASE + STM32_DMACHAN_OFFSET(2),
- },
- {
- .chan = 3,
-#ifdef CONFIG_STM32_CONNECTIVITY_LINE
- .irq = STM32_IRQ_DMA2CH4,
-#else
- .irq = STM32_IRQ_DMA2CH45,
-#endif
- .base = STM32_DMA2_BASE + STM32_DMACHAN_OFFSET(3),
- },
- {
- .chan = 4,
-#ifdef CONFIG_STM32_CONNECTIVITY_LINE
- .irq = STM32_IRQ_DMA2CH5,
-#else
- .irq = STM32_IRQ_DMA2CH45,
-#endif
- .base = STM32_DMA2_BASE + STM32_DMACHAN_OFFSET(4),
- },
-#endif
-};
-
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
- * DMA register access functions
- ****************************************************************************/
-
-/* Get non-channel register from DMA1 or DMA2 */
-
-static inline uint32_t dmabase_getreg(struct stm32_dma_s *dmach, uint32_t offset)
-{
- return getreg32(DMA_BASE(dmach->base) + offset);
-}
-
-/* Write to non-channel register in DMA1 or DMA2 */
-
-static inline void dmabase_putreg(struct stm32_dma_s *dmach, uint32_t offset, uint32_t value)
-{
- putreg32(value, DMA_BASE(dmach->base) + offset);
-}
-
-/* Get channel register from DMA1 or DMA2 */
-
-static inline uint32_t dmachan_getreg(struct stm32_dma_s *dmach, uint32_t offset)
-{
- return getreg32(dmach->base + offset);
-}
-
-/* Write to channel register in DMA1 or DMA2 */
-
-static inline void dmachan_putreg(struct stm32_dma_s *dmach, uint32_t offset, uint32_t value)
-{
- putreg32(value, dmach->base + offset);
-}
-
-/************************************************************************************
- * Name: stm32_dmatake() and stm32_dmagive()
- *
- * Description:
- * Used to get exclusive access to a DMA channel.
- *
- ************************************************************************************/
-
-static void stm32_dmatake(FAR struct stm32_dma_s *dmach)
-{
- /* Take the semaphore (perhaps waiting) */
-
- while (sem_wait(&dmach->sem) != 0)
- {
- /* The only case that an error should occur here is if the wait was awakened
- * by a signal.
- */
-
- ASSERT(errno == EINTR);
- }
-}
-
-static inline void stm32_dmagive(FAR struct stm32_dma_s *dmach)
-{
- (void)sem_post(&dmach->sem);
-}
-
-/************************************************************************************
- * Name: stm32_dmachandisable
- *
- * Description:
- * Disable the DMA channel
- *
- ************************************************************************************/
-
-static void stm32_dmachandisable(struct stm32_dma_s *dmach)
-{
- uint32_t regval;
-
- /* Disable all interrupts at the DMA controller */
-
- regval = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET);
- regval &= ~DMA_CCR_ALLINTS;
-
- /* Disable the DMA channel */
-
- regval &= ~DMA_CCR_EN;
- dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, regval);
-
- /* Clear pending channel interrupts */
-
- dmabase_putreg(dmach, STM32_DMA_IFCR_OFFSET, DMA_ISR_CHAN_MASK(dmach->chan));
-}
-
-/************************************************************************************
- * Name: stm32_dmainterrupt
- *
- * Description:
- * DMA interrupt handler
- *
- ************************************************************************************/
-
-static int stm32_dmainterrupt(int irq, void *context)
-{
- struct stm32_dma_s *dmach;
- uint32_t isr;
- int chndx = 0;
-
- /* Get the channel structure from the interrupt number */
-
- if (irq >= STM32_IRQ_DMA1CH1 && irq <= STM32_IRQ_DMA1CH7)
- {
- chndx = irq - STM32_IRQ_DMA1CH1;
- }
- else
-#if STM32_NDMA > 1
-#ifdef CONFIG_STM32_CONNECTIVITY_LINE
- if (irq >= STM32_IRQ_DMA2CH1 && irq <= STM32_IRQ_DMA2CH5)
-#else
- if (irq >= STM32_IRQ_DMA2CH1 && irq <= STM32_IRQ_DMA2CH45)
-#endif
- {
- chndx = irq - STM32_IRQ_DMA2CH1 + DMA1_NCHANNELS;
- }
- else
-#endif
- {
- PANIC(OSERR_INTERNAL);
- }
- dmach = &g_dma[chndx];
-
- /* Get the interrupt status (for this channel only) -- not currently used */
-
- isr = dmabase_getreg(dmach, STM32_DMA_ISR_OFFSET) & DMA_ISR_CHAN_MASK(dmach->chan);
-
- /* Disable the DMA channel */
-
- stm32_dmachandisable(dmach);
-
- /* Invoke the callback */
-
- if (dmach->callback)
- {
- dmach->callback(dmach, isr >> DMA_ISR_CHAN_SHIFT(dmach->chan), dmach->arg);
- }
- return OK;
-}
-
-/****************************************************************************
* Public Functions
****************************************************************************/
-/****************************************************************************
- * Name: stm32_dmainitialize
- *
- * Description:
- * Initialize the DMA subsystem
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-void weak_function up_dmainitialize(void)
-{
- struct stm32_dma_s *dmach;
- int chndx;
-
- /* Initialize each DMA channel */
-
- for (chndx = 0; chndx < DMA_NCHANNELS; chndx++)
- {
- dmach = &g_dma[chndx];
- sem_init(&dmach->sem, 0, 1);
-
- /* Attach DMA interrupt vectors */
-
- (void)irq_attach(dmach->irq, stm32_dmainterrupt);
-
- /* Disable the DMA channel */
-
- stm32_dmachandisable(dmach);
-
- /* Enable the IRQ at the NVIC (still disabled at the DMA controller) */
-
- up_enable_irq(dmach->irq);
-
- /* Set the interrrupt priority */
-
- up_prioritize_irq(dmach->irq, CONFIG_DMA_PRI);
- }
-}
-
-/****************************************************************************
- * Name: stm32_dmachannel
- *
- * Description:
- * Allocate a DMA channel. This function gives the caller mutually
- * exclusive access to the DMA channel specified by the 'chndx' argument.
- * DMA channels are shared on the STM32: Devices sharing the same DMA
- * channel cannot do DMA concurrently! See the DMACHAN_* definitions in
- * stm32_dma.h.
- *
- * If the DMA channel is not available, then stm32_dmachannel() will wait
- * until the holder of the channel relinquishes the channel by calling
- * stm32_dmafree(). WARNING: If you have two devices sharing a DMA
- * channel and the code never releases the channel, the stm32_dmachannel
- * call for the other will hang forever in this function! Don't let your
- * design do that!
- *
- * Hmm.. I suppose this interface could be extended to make a non-blocking
- * version. Feel free to do that if that is what you need.
- *
- * Returned Value:
- * Provided that 'chndx' is valid, this function ALWAYS returns a non-NULL,
- * void* DMA channel handle. (If 'chndx' is invalid, the function will
- * assert if debug is enabled or do something ignorant otherwise).
- *
- * Assumptions:
- * - The caller does not hold he DMA channel.
- * - The caller can wait for the DMA channel to be freed if it is no
- * available.
- *
- ****************************************************************************/
-
-DMA_HANDLE stm32_dmachannel(int chndx)
-{
- struct stm32_dma_s *dmach = &g_dma[chndx];
-
- DEBUGASSERT(chndx < DMA_NCHANNELS);
-
- /* Get exclusive access to the DMA channel -- OR wait until the channel
- * is available if it is currently being used by another driver
- */
-
- stm32_dmatake(dmach);
-
- /* The caller now has exclusive use of the DMA channel */
-
- return (DMA_HANDLE)dmach;
-}
-
-/****************************************************************************
- * Name: stm32_dmafree
- *
- * Description:
- * Release a DMA channel. If another thread is waiting for this DMA channel
- * in a call to stm32_dmachannel, then this function will re-assign the
- * DMA channel to that thread and wake it up. NOTE: The 'handle' used
- * in this argument must NEVER be used again until stm32_dmachannel() is
- * called again to re-gain access to the channel.
- *
- * Returned Value:
- * None
- *
- * Assumptions:
- * - The caller holds the DMA channel.
- * - There is no DMA in progress
- *
- ****************************************************************************/
-
-void stm32_dmafree(DMA_HANDLE handle)
-{
- struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
-
- DEBUGASSERT(handle != NULL);
-
- /* Release the channel */
-
- stm32_dmagive(dmach);
-}
-
-/****************************************************************************
- * Name: stm32_dmasetup
- *
- * Description:
- * Configure DMA before using
+/* This file is only a thin shell that includes the correct DMA implementation
+ * for the selected STM32 family. The correct file cannot be selected by
+ * the make system because it needs the intelligence that only exists in
+ * chip.h that can associate an STM32 part number with an STM32 family.
*
- ****************************************************************************/
-
-void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, size_t ntransfers, uint32_t ccr)
-{
- struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
- uint32_t regval;
+ * The STM32 F4 DMA differs from the F1 DMA primarily in that it adds the
+ * concept of "streams" that are used to associate DMA sources with DMA
+ * channels.
+ */
- /* Set the peripheral register address in the DMA_CPARx register. The data
- * will be moved from/to this address to/from the memory after the
- * peripheral event.
- */
-
- dmachan_putreg(dmach, STM32_DMACHAN_CPAR_OFFSET, paddr);
-
- /* Set the memory address in the DMA_CMARx register. The data will be
- * written to or read from this memory after the peripheral event.
- */
-
- dmachan_putreg(dmach, STM32_DMACHAN_CMAR_OFFSET, maddr);
-
- /* Configure the total number of data to be transferred in the DMA_CNDTRx
- * register. After each peripheral event, this value will be decremented.
- */
-
- dmachan_putreg(dmach, STM32_DMACHAN_CNDTR_OFFSET, ntransfers);
-
- /* Configure the channel priority using the PL[1:0] bits in the DMA_CCRx
- * register. Configure data transfer direction, circular mode, peripheral & memory
- * incremented mode, peripheral & memory data size, and interrupt after
- * half and/or full transfer in the DMA_CCRx register.
- */
-
- regval = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET);
- regval &= ~(DMA_CCR_MEM2MEM|DMA_CCR_PL_MASK|DMA_CCR_MSIZE_MASK|DMA_CCR_PSIZE_MASK|
- DMA_CCR_MINC|DMA_CCR_PINC|DMA_CCR_CIRC|DMA_CCR_DIR);
- ccr &= (DMA_CCR_MEM2MEM|DMA_CCR_PL_MASK|DMA_CCR_MSIZE_MASK|DMA_CCR_PSIZE_MASK|
- DMA_CCR_MINC|DMA_CCR_PINC|DMA_CCR_CIRC|DMA_CCR_DIR);
- regval |= ccr;
- dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, regval);
-}
-
-/****************************************************************************
- * Name: stm32_dmastart
- *
- * Description:
- * Start the DMA transfer
- *
- * Assumptions:
- * - DMA handle allocated by stm32_dmachannel()
- * - No DMA in progress
- *
- ****************************************************************************/
-
-void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool half)
-{
- struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
- uint32_t ccr;
-
- DEBUGASSERT(handle != NULL);
-
- /* Save the callback info. This will be invoked whent the DMA commpletes */
-
- dmach->callback = callback;
- dmach->arg = arg;
-
- /* Activate the channel by setting the ENABLE bit in the DMA_CCRx register.
- * As soon as the channel is enabled, it can serve any DMA request from the
- * peripheral connected on the channel.
- */
-
- ccr = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET);
- ccr |= DMA_CCR_EN;
-
- /* Once half of the bytes are transferred, the half-transfer flag (HTIF) is
- * set and an interrupt is generated if the Half-Transfer Interrupt Enable
- * bit (HTIE) is set. At the end of the transfer, the Transfer Complete Flag
- * (TCIF) is set and an interrupt is generated if the Transfer Complete
- * Interrupt Enable bit (TCIE) is set.
- */
-
- ccr |= (half ? (DMA_CCR_HTIE|DMA_CCR_TEIE) : (DMA_CCR_TCIE|DMA_CCR_TEIE));
- dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, ccr);
-}
-
-/****************************************************************************
- * Name: stm32_dmastop
- *
- * Description:
- * Cancel the DMA. After stm32_dmastop() is called, the DMA channel is
- * reset and stm32_dmasetup() must be called before stm32_dmastart() can be
- * called again
- *
- * Assumptions:
- * - DMA handle allocated by stm32_dmachannel()
- *
- ****************************************************************************/
-
-void stm32_dmastop(DMA_HANDLE handle)
-{
- struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
- stm32_dmachandisable(dmach);
-}
-
-/****************************************************************************
- * Name: stm32_dmasample
- *
- * Description:
- * Sample DMA register contents
- *
- * Assumptions:
- * - DMA handle allocated by stm32_dmachannel()
- *
- ****************************************************************************/
-
-#ifdef CONFIG_DEBUG_DMA
-void stm32_dmasample(DMA_HANDLE handle, struct stm32_dmaregs_s *regs)
-{
- struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
- irqstate_t flags;
-
- flags = irqsave();
- regs->isr = dmabase_getreg(dmach, STM32_DMA_ISR_OFFSET);
- regs->ccr = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET);
- regs->cndtr = dmachan_getreg(dmach, STM32_DMACHAN_CNDTR_OFFSET);
- regs->cpar = dmachan_getreg(dmach, STM32_DMACHAN_CPAR_OFFSET);
- regs->cmar = dmachan_getreg(dmach, STM32_DMACHAN_CMAR_OFFSET);
- irqrestore(flags);
-}
-#endif
-
-/****************************************************************************
- * Name: stm32_dmadump
- *
- * Description:
- * Dump previously sampled DMA register contents
- *
- * Assumptions:
- * - DMA handle allocated by stm32_dmachannel()
- *
- ****************************************************************************/
-
-#ifdef CONFIG_DEBUG_DMA
-void stm32_dmadump(DMA_HANDLE handle, const struct stm32_dmaregs_s *regs,
- const char *msg)
-{
- struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
- uint32_t dmabase = DMA_BASE(dmach->base);
-
- dmadbg("DMA Registers: %s\n", msg);
- dmadbg(" ISRC[%08x]: %08x\n", dmabase + STM32_DMA_ISR_OFFSET, regs->isr);
- dmadbg(" CCR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CCR_OFFSET, regs->ccr);
- dmadbg(" CNDTR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CNDTR_OFFSET, regs->cndtr);
- dmadbg(" CPAR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CPAR_OFFSET, regs->cpar);
- dmadbg(" CMAR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CMAR_OFFSET, regs->cmar);
-}
+#if defined(CONFIG_STM32_STM32F10XX)
+# include "stm32f10xxx_dma.c"
+#elif defined(CONFIG_STM32_STM32F40XX)
+# include "stm32f40xxx_dma.c"
#endif
-
-#endif /* CONFIG_STM32_STM32F10XX */
diff --git a/nuttx/arch/arm/src/stm32/stm32_dma.h b/nuttx/arch/arm/src/stm32/stm32_dma.h
index 8ce888bc2..717c5ae1d 100644
--- a/nuttx/arch/arm/src/stm32/stm32_dma.h
+++ b/nuttx/arch/arm/src/stm32/stm32_dma.h
@@ -61,6 +61,7 @@ typedef FAR void *DMA_HANDLE;
typedef void (*dma_callback_t)(DMA_HANDLE handle, uint8_t isr, void *arg);
#ifdef CONFIG_DEBUG_DMA
+#if defined(CONFIG_STM32_STM32F10XX)
struct stm32_dmaregs_s
{
uint32_t isr;
@@ -69,6 +70,21 @@ struct stm32_dmaregs_s
uint32_t cpar;
uint32_t cmar;
};
+#elif defined(CONFIG_STM32_STM32F40XX)
+struct stm32_dmaregs_s
+{
+ uint32_t lisr;
+ uint32_t hisr;
+ uint32_t scr;
+ uint32_t sndtr;
+ uint32_t spar;
+ uint32_t sm0ar;
+ uint32_t sm1ar;
+ uint32_t sfcr;
+};
+#else
+# error "Unknown STM32 DMA"
+#endif
#endif
/************************************************************************************
diff --git a/nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c b/nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c
new file mode 100644
index 000000000..eaa719e41
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c
@@ -0,0 +1,610 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32f10xxx_dma.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <arch/irq.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+#include "os_internal.h"
+#include "chip.h"
+#include "stm32_dma.h"
+#include "stm32_internal.h"
+
+/* Only for the STM32F10xx family for now */
+
+#ifdef CONFIG_STM32_STM32F10XX
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define DMA1_NCHANNELS 7
+#if STM32_NDMA > 1
+# define DMA2_NCHANNELS 5
+# define DMA_NCHANNELS (DMA1_NCHANNELS+DMA2_NCHANNELS)
+#else
+# define DMA_NCHANNELS DMA1_NCHANNELS
+#endif
+
+#ifndef CONFIG_DMA_PRI
+# define CONFIG_DMA_PRI NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+
+/* Convert the DMA channel base address to the DMA register block address */
+
+#define DMA_BASE(ch) (ch & 0xfffffc00)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* This structure descibes one DMA channel */
+
+struct stm32_dma_s
+{
+ uint8_t chan; /* DMA channel number (0-6) */
+ uint8_t irq; /* DMA channel IRQ number */
+ sem_t sem; /* Used to wait for DMA channel to become available */
+ uint32_t base; /* DMA register channel base address */
+ dma_callback_t callback; /* Callback invoked when the DMA completes */
+ void *arg; /* Argument passed to callback function */
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* This array describes the state of each DMA */
+
+static struct stm32_dma_s g_dma[DMA_NCHANNELS] =
+{
+ {
+ .chan = 0,
+ .irq = STM32_IRQ_DMA1CH1,
+ .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(0),
+ },
+ {
+ .chan = 1,
+ .irq = STM32_IRQ_DMA1CH2,
+ .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(1),
+ },
+ {
+ .chan = 2,
+ .irq = STM32_IRQ_DMA1CH3,
+ .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(2),
+ },
+ {
+ .chan = 3,
+ .irq = STM32_IRQ_DMA1CH4,
+ .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(3),
+ },
+ {
+ .chan = 4,
+ .irq = STM32_IRQ_DMA1CH5,
+ .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(4),
+ },
+ {
+ .chan = 5,
+ .irq = STM32_IRQ_DMA1CH6,
+ .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(5),
+ },
+ {
+ .chan = 6,
+ .irq = STM32_IRQ_DMA1CH7,
+ .base = STM32_DMA1_BASE + STM32_DMACHAN_OFFSET(6),
+ },
+#if STM32_NDMA > 1
+ {
+ .chan = 0,
+ .irq = STM32_IRQ_DMA2CH1,
+ .base = STM32_DMA2_BASE + STM32_DMACHAN_OFFSET(0),
+ },
+ {
+ .chan = 1,
+ .irq = STM32_IRQ_DMA2CH2,
+ .base = STM32_DMA2_BASE + STM32_DMACHAN_OFFSET(1),
+ },
+ {
+ .chan = 2,
+ .irq = STM32_IRQ_DMA2CH3,
+ .base = STM32_DMA2_BASE + STM32_DMACHAN_OFFSET(2),
+ },
+ {
+ .chan = 3,
+#ifdef CONFIG_STM32_CONNECTIVITY_LINE
+ .irq = STM32_IRQ_DMA2CH4,
+#else
+ .irq = STM32_IRQ_DMA2CH45,
+#endif
+ .base = STM32_DMA2_BASE + STM32_DMACHAN_OFFSET(3),
+ },
+ {
+ .chan = 4,
+#ifdef CONFIG_STM32_CONNECTIVITY_LINE
+ .irq = STM32_IRQ_DMA2CH5,
+#else
+ .irq = STM32_IRQ_DMA2CH45,
+#endif
+ .base = STM32_DMA2_BASE + STM32_DMACHAN_OFFSET(4),
+ },
+#endif
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * DMA register access functions
+ ****************************************************************************/
+
+/* Get non-channel register from DMA1 or DMA2 */
+
+static inline uint32_t dmabase_getreg(struct stm32_dma_s *dmach, uint32_t offset)
+{
+ return getreg32(DMA_BASE(dmach->base) + offset);
+}
+
+/* Write to non-channel register in DMA1 or DMA2 */
+
+static inline void dmabase_putreg(struct stm32_dma_s *dmach, uint32_t offset, uint32_t value)
+{
+ putreg32(value, DMA_BASE(dmach->base) + offset);
+}
+
+/* Get channel register from DMA1 or DMA2 */
+
+static inline uint32_t dmachan_getreg(struct stm32_dma_s *dmach, uint32_t offset)
+{
+ return getreg32(dmach->base + offset);
+}
+
+/* Write to channel register in DMA1 or DMA2 */
+
+static inline void dmachan_putreg(struct stm32_dma_s *dmach, uint32_t offset, uint32_t value)
+{
+ putreg32(value, dmach->base + offset);
+}
+
+/************************************************************************************
+ * Name: stm32_dmatake() and stm32_dmagive()
+ *
+ * Description:
+ * Used to get exclusive access to a DMA channel.
+ *
+ ************************************************************************************/
+
+static void stm32_dmatake(FAR struct stm32_dma_s *dmach)
+{
+ /* Take the semaphore (perhaps waiting) */
+
+ while (sem_wait(&dmach->sem) != 0)
+ {
+ /* The only case that an error should occur here is if the wait was awakened
+ * by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+}
+
+static inline void stm32_dmagive(FAR struct stm32_dma_s *dmach)
+{
+ (void)sem_post(&dmach->sem);
+}
+
+/************************************************************************************
+ * Name: stm32_dmachandisable
+ *
+ * Description:
+ * Disable the DMA channel
+ *
+ ************************************************************************************/
+
+static void stm32_dmachandisable(struct stm32_dma_s *dmach)
+{
+ uint32_t regval;
+
+ /* Disable all interrupts at the DMA controller */
+
+ regval = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET);
+ regval &= ~DMA_CCR_ALLINTS;
+
+ /* Disable the DMA channel */
+
+ regval &= ~DMA_CCR_EN;
+ dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, regval);
+
+ /* Clear pending channel interrupts */
+
+ dmabase_putreg(dmach, STM32_DMA_IFCR_OFFSET, DMA_ISR_CHAN_MASK(dmach->chan));
+}
+
+/************************************************************************************
+ * Name: stm32_dmainterrupt
+ *
+ * Description:
+ * DMA interrupt handler
+ *
+ ************************************************************************************/
+
+static int stm32_dmainterrupt(int irq, void *context)
+{
+ struct stm32_dma_s *dmach;
+ uint32_t isr;
+ int chndx = 0;
+
+ /* Get the channel structure from the interrupt number */
+
+ if (irq >= STM32_IRQ_DMA1CH1 && irq <= STM32_IRQ_DMA1CH7)
+ {
+ chndx = irq - STM32_IRQ_DMA1CH1;
+ }
+ else
+#if STM32_NDMA > 1
+#ifdef CONFIG_STM32_CONNECTIVITY_LINE
+ if (irq >= STM32_IRQ_DMA2CH1 && irq <= STM32_IRQ_DMA2CH5)
+#else
+ if (irq >= STM32_IRQ_DMA2CH1 && irq <= STM32_IRQ_DMA2CH45)
+#endif
+ {
+ chndx = irq - STM32_IRQ_DMA2CH1 + DMA1_NCHANNELS;
+ }
+ else
+#endif
+ {
+ PANIC(OSERR_INTERNAL);
+ }
+ dmach = &g_dma[chndx];
+
+ /* Get the interrupt status (for this channel only) -- not currently used */
+
+ isr = dmabase_getreg(dmach, STM32_DMA_ISR_OFFSET) & DMA_ISR_CHAN_MASK(dmach->chan);
+
+ /* Disable the DMA channel */
+
+ stm32_dmachandisable(dmach);
+
+ /* Invoke the callback */
+
+ if (dmach->callback)
+ {
+ dmach->callback(dmach, isr >> DMA_ISR_CHAN_SHIFT(dmach->chan), dmach->arg);
+ }
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_dmainitialize
+ *
+ * Description:
+ * Initialize the DMA subsystem
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void weak_function up_dmainitialize(void)
+{
+ struct stm32_dma_s *dmach;
+ int chndx;
+
+ /* Initialize each DMA channel */
+
+ for (chndx = 0; chndx < DMA_NCHANNELS; chndx++)
+ {
+ dmach = &g_dma[chndx];
+ sem_init(&dmach->sem, 0, 1);
+
+ /* Attach DMA interrupt vectors */
+
+ (void)irq_attach(dmach->irq, stm32_dmainterrupt);
+
+ /* Disable the DMA channel */
+
+ stm32_dmachandisable(dmach);
+
+ /* Enable the IRQ at the NVIC (still disabled at the DMA controller) */
+
+ up_enable_irq(dmach->irq);
+
+ /* Set the interrrupt priority */
+
+ up_prioritize_irq(dmach->irq, CONFIG_DMA_PRI);
+ }
+}
+
+/****************************************************************************
+ * Name: stm32_dmachannel
+ *
+ * Description:
+ * Allocate a DMA channel. This function gives the caller mutually
+ * exclusive access to the DMA channel specified by the 'chndx' argument.
+ * DMA channels are shared on the STM32: Devices sharing the same DMA
+ * channel cannot do DMA concurrently! See the DMACHAN_* definitions in
+ * stm32_dma.h.
+ *
+ * If the DMA channel is not available, then stm32_dmachannel() will wait
+ * until the holder of the channel relinquishes the channel by calling
+ * stm32_dmafree(). WARNING: If you have two devices sharing a DMA
+ * channel and the code never releases the channel, the stm32_dmachannel
+ * call for the other will hang forever in this function! Don't let your
+ * design do that!
+ *
+ * Hmm.. I suppose this interface could be extended to make a non-blocking
+ * version. Feel free to do that if that is what you need.
+ *
+ * Returned Value:
+ * Provided that 'chndx' is valid, this function ALWAYS returns a non-NULL,
+ * void* DMA channel handle. (If 'chndx' is invalid, the function will
+ * assert if debug is enabled or do something ignorant otherwise).
+ *
+ * Assumptions:
+ * - The caller does not hold he DMA channel.
+ * - The caller can wait for the DMA channel to be freed if it is no
+ * available.
+ *
+ ****************************************************************************/
+
+DMA_HANDLE stm32_dmachannel(int chndx)
+{
+ struct stm32_dma_s *dmach = &g_dma[chndx];
+
+ DEBUGASSERT(chndx < DMA_NCHANNELS);
+
+ /* Get exclusive access to the DMA channel -- OR wait until the channel
+ * is available if it is currently being used by another driver
+ */
+
+ stm32_dmatake(dmach);
+
+ /* The caller now has exclusive use of the DMA channel */
+
+ return (DMA_HANDLE)dmach;
+}
+
+/****************************************************************************
+ * Name: stm32_dmafree
+ *
+ * Description:
+ * Release a DMA channel. If another thread is waiting for this DMA channel
+ * in a call to stm32_dmachannel, then this function will re-assign the
+ * DMA channel to that thread and wake it up. NOTE: The 'handle' used
+ * in this argument must NEVER be used again until stm32_dmachannel() is
+ * called again to re-gain access to the channel.
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * - The caller holds the DMA channel.
+ * - There is no DMA in progress
+ *
+ ****************************************************************************/
+
+void stm32_dmafree(DMA_HANDLE handle)
+{
+ struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
+
+ DEBUGASSERT(handle != NULL);
+
+ /* Release the channel */
+
+ stm32_dmagive(dmach);
+}
+
+/****************************************************************************
+ * Name: stm32_dmasetup
+ *
+ * Description:
+ * Configure DMA before using
+ *
+ ****************************************************************************/
+
+void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, size_t ntransfers, uint32_t ccr)
+{
+ struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
+ uint32_t regval;
+
+ /* Set the peripheral register address in the DMA_CPARx register. The data
+ * will be moved from/to this address to/from the memory after the
+ * peripheral event.
+ */
+
+ dmachan_putreg(dmach, STM32_DMACHAN_CPAR_OFFSET, paddr);
+
+ /* Set the memory address in the DMA_CMARx register. The data will be
+ * written to or read from this memory after the peripheral event.
+ */
+
+ dmachan_putreg(dmach, STM32_DMACHAN_CMAR_OFFSET, maddr);
+
+ /* Configure the total number of data to be transferred in the DMA_CNDTRx
+ * register. After each peripheral event, this value will be decremented.
+ */
+
+ dmachan_putreg(dmach, STM32_DMACHAN_CNDTR_OFFSET, ntransfers);
+
+ /* Configure the channel priority using the PL[1:0] bits in the DMA_CCRx
+ * register. Configure data transfer direction, circular mode, peripheral & memory
+ * incremented mode, peripheral & memory data size, and interrupt after
+ * half and/or full transfer in the DMA_CCRx register.
+ */
+
+ regval = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET);
+ regval &= ~(DMA_CCR_MEM2MEM|DMA_CCR_PL_MASK|DMA_CCR_MSIZE_MASK|DMA_CCR_PSIZE_MASK|
+ DMA_CCR_MINC|DMA_CCR_PINC|DMA_CCR_CIRC|DMA_CCR_DIR);
+ ccr &= (DMA_CCR_MEM2MEM|DMA_CCR_PL_MASK|DMA_CCR_MSIZE_MASK|DMA_CCR_PSIZE_MASK|
+ DMA_CCR_MINC|DMA_CCR_PINC|DMA_CCR_CIRC|DMA_CCR_DIR);
+ regval |= ccr;
+ dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, regval);
+}
+
+/****************************************************************************
+ * Name: stm32_dmastart
+ *
+ * Description:
+ * Start the DMA transfer
+ *
+ * Assumptions:
+ * - DMA handle allocated by stm32_dmachannel()
+ * - No DMA in progress
+ *
+ ****************************************************************************/
+
+void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool half)
+{
+ struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
+ uint32_t ccr;
+
+ DEBUGASSERT(handle != NULL);
+
+ /* Save the callback info. This will be invoked whent the DMA commpletes */
+
+ dmach->callback = callback;
+ dmach->arg = arg;
+
+ /* Activate the channel by setting the ENABLE bit in the DMA_CCRx register.
+ * As soon as the channel is enabled, it can serve any DMA request from the
+ * peripheral connected on the channel.
+ */
+
+ ccr = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET);
+ ccr |= DMA_CCR_EN;
+
+ /* Once half of the bytes are transferred, the half-transfer flag (HTIF) is
+ * set and an interrupt is generated if the Half-Transfer Interrupt Enable
+ * bit (HTIE) is set. At the end of the transfer, the Transfer Complete Flag
+ * (TCIF) is set and an interrupt is generated if the Transfer Complete
+ * Interrupt Enable bit (TCIE) is set.
+ */
+
+ ccr |= (half ? (DMA_CCR_HTIE|DMA_CCR_TEIE) : (DMA_CCR_TCIE|DMA_CCR_TEIE));
+ dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, ccr);
+}
+
+/****************************************************************************
+ * Name: stm32_dmastop
+ *
+ * Description:
+ * Cancel the DMA. After stm32_dmastop() is called, the DMA channel is
+ * reset and stm32_dmasetup() must be called before stm32_dmastart() can be
+ * called again
+ *
+ * Assumptions:
+ * - DMA handle allocated by stm32_dmachannel()
+ *
+ ****************************************************************************/
+
+void stm32_dmastop(DMA_HANDLE handle)
+{
+ struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
+ stm32_dmachandisable(dmach);
+}
+
+/****************************************************************************
+ * Name: stm32_dmasample
+ *
+ * Description:
+ * Sample DMA register contents
+ *
+ * Assumptions:
+ * - DMA handle allocated by stm32_dmachannel()
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG_DMA
+void stm32_dmasample(DMA_HANDLE handle, struct stm32_dmaregs_s *regs)
+{
+ struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
+ irqstate_t flags;
+
+ flags = irqsave();
+ regs->isr = dmabase_getreg(dmach, STM32_DMA_ISR_OFFSET);
+ regs->ccr = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET);
+ regs->cndtr = dmachan_getreg(dmach, STM32_DMACHAN_CNDTR_OFFSET);
+ regs->cpar = dmachan_getreg(dmach, STM32_DMACHAN_CPAR_OFFSET);
+ regs->cmar = dmachan_getreg(dmach, STM32_DMACHAN_CMAR_OFFSET);
+ irqrestore(flags);
+}
+#endif
+
+/****************************************************************************
+ * Name: stm32_dmadump
+ *
+ * Description:
+ * Dump previously sampled DMA register contents
+ *
+ * Assumptions:
+ * - DMA handle allocated by stm32_dmachannel()
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG_DMA
+void stm32_dmadump(DMA_HANDLE handle, const struct stm32_dmaregs_s *regs,
+ const char *msg)
+{
+ struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
+ uint32_t dmabase = DMA_BASE(dmach->base);
+
+ dmadbg("DMA Registers: %s\n", msg);
+ dmadbg(" ISRC[%08x]: %08x\n", dmabase + STM32_DMA_ISR_OFFSET, regs->isr);
+ dmadbg(" CCR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CCR_OFFSET, regs->ccr);
+ dmadbg(" CNDTR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CNDTR_OFFSET, regs->cndtr);
+ dmadbg(" CPAR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CPAR_OFFSET, regs->cpar);
+ dmadbg(" CMAR[%08x]: %08x\n", dmach->base + STM32_DMACHAN_CMAR_OFFSET, regs->cmar);
+}
+#endif
+
+#endif /* CONFIG_STM32_STM32F10XX */
diff --git a/nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c b/nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c
new file mode 100644
index 000000000..8dedde3ac
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c
@@ -0,0 +1,662 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32f40xxx_dma.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <arch/irq.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+#include "os_internal.h"
+#include "chip.h"
+#include "stm32_dma.h"
+#include "stm32_internal.h"
+
+/* This file supports only the STM32 F4 family (an probably the F2 family
+ * as well?)
+ */
+
+#if defined(CONFIG_STM32_STM32F40XX)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define DMA1_NSTREAMS 8
+#if STM32_NDMA > 1
+# define DMA2_NSTREAMS 8
+# define DMA_NSTREAMS (DMA1_NSTREAMS+DMA2_NSTREAMS)
+#else
+# define DMA_NSTREAMS DMA1_NSTREAMS
+#endif
+
+#ifndef CONFIG_DMA_PRI
+# define CONFIG_DMA_PRI NVIC_SYSH_PRIORITY_DEFAULT
+#endif
+
+/* Convert the DMA stream base address to the DMA register block address */
+
+#define DMA_BASE(ch) (ch & 0xfffffc00)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* This structure descibes one DMA channel */
+
+struct stm32_dma_s
+{
+ uint8_t stream; /* DMA stream number (0-7) */
+ uint8_t irq; /* DMA stream IRQ number */
+ uint8_t shift; /* ISR/IFCR bit shift value */
+ uint8_t pad; /* Unused */
+ sem_t sem; /* Used to wait for DMA channel to become available */
+ uint32_t base; /* DMA register channel base address */
+ dma_callback_t callback; /* Callback invoked when the DMA completes */
+ void *arg; /* Argument passed to callback function */
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* This array describes the state of each DMA */
+
+static struct stm32_dma_s g_dma[DMA_NSTREAMS] =
+{
+ {
+ .stream = 0,
+ .irq = STM32_IRQ_DMA1S0,
+ .shift = DMA_INT_STREAM0_SHIFT,
+ .base = STM32_DMA1_BASE + STM32_DMA_OFFSET(0),
+ },
+ {
+ .stream = 1,
+ .irq = STM32_IRQ_DMA1S1,
+ .shift = DMA_INT_STREAM1_SHIFT,
+ .base = STM32_DMA1_BASE + STM32_DMA_OFFSET(1),
+ },
+ {
+ .stream = 2,
+ .irq = STM32_IRQ_DMA1S2,
+ .shift = DMA_INT_STREAM2_SHIFT,
+ .base = STM32_DMA1_BASE + STM32_DMA_OFFSET(2),
+ },
+ {
+ .stream = 3,
+ .irq = STM32_IRQ_DMA1S3,
+ .shift = DMA_INT_STREAM3_SHIFT,
+ .base = STM32_DMA1_BASE + STM32_DMA_OFFSET(4),
+ },
+ {
+ .stream = 4,
+ .irq = STM32_IRQ_DMA1S4,
+ .shift = DMA_INT_STREAM4_SHIFT,
+ .base = STM32_DMA1_BASE + STM32_DMA_OFFSET(4),
+ },
+ {
+ .stream = 5,
+ .irq = STM32_IRQ_DMA1S5,
+ .shift = DMA_INT_STREAM5_SHIFT,
+ .base = STM32_DMA1_BASE + STM32_DMA_OFFSET(5),
+ },
+ {
+ .stream = 6,
+ .irq = STM32_IRQ_DMA1S6,
+ .shift = DMA_INT_STREAM6_SHIFT,
+ .base = STM32_DMA1_BASE + STM32_DMA_OFFSET(6),
+ },
+ {
+ .stream = 7,
+ .irq = STM32_IRQ_DMA1S7,
+ .shift = DMA_INT_STREAM7_SHIFT,
+ .base = STM32_DMA1_BASE + STM32_DMA_OFFSET(7),
+ },
+#if STM32_NDMA > 1
+ {
+ .stream = 0,
+ .irq = STM32_IRQ_DMA2S0,
+ .shift = DMA_INT_STREAM0_SHIFT,
+ .base = STM32_DMA2_BASE + STM32_DMA_OFFSET(0),
+ },
+ {
+ .stream = 1,
+ .irq = STM32_IRQ_DMA2S1,
+ .shift = DMA_INT_STREAM1_SHIFT,
+ .base = STM32_DMA2_BASE + STM32_DMA_OFFSET(1),
+ },
+ {
+ .stream = 2,
+ .irq = STM32_IRQ_DMA2S2,
+ .shift = DMA_INT_STREAM2_SHIFT,
+ .base = STM32_DMA2_BASE + STM32_DMA_OFFSET(2),
+ },
+ {
+ .stream = 3,
+ .irq = STM32_IRQ_DMA2S3,
+ .shift = DMA_INT_STREAM3_SHIFT,
+ .base = STM32_DMA2_BASE + STM32_DMA_OFFSET(3),
+ },
+ {
+ .stream = 4,
+ .irq = STM32_IRQ_DMA2S4,
+ .base = STM32_DMA2_BASE + STM32_DMA_OFFSET(4),
+ },
+ {
+ .stream = 5,
+ .irq = STM32_IRQ_DMA2S5,
+ .shift = DMA_INT_STREAM5_SHIFT,
+ .base = STM32_DMA2_BASE + STM32_DMA_OFFSET(5),
+ },
+ {
+ .stream = 6,
+ .irq = STM32_IRQ_DMA2S6,
+ .shift = DMA_INT_STREAM6_SHIFT,
+ .base = STM32_DMA2_BASE + STM32_DMA_OFFSET(6),
+ },
+ {
+ .stream = 7,
+ .irq = STM32_IRQ_DMA2S7,
+ .shift = DMA_INT_STREAM7_SHIFT,
+ .base = STM32_DMA2_BASE + STM32_DMA_OFFSET(7),
+ },
+#endif
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * DMA register access functions
+ ****************************************************************************/
+
+/* Get non-channel register from DMA1 or DMA2 */
+
+static inline uint32_t dmabase_getreg(struct stm32_dma_s *dmast, uint32_t offset)
+{
+ return getreg32(DMA_BASE(dmast->base) + offset);
+}
+
+/* Write to non-channel register in DMA1 or DMA2 */
+
+static inline void dmabase_putreg(struct stm32_dma_s *dmast, uint32_t offset, uint32_t value)
+{
+ putreg32(value, DMA_BASE(dmast->base) + offset);
+}
+
+/* Get channel register from DMA1 or DMA2 */
+
+static inline uint32_t dmast_getreg(struct stm32_dma_s *dmast, uint32_t offset)
+{
+ return getreg32(dmast->base + offset);
+}
+
+/* Write to channel register in DMA1 or DMA2 */
+
+static inline void dmast_putreg(struct stm32_dma_s *dmast, uint32_t offset, uint32_t value)
+{
+ putreg32(value, dmast->base + offset);
+}
+
+/************************************************************************************
+ * Name: stm32_dmatake() and stm32_dmagive()
+ *
+ * Description:
+ * Used to get exclusive access to a DMA channel.
+ *
+ ************************************************************************************/
+
+static void stm32_dmatake(FAR struct stm32_dma_s *dmast)
+{
+ /* Take the semaphore (perhaps waiting) */
+
+ while (sem_wait(&dmast->sem) != 0)
+ {
+ /* The only case that an error should occur here is if the wait was awakened
+ * by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+}
+
+static inline void stm32_dmagive(FAR struct stm32_dma_s *dmast)
+{
+ (void)sem_post(&dmast->sem);
+}
+
+/************************************************************************************
+ * Name: stm32_dmastreamdisable
+ *
+ * Description:
+ * Disable the DMA stream
+ *
+ ************************************************************************************/
+
+static void stm32_dmastreamdisable(struct stm32_dma_s *dmast)
+{
+ uint32_t regoffset;
+ uint32_t regval;
+
+ /* Disable all interrupts at the DMA controller */
+
+ regval = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
+ regval &= ~DMA_SCR_ALLINTS;
+
+ /* Disable the DMA stream */
+
+ regval &= ~DMA_SCR_EN;
+ dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, regval);
+
+ /* Clear pending stream interrupts by setting bits in the upper or lower IFCR
+ * register
+ */
+
+ if (dmast->stream < 4)
+ {
+ regoffset = STM32_DMA_LIFCR_OFFSET;
+ }
+ else
+ {
+ regoffset = STM32_DMA_HIFCR_OFFSET;
+ }
+
+ dmabase_putreg(dmast, regoffset, (DMA_STREAM_MASK << dmast->shift));
+}
+
+/************************************************************************************
+ * Name: stm32_dmainterrupt
+ *
+ * Description:
+ * DMA interrupt handler
+ *
+ ************************************************************************************/
+
+static int stm32_dmainterrupt(int irq, void *context)
+{
+ struct stm32_dma_s *dmast;
+ uint32_t isr;
+ uint32_t regoffset = 0;
+ int stndx = 0;
+
+ /* Get the stream structure from the interrupt number */
+
+ if (irq >= STM32_IRQ_DMA1S0 && irq <= STM32_IRQ_DMA1S7)
+ {
+ stndx = irq - STM32_IRQ_DMA1S0;
+ regoffset = STM32_DMA_LISR_OFFSET;
+ }
+ else
+#if STM32_NDMA > 1
+ if (irq >= STM32_IRQ_DMA2S0 && irq <= STM32_IRQ_DMA2S7)
+ {
+ stndx = irq - STM32_IRQ_DMA2S0 + DMA1_NSTREAMS;
+ regoffset = STM32_DMA_HISR_OFFSET;
+ }
+ else
+#endif
+ {
+ PANIC(OSERR_INTERNAL);
+ }
+ dmast = &g_dma[stndx];
+
+ /* Get the interrupt status for this stream */
+
+ isr = (dmabase_getreg(dmast, regoffset) >> dmast->shift) & DMA_STREAM_MASK;
+
+ /* Disable the DMA stream */
+
+ stm32_dmastreamdisable(dmast);
+
+ /* Invoke the callback */
+
+ if (dmast->callback)
+ {
+ dmast->callback(dmast, isr, dmast->arg);
+ }
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_dmainitialize
+ *
+ * Description:
+ * Initialize the DMA subsystem
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void weak_function up_dmainitialize(void)
+{
+ struct stm32_dma_s *dmast;
+ int stndx;
+
+ /* Initialize each DMA stream */
+
+ for (stndx = 0; stndx < DMA_NSTREAMS; stndx++)
+ {
+ dmast = &g_dma[stndx];
+ sem_init(&dmast->sem, 0, 1);
+
+ /* Attach DMA interrupt vectors */
+
+ (void)irq_attach(dmast->irq, stm32_dmainterrupt);
+
+ /* Disable the DMA stream */
+
+ stm32_dmastreamdisable(dmast);
+
+ /* Enable the IRQ at the NVIC (still disabled at the DMA controller) */
+
+ up_enable_irq(dmast->irq);
+
+ /* Set the interrrupt priority */
+
+ up_prioritize_irq(dmast->irq, CONFIG_DMA_PRI);
+ }
+}
+
+/****************************************************************************
+ * Name: stm32_dmachannel
+ *
+ * Description:
+ * Allocate a DMA channel. This function gives the caller mutually
+ * exclusive access to the DMA channel specified by the 'stndx' argument.
+ * DMA channels are shared on the STM32: Devices sharing the same DMA
+ * channel cannot do DMA concurrently! See the DMACHAN_* definitions in
+ * stm32_dma.h.
+ *
+ * If the DMA channel is not available, then stm32_dmachannel() will wait
+ * until the holder of the channel relinquishes the channel by calling
+ * stm32_dmafree(). WARNING: If you have two devices sharing a DMA
+ * channel and the code never releases the channel, the stm32_dmachannel
+ * call for the other will hang forever in this function! Don't let your
+ * design do that!
+ *
+ * Hmm.. I suppose this interface could be extended to make a non-blocking
+ * version. Feel free to do that if that is what you need.
+ *
+ * Returned Value:
+ * Provided that 'stndx' is valid, this function ALWAYS returns a non-NULL,
+ * void* DMA channel handle. (If 'stndx' is invalid, the function will
+ * assert if debug is enabled or do something ignorant otherwise).
+ *
+ * Assumptions:
+ * - The caller does not hold he DMA channel.
+ * - The caller can wait for the DMA channel to be freed if it is no
+ * available.
+ *
+ ****************************************************************************/
+
+DMA_HANDLE stm32_dmachannel(int stndx)
+{
+ struct stm32_dma_s *dmast = &g_dma[stndx];
+
+ DEBUGASSERT(stndx < DMA_NSTREAMS);
+
+ /* Get exclusive access to the DMA channel -- OR wait until the channel
+ * is available if it is currently being used by another driver
+ */
+
+ stm32_dmatake(dmast);
+
+ /* The caller now has exclusive use of the DMA channel */
+
+ return (DMA_HANDLE)dmast;
+}
+
+/****************************************************************************
+ * Name: stm32_dmafree
+ *
+ * Description:
+ * Release a DMA channel. If another thread is waiting for this DMA channel
+ * in a call to stm32_dmachannel, then this function will re-assign the
+ * DMA channel to that thread and wake it up. NOTE: The 'handle' used
+ * in this argument must NEVER be used again until stm32_dmachannel() is
+ * called again to re-gain access to the channel.
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * - The caller holds the DMA channel.
+ * - There is no DMA in progress
+ *
+ ****************************************************************************/
+
+void stm32_dmafree(DMA_HANDLE handle)
+{
+ struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
+
+ DEBUGASSERT(handle != NULL);
+
+ /* Release the channel */
+
+ stm32_dmagive(dmast);
+}
+
+/****************************************************************************
+ * Name: stm32_dmasetup
+ *
+ * Description:
+ * Configure DMA before using
+ *
+ ****************************************************************************/
+
+void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, size_t ntransfers, uint32_t scr)
+{
+ struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
+ uint32_t regval;
+
+ /* Set the peripheral register address in the DMA_SPARx register. The data
+ * will be moved from/to this address to/from the memory after the
+ * peripheral event.
+ */
+
+ dmast_putreg(dmast, STM32_DMA_SPAR_OFFSET, paddr);
+
+ /* Set the memory address in the DMA_SM0ARx register. The data will be
+ * written to or read from this memory after the peripheral event.
+ * Note that only single-buffer mode is currently supported so SM1ARx
+ * is not used.
+ */
+
+ dmast_putreg(dmast, STM32_DMA_SM0AR_OFFSET, maddr);
+
+ /* Configure the total number of data items to be transferred in the DMA_SNDTRx
+ * register. After each peripheral event, this value will be decremented.
+ */
+
+ dmast_putreg(dmast, STM32_DMA_SNDTR_OFFSET, ntransfers);
+
+ /* Configure the stream priority using the PL[1:0] bits in the DMA_SCRx
+ * register. Configure data transfer direction, circular mode, peripheral & memory
+ * incremented mode, peripheral & memory data size, and interrupt after
+ * half and/or full transfer in the DMA_CCRx register.
+ */
+
+ regval = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
+ regval &= ~(DMA_SCR_DIR_MASK|DMA_SCR_PINC|DMA_SCR_MINC|DMA_SCR_PSIZE_MASK|
+ DMA_SCR_MSIZE_MASK|DMA_SCR_PINCOS|DMA_SCR_PL_MASK|DMA_SCR_PBURST_MASK|
+ DMA_SCR_MBURST_MASK);
+ scr &= (DMA_SCR_DIR_MASK|DMA_SCR_PINC|DMA_SCR_MINC|DMA_SCR_PSIZE_MASK|
+ DMA_SCR_MSIZE_MASK|DMA_SCR_PINCOS|DMA_SCR_PL_MASK|DMA_SCR_PBURST_MASK|
+ DMA_SCR_MBURST_MASK);
+ regval |= scr;
+ dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, regval);
+}
+
+/****************************************************************************
+ * Name: stm32_dmastart
+ *
+ * Description:
+ * Start the DMA transfer
+ *
+ * Assumptions:
+ * - DMA handle allocated by stm32_dmachannel()
+ * - No DMA in progress
+ *
+ ****************************************************************************/
+
+void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool half)
+{
+ struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
+ uint32_t scr;
+
+ DEBUGASSERT(handle != NULL);
+
+ /* Save the callback info. This will be invoked whent the DMA commpletes */
+
+ dmast->callback = callback;
+ dmast->arg = arg;
+
+ /* Activate the stream by setting the ENABLE bit in the DMA_SCRx register.
+ * As soon as the stream is enabled, it can serve any DMA request from the
+ * peripheral connected on the stream.
+ */
+
+ scr = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
+ scr |= DMA_SCR_EN;
+
+ /* Once half of the bytes are transferred, the half-transfer flag (HTIF) is
+ * set and an interrupt is generated if the Half-Transfer Interrupt Enable
+ * bit (HTIE) is set. At the end of the transfer, the Transfer Complete Flag
+ * (TCIF) is set and an interrupt is generated if the Transfer Complete
+ * Interrupt Enable bit (TCIE) is set.
+ */
+
+ scr |= (half ? (DMA_SCR_HTIE|DMA_SCR_TEIE) : (DMA_SCR_TCIE|DMA_SCR_TEIE));
+ dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, scr);
+}
+
+/****************************************************************************
+ * Name: stm32_dmastop
+ *
+ * Description:
+ * Cancel the DMA. After stm32_dmastop() is called, the DMA channel is
+ * reset and stm32_dmasetup() must be called before stm32_dmastart() can be
+ * called again
+ *
+ * Assumptions:
+ * - DMA handle allocated by stm32_dmachannel()
+ *
+ ****************************************************************************/
+
+void stm32_dmastop(DMA_HANDLE handle)
+{
+ struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
+ stm32_dmastreamdisable(dmast);
+}
+
+/****************************************************************************
+ * Name: stm32_dmasample
+ *
+ * Description:
+ * Sample DMA register contents
+ *
+ * Assumptions:
+ * - DMA handle allocated by stm32_dmachannel()
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG_DMA
+void stm32_dmasample(DMA_HANDLE handle, struct stm32_dmaregs_s *regs)
+{
+ struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
+ irqstate_t flags;
+
+ flags = irqsave();
+ regs->lisr = dmabase_getreg(dmast, STM32_DMA_LISR_OFFSET);
+ regs->hisr = dmabase_getreg(dmast, STM32_DMA_LISR_OFFSET);
+ regs->scr = dmast_getreg(dmast, STM32_DMA_HISR_OFFSET);
+ regs->sndtr = dmast_getreg(dmast, STM32_DMA_SNDTR_OFFSET);
+ regs->spar = dmast_getreg(dmast, STM32_DMA_SPAR_OFFSET);
+ regs->sm0ar = dmast_getreg(dmast, STM32_DMA_SM0AR_OFFSET);
+ regs->sm1ar = dmast_getreg(dmast, STM32_DMA_SM1AR_OFFSET);
+ regs->sfcr = dmast_getreg(dmast, STM32_DMA_SFCR_OFFSET);
+ irqrestore(flags);
+}
+#endif
+
+/****************************************************************************
+ * Name: stm32_dmadump
+ *
+ * Description:
+ * Dump previously sampled DMA register contents
+ *
+ * Assumptions:
+ * - DMA handle allocated by stm32_dmachannel()
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG_DMA
+void stm32_dmadump(DMA_HANDLE handle, const struct stm32_dmaregs_s *regs,
+ const char *msg)
+{
+ struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
+ uint32_t dmabase = DMA_BASE(dmast->base);
+
+ dmadbg("DMA Registers: %s\n", msg);
+ dmadbg(" LISR[%08x]: %08x\n", dmabase + STM32_DMA_LISR_OFFSET, regs->lisr);
+ dmadbg(" HISR[%08x]: %08x\n", dmabase + STM32_DMA_HISR_OFFSET, regs->hisr);
+ dmadbg(" SCR[%08x]: %08x\n", dmast->base + STM32_DMA_SCR_OFFSET, regs->scr);
+ dmadbg(" SNDTR[%08x]: %08x\n", dmast->base + STM32_DMA_SNDTR_OFFSET, regs->sndtr);
+ dmadbg(" SPAR[%08x]: %08x\n", dmast->base + STM32_DMA_SPAR_OFFSET, regs->spar);
+ dmadbg(" SM0AR[%08x]: %08x\n", dmast->base + STM32_DMA_SM0AR_OFFSET, regs->sm0ar);
+ dmadbg(" SM1AR[%08x]: %08x\n", dmast->base + STM32_DMA_SM1AR_OFFSET, regs->sm1ar);
+ dmadbg(" SFCRF[%08x]: %08x\n", dmast->base + STM32_DMA_SFCR_OFFSET, regs->sfcr);
+}
+#endif
+
+#endif /* CONFIG_STM32_STM32F10XX */