From f636ee02124366885a669d2434e408e43ad08ebf Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 27 Mar 2010 02:07:51 +0000 Subject: A little more DMA logic git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2556 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/sam3u/chip.h | 2 - nuttx/arch/arm/src/sam3u/sam3u_dmac.c | 211 +++++++++++++++++------------- nuttx/arch/arm/src/sam3u/sam3u_dmac.h | 2 + nuttx/arch/arm/src/sam3u/sam3u_hsmci.c | 12 +- nuttx/arch/arm/src/sam3u/sam3u_internal.h | 41 ++++-- 5 files changed, 152 insertions(+), 116 deletions(-) (limited to 'nuttx/arch/arm') diff --git a/nuttx/arch/arm/src/sam3u/chip.h b/nuttx/arch/arm/src/sam3u/chip.h index a867567e4..7e18e45c9 100755 --- a/nuttx/arch/arm/src/sam3u/chip.h +++ b/nuttx/arch/arm/src/sam3u/chip.h @@ -58,8 +58,6 @@ /* DMA */ # define CONFIG_SAM3U_NDMACHAN 4 /* 4 DMA Channels */ -# define CONFIG_SAM3U_DMACHAN8SET 0x07 /* DMA Channels 0-2 have 8-byte FIFOs */ -# define CONFIG_SAM3U_DMACHAN32SET 0x08 /* DMA channel 3 has a 32-byte FIFO */ /* Memory card interface */ diff --git a/nuttx/arch/arm/src/sam3u/sam3u_dmac.c b/nuttx/arch/arm/src/sam3u/sam3u_dmac.c index 79897783b..ea5a661fc 100755 --- a/nuttx/arch/arm/src/sam3u/sam3u_dmac.c +++ b/nuttx/arch/arm/src/sam3u/sam3u_dmac.c @@ -68,44 +68,54 @@ struct sam3u_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 */ + uint8_t chan; /* DMA channel number (0-6) */ + uint8_t fifosize; /* Size of DMA FIFO in btyes */ + bool inuse; /* TRUE: The DMA channel is in use */ + 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 */ + volatile uint16_t xfrsize; /* Total transfer size */ }; /**************************************************************************** * Private Data ****************************************************************************/ +/* This semaphore protects the DMA channel table */ + +static sem_t g_dmasem; + /* This array describes the state of each DMA */ +static struct sam3u_dma_s g_dma[CONFIG_SAM3U_NDMACHAN] = +{ +#ifdef CONFIG_ARCH_CHIP_AT91SAM3U4E + /* the AT91SAM3U4E has four DMA channels. The FIFOs for channels 0-2 are + * 8 bytes in size; channel 3 is 32 bytes. + */ + #if CONFIG_SAM3U_NDMACHAN != 4 # error "Logic here assumes CONFIG_SAM3U_NDMACHAN is 4" #endif -static struct sam3u_dma_s g_dma[CONFIG_SAM3U_NDMACHAN] = -{ { .chan = 0, -// .irq = SAM3U_IRQ_DMA1CH1, + .fifosize = 8, .base = SAM3U_DMACHAN0_BASE, }, { .chan = 1, -// .irq = SAM3U_IRQ_DMA1CH2, + .fifosize = 8, .base = SAM3U_DMACHAN1_BASE, }, { .chan = 2, -// .irq = SAM3U_IRQ_DMA1CH3, + .fifosize = 8, .base = SAM3U_DMACHAN2_BASE, }, { .chan = 3, -// .irq = SAM3U_IRQ_DMA1CH4, + .fifosize = 32, .base = SAM3U_DMACHAN3_BASE, } }; @@ -122,11 +132,11 @@ static struct sam3u_dma_s g_dma[CONFIG_SAM3U_NDMACHAN] = * ************************************************************************************/ -static void sam3u_dmatake(FAR struct sam3u_dma_s *dmach) +static void sam3u_dmatake(void) { /* Take the semaphore (perhaps waiting) */ - while (sem_wait(&dmach->sem) != 0) + while (sem_wait(&g_dmasem) != 0) { /* The only case that an error should occur here is if the wait was awakened * by a signal. @@ -136,27 +146,9 @@ static void sam3u_dmatake(FAR struct sam3u_dma_s *dmach) } } -static inline void sam3u_dmagive(FAR struct sam3u_dma_s *dmach) +static inline void sam3u_dmagive(void) { - (void)sem_post(&dmach->sem); -} - -/************************************************************************************ - * Name: sam3u_dmachandisable - * - * Description: - * Disable the DMA channel - * - ************************************************************************************/ - -static void sam3u_dmachandisable(struct sam3u_dma_s *dmach) -{ - /* Disable all interrupts at the DMA controller */ - - /* Disable the DMA channel */ - - /* Clear pending channel interrupts */ -# warning "Missing logic" + (void)sem_post(&g_dmasem); } /************************************************************************************ @@ -190,27 +182,30 @@ static int sam3u_dmainterrupt(int irq, void *context) void weak_function up_dmainitialize(void) { struct sam3u_dma_s *dmach; - int chndx; - /* Initialize each DMA channel */ + /* Enable peripheral clock */ - for (chndx = 0; chndx < CONFIG_SAM3U_NDMACHAN; chndx++) - { - dmach = &g_dma[chndx]; - sem_init(&dmach->sem, 0, 1); + putreg32((1 << SAM3U_PID_DMAC), SAM3U_PMC_PCER); - /* Attach DMA interrupt vectors */ + /* Disable all DMA interrupts */ -// (void)irq_attach(dmach->irq, sam3u_dmainterrupt); + putreg32(DMAC_DBC_ERR_ALLINTS, SAM3U_DMAC_EBCIDR); - /* Disable the DMA channel */ + /* Disable all DMA channels */ - sam3u_dmachandisable(dmach); + putreg32(DMAC_CHDR_DIS_ALL, SAM3U_DMAC_CHDR); - /* Enable the IRQ at the NVIC (still disabled at the DMA controller) */ + /* Attach DMA interrupt vector */ -// up_enable_irq(dmach->irq); - } + (void)irq_attach(SAM3U_IRQ_DMAC, sam3u_dmainterrupt); + + /* Enable the IRQ at the NVIC (still disabled at the DMA controller) */ + + up_enable_irq(SAM3U_IRQ_DMAC); + + /* Enable the DMA controller */ + + putreg32(DMAC_EN_ENABLE, SAM3U_DMAC_EN); } /**************************************************************************** @@ -218,46 +213,56 @@ void weak_function up_dmainitialize(void) * * 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 SAM3U: Devices sharing the same DMA - * channel cannot do DMA concurrently! See the DMACHAN_* definitions in - * sam3u_dma.h. - * - * If the DMA channel is not available, then sam3u_dmachannel() will wait - * until the holder of the channel relinquishes the channel by calling - * sam3u_dmafree(). WARNING: If you have two devices sharing a DMA - * channel and the code never releases the channel, the sam3u_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. + * sets aside a DMA channel with the required FIFO size and gives the + * caller exclusive access to the DMA channelt. * * 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. + * If a DMA channel if the required FIFO size is available, this function + * returns a non-NULL, void* DMA channel handle. NULL is returned on any + * failure. * ****************************************************************************/ -DMA_HANDLE sam3u_dmachannel(int chndx) +DMA_HANDLE sam3u_dmachannel(unsigned int fifosize) { - struct sam3u_dma_s *dmach = &g_dma[chndx]; - - DEBUGASSERT(chndx < CONFIG_SAM3U_NDMACHAN); + struct sam3u_dma_s *dmach; + unsigned int chndx; + uint32_t regval; - /* Get exclusive access to the DMA channel -- OR wait until the channel - * is available if it is currently being used by another driver + /* Search for an available DMA channel with at least the requested FIFO + * size. */ - sam3u_dmatake(dmach); + dmach = NULL; + sam3u_dmatake(); + for (chndx = 0; chndx < CONFIG_SAM3U_NDMACHAN; chndx++) + { + struct sam3u_dma_s *candidate = &g_dma[chndx]; + if (!candidate->inuse && candidate->fifosize >= fifosize) + { + dmach = candidate; + dmach->inuse = true; + break; + } + } + sam3u_dmagive(); + + /* Did we get one? */ - /* The caller now has exclusive use of the DMA channel */ + if (dmach) + { + /* Read the status register to clear any pending interrupts on the channel */ + + (void)getreg32(SAM3U_DMAC_EBCISR); + + /* Disable the channel by writing one to the write-only channel disable register */ + + putreg32(DMAC_CHDR_DIS(chndx), SAM3U_DMAC_CHDR); + + /* Initilize the transfer size */ + + dmach->xfrsize = 0; + } return (DMA_HANDLE)dmach; } @@ -266,41 +271,51 @@ DMA_HANDLE sam3u_dmachannel(int chndx) * Name: sam3u_dmafree * * Description: - * Release a DMA channel. If another thread is waiting for this DMA channel - * in a call to sam3u_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 sam3u_dmachannel() is - * called again to re-gain access to the channel. + * Release a DMA channel. NOTE: The 'handle' used in this argument must + * NEVER be used again until sam3u_dmachannel() is called again to re-gain + * a valid handle. * * Returned Value: * None * - * Assumptions: - * - The caller holds the DMA channel. - * - There is no DMA in progress - * ****************************************************************************/ void sam3u_dmafree(DMA_HANDLE handle) { struct sam3u_dma_s *dmach = (struct sam3u_dma_s *)handle; - DEBUGASSERT(handle != NULL); + /* Mark the channel no longer in use. This is an atomic operation and so + * should be safe. + */ - /* Release the channel */ + DEBUGASSERT(dmach != NULL); + dmach->inuse = true; +} - sam3u_dmagive(dmach); +/**************************************************************************** + * Name: sam3u_dmatxsetup + * + * Description: + * Configure DMA for transmit (memory to peripheral) before using + * + ****************************************************************************/ + +void sam3u_dmarxsetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, size_t ntransfers, uint32_t ccr) +{ + struct sam3u_dma_s *dmach = (struct sam3u_dma_s *)handle; + uint32_t regval; +# warning "Missing logic" } /**************************************************************************** - * Name: sam3u_dmasetup + * Name: sam3u_dmarxsetup * * Description: - * Configure DMA before using + * Configure DMA for receuve (peripheral to memory) before using * ****************************************************************************/ -void sam3u_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, size_t ntransfers, uint32_t ccr) +void sam3u_dmarxsetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, size_t ntransfers, uint32_t ccr) { struct sam3u_dma_s *dmach = (struct sam3u_dma_s *)handle; uint32_t regval; @@ -348,7 +363,11 @@ void sam3u_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool void sam3u_dmastop(DMA_HANDLE handle) { struct sam3u_dma_s *dmach = (struct sam3u_dma_s *)handle; - sam3u_dmachandisable(dmach); + + /* Disable the channel by writing one to the write-only channel disable register */ + + DEBUGASSERT(dmach != NULL); + putreg32(DMAC_CHDR_DIS(dmach->chan), SAM3U_DMAC_CHDR); } /**************************************************************************** @@ -368,7 +387,11 @@ void sam3u_dmasample(DMA_HANDLE handle, struct sam3u_dmaregs_s *regs) struct sam3u_dma_s *dmach = (struct sam3u_dma_s *)handle; irqstate_t flags; - /* Sample global registers */ + /* Sample global registers. NOTE: reading EBCISR clears interrupts, but + * that should be okay IF interrupts are enabled when this function is + * called. But there is a race condition where this instrumentation could + * cause lost interrupts. + */ flags = irqsave(); regs->gcfg = getreg32(SAM3U_DMAC_GCFG); diff --git a/nuttx/arch/arm/src/sam3u/sam3u_dmac.h b/nuttx/arch/arm/src/sam3u/sam3u_dmac.h index 723529eff..874e710cd 100755 --- a/nuttx/arch/arm/src/sam3u/sam3u_dmac.h +++ b/nuttx/arch/arm/src/sam3u/sam3u_dmac.h @@ -263,6 +263,7 @@ # define DMAC_EBC_ERR1 (1 << (DMAC_EBC_ERR_SHIFT+1)) # define DMAC_EBC_ERR2 (1 << (DMAC_EBC_ERR_SHIFT+2)) # define DMAC_EBC_ERR3 (1 << (DMAC_EBC_ERR_SHIFT+3)) +#define DMAC_DBC_ERR_ALLINTS (0x000f0f0f) /* DMAC Channel Handler Enable Register */ @@ -297,6 +298,7 @@ # define DMAC_CHDR_DIS1 (1 << (DMAC_CHDR_DIS_SHIFT+1)) # define DMAC_CHDR_DIS2 (1 << (DMAC_CHDR_DIS_SHIFT+2)) # define DMAC_CHDR_DIS3 (1 << (DMAC_CHDR_DIS_SHIFT+3)) +# define DMAC_CHDR_DIS_ALL DMAC_CHDR_DIS_MASK #define DMAC_CHDR_RES_SHIFT (8) /* Bits 8-11: Resume trasnfer, restoring context */ #define DMAC_CHDR_RES_MASK (15 << DMAC_CHDR_RES_SHIFT) # define DMAC_CHDR_RES(n) (1 << (DMAC_CHDR_RES_SHIFT+(n))) diff --git a/nuttx/arch/arm/src/sam3u/sam3u_hsmci.c b/nuttx/arch/arm/src/sam3u/sam3u_hsmci.c index 64bef3ff0..94a8b7d91 100755 --- a/nuttx/arch/arm/src/sam3u/sam3u_hsmci.c +++ b/nuttx/arch/arm/src/sam3u/sam3u_hsmci.c @@ -2346,8 +2346,8 @@ static int sam3u_dmarecvsetup(FAR struct sdio_dev_s *dev, FAR uint8_t *buffer, sam3u_enablexfrints(priv, HSMCI_DMARECV_INTS); putreg32(1, HSMCI_DCTRL_DMAEN_BB); - sam3u_dmasetup(priv->dma, SAM3U_HSMCI_FIFO, (uint32_t)buffer, - (buflen + 3) >> 2, HSMCI_RXDMA32_CONFIG); + sam3u_dmarxsetup(priv->dma, SAM3U_HSMCI_FIFO, (uint32_t)buffer, + (buflen + 3) >> 2, HSMCI_RXDMA32_CONFIG); /* Start the DMA */ @@ -2412,8 +2412,8 @@ static int sam3u_dmasendsetup(FAR struct sdio_dev_s *dev, /* Configure the TX DMA */ - sam3u_dmasetup(priv->dma, SAM3U_HSMCI_FIFO, (uint32_t)buffer, - (buflen + 3) >> 2, HSMCI_TXDMA32_CONFIG); + sam3u_dmatxsetup(priv->dma, SAM3U_HSMCI_FIFO, (uint32_t)buffer, + (buflen + 3) >> 2, HSMCI_TXDMA32_CONFIG); sam3u_sample(priv, SAMPLENDX_BEFORE_ENABLE); putreg32(1, HSMCI_DCTRL_DMAEN_BB); @@ -2543,9 +2543,9 @@ FAR struct sdio_dev_s *sdio_initialize(int slotno) priv->waitwdog = wd_create(); DEBUGASSERT(priv->waitwdog); - /* Allocate a DMA channel */ + /* Allocate a DMA channel. A FIFO size of 8 is sufficient. */ - priv->dma = sam3u_dmachannel(); + priv->dma = sam3u_dmachannel(8); DEBUGASSERT(priv->dma); /* Configure GPIOs for 4-bit, wide-bus operation. NOTE: (1) the chip is capable of diff --git a/nuttx/arch/arm/src/sam3u/sam3u_internal.h b/nuttx/arch/arm/src/sam3u/sam3u_internal.h index 56bb79641..b27a6ba1f 100755 --- a/nuttx/arch/arm/src/sam3u/sam3u_internal.h +++ b/nuttx/arch/arm/src/sam3u/sam3u_internal.h @@ -461,41 +461,54 @@ EXTERN void sam3u_gpioirqdisable(int irq); * Name: sam3u_dmachannel * * Description: - * Allocate a DMA channel. This function sets aside a DMA channel and - * gives the caller mutually exclusive access to the DMA channel. + * Allocate a DMA channel. This function gives the caller mutually + * sets aside a DMA channel with the required FIFO size and gives the + * caller exclusive access to the DMA channelt. * * Returned Value: - * One success, this function ALWAYS will return a non-NULL, DMA channel - * handle. + * If a DMA channel if the required FIFO size is available, this function + * returns a non-NULL, void* DMA channel handle. NULL is returned on any + * failure. * ****************************************************************************/ -EXTERN DMA_HANDLE sam3u_dmachannel(void); +EXTERN DMA_HANDLE sam3u_dmachannel(unsigned int fifosize); /**************************************************************************** * Name: sam3u_dmafree * * Description: * Release a DMA channel. NOTE: The 'handle' used in this argument must - * NEVER be used again until sam3u_dmachannel() is called again to - * re-allocate the channel. + * NEVER be used again until sam3u_dmachannel() is called again to re-gain + * a valid handle. * * Returned Value: * None * + ****************************************************************************/ + +EXTERN void sam3u_dmafree(DMA_HANDLE handle); + +/**************************************************************************** + * Name: sam3u_dmatxsetup + * + * Description: + * Configure DMA for transmit (memory to periphal) before using + * * Assumptions: - * - The caller holds the DMA channel. - * - There is no DMA in progress + * - DMA handle allocated by sam3u_dmachannel() + * - No DMA in progress * ****************************************************************************/ -EXTERN void sam3u_dmafree(DMA_HANDLE handle); +EXTERN void sam3u_dmatxsetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, + size_t ntransfers, uint32_t ccr); /**************************************************************************** - * Name: sam3u_dmasetup + * Name: sam3u_dmarxsetup * * Description: - * Configure DMA before using + * Configure DMA for receive (peripheral to memory) before using * * Assumptions: * - DMA handle allocated by sam3u_dmachannel() @@ -503,8 +516,8 @@ EXTERN void sam3u_dmafree(DMA_HANDLE handle); * ****************************************************************************/ -EXTERN void sam3u_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, - size_t ntransfers, uint32_t ccr); +EXTERN void sam3u_dmarxsetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, + size_t ntransfers, uint32_t ccr); /**************************************************************************** * Name: sam3u_dmastart -- cgit v1.2.3