Browse Source

Implement non-stop DMA mode (circular) for the F1x DMA driver.

sbg
px4dev 12 years ago
parent
commit
770f2545fb
  1. 38
      nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c

38
nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c

@ -90,6 +90,7 @@ struct stm32_dma_s @@ -90,6 +90,7 @@ struct stm32_dma_s
{
uint8_t chan; /* DMA channel number (0-6) */
uint8_t irq; /* DMA channel IRQ number */
bool nonstop; /* Stream is configured in non-stopping mode */
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 */
@ -303,14 +304,10 @@ static int stm32_dmainterrupt(int irq, void *context) @@ -303,14 +304,10 @@ static int stm32_dmainterrupt(int irq, void *context)
}
dmach = &g_dma[chndx];
/* Get the interrupt status (for this channel only) -- not currently used */
/* Get the interrupt status (for this channel only) */
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)
@ -493,6 +490,7 @@ void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, size_t nt @@ -493,6 +490,7 @@ void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, size_t nt
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;
dmach->nonstop = (ccr & DMA_CCR_CIRC) != 0;
dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, regval);
}
@ -528,14 +526,30 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool @@ -528,14 +526,30 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
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.
*/
if (!dmach->nonstop)
{
/* 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));
}
else
{
/* In nonstop mode, when the transfer completes it immediately resets
* and starts again. The transfer-complete interrupt is thus always
* enabled, and the half-complete interrupt can be used in circular
* mode to determine when the buffer is half-full, or in double-buffered
* mode to determine when one of the two buffers is full.
*/
ccr |= (half ? DMA_CCR_HTIE : 0) | DMA_CCR_TCIE | DMA_CCR_TEIE;
}
ccr |= (half ? (DMA_CCR_HTIE|DMA_CCR_TEIE) : (DMA_CCR_TCIE|DMA_CCR_TEIE));
dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, ccr);
}

Loading…
Cancel
Save