More STM32 SDIO DMA fixes

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4407 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-02-21 00:21:26 +00:00
parent bf06e16a5f
commit 070f707e7d
5 changed files with 70 additions and 18 deletions

View File

@ -393,7 +393,7 @@
#define STM32_DMA_MAP(d,s,c) ((d) << 6 | (s) << 3 | (c))
#define STM32_DMA_CONTROLLER(m) (((m) >> 6) & 1)
#define STM32_DMA_STREAM(m) (((m) >> 3) & 7)
#define STM32_DMA_CHAN(c) ((c) & 7)
#define STM32_DMA_CHANNEL(m) ((m) & 7)
#define DMAMAP_SPI3_RX_1 STM32_DMA_MAP(DMA1,DMA_STREAM0,DMA_CHAN0)
#define DMAMAP_SPI3_RX_2 STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN0)

View File

@ -1,7 +1,7 @@
/****************************************************************************************************
* arch/arm/src/stm32/chip/stm32f40xxx_rcc.h
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -240,7 +240,7 @@
#define RCC_AHB1RSTR_GPIOGRST (1 << 6) /* Bit 6: IO port G reset */
#define RCC_AHB1RSTR_GPIOHRST (1 << 7) /* Bit 7: IO port H reset */
#define RCC_AHB1RSTR_CRCRST (1 << 12) /* Bit 12 IO port I reset */
#define RCC_AHB1RSTR_DMA1RST (1 << 21) /* Bit 21: DMA2 reset */
#define RCC_AHB1RSTR_DMA1RST (1 << 21) /* Bit 21: DMA1 reset */
#define RCC_AHB1RSTR_DMA2RST (1 << 22) /* Bit 22: DMA2 reset */
#define RCC_AHB1RSTR_ETHMACRST (1 << 25) /* Bit 25: Ethernet MAC reset */
#define RCC_AHB1RSTR_OTGHSRST (1 << 29) /* Bit 29: USB OTG HS module reset */

View File

@ -188,7 +188,26 @@
# define SDIO_TXDMA32_CONFIG (CONFIG_SDIO_DMAPRIO|DMA_CCR_MSIZE_32BITS|\
DMA_CCR_PSIZE_32BITS|DMA_CCR_MINC|DMA_CCR_DIR)
/* STM32 F4 stream configuration register (SCR) settings. */
/* STM32 F4 stream configuration register (SCR) settings.
*
* Hmmm... I see conflicting statements in the Reference Manual. In the DMA
* section it says:
* "Note: The Burst mode is allowed only when incremetation is enabled:
* When the PINC bit is at 0, the PBURST bits should also be cleared to 00
* When the MINC bit is at 0, the MBURST bits should also be cleared to 00."
*
* But in the SDIO section it says:
*
* "4. Configure the DMA2 as follows:
* ...
* c) Program DMA2_Stream3 or DMA2_Stream6 Channel4 control register
* (memory increment, not peripheral increment, peripheral and source
* width is word size).
* ...
* e) Configure the incremental burst transfer to 4 beats (at least from
* peripheral side)..."
*/
#elif defined(CONFIG_STM32_STM32F40XX)
# define SDIO_RXDMA32_CONFIG (DMA_SCR_PFCTRL|DMA_SCR_DIR_P2M|DMA_SCR_MINC|\

View File

@ -93,7 +93,7 @@ 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 */
uint8_t channel; /* DMA channel number (0-7) */
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 */
@ -373,37 +373,61 @@ static void stm32_dmastreamdisable(struct stm32_dma_s *dmast)
static int stm32_dmainterrupt(int irq, void *context)
{
struct stm32_dma_s *dmast;
uint32_t isr;
uint32_t status;
uint32_t regoffset = 0;
unsigned int stream = 0;
unsigned int controller = 0;
/* Get the stream structure from the interrupt number */
/* Get the stream and the controller that generated the interrupt */
if (irq >= STM32_IRQ_DMA1S0 && irq <= STM32_IRQ_DMA1S7)
if (irq >= STM32_IRQ_DMA1S0 && irq <= STM32_IRQ_DMA1S6)
{
stream = irq - STM32_IRQ_DMA1S0;
controller = DMA1;
regoffset = STM32_DMA_LISR_OFFSET;
}
else if (irq == STM32_IRQ_DMA1S7)
{
stream = 7;
controller = DMA1;
}
else
#if STM32_NDMA > 1
if (irq >= STM32_IRQ_DMA2S0 && irq <= STM32_IRQ_DMA2S7)
if (irq >= STM32_IRQ_DMA2S0 && irq <= STM32_IRQ_DMA2S4)
{
stream = irq - STM32_IRQ_DMA2S0 + DMA1_NSTREAMS;
stream = irq - STM32_IRQ_DMA2S0;
controller = DMA2;
}
else if (irq >= STM32_IRQ_DMA2S5 && irq <= STM32_IRQ_DMA2S7)
{
stream = irq - STM32_IRQ_DMA2S5 + 5;
controller = DMA2;
regoffset = STM32_DMA_HISR_OFFSET;
}
else
#endif
{
PANIC(OSERR_INTERNAL);
}
/* Get the stream structure from the stream and controller numbers */
dmast = stm32_dmastream(stream, controller);
/* Select the interrupt status register (either the LISR or HISR)
* based on the stream number that caused the interrupt.
*/
if (stream < 4)
{
regoffset = STM32_DMA_LISR_OFFSET;
}
else
{
regoffset = STM32_DMA_HISR_OFFSET;
}
/* Get the interrupt status for this stream */
isr = (dmabase_getreg(dmast, regoffset) >> dmast->shift) & DMA_STREAM_MASK;
status = (dmabase_getreg(dmast, regoffset) >> dmast->shift) & DMA_STREAM_MASK;
/* Disable the DMA stream */
@ -413,7 +437,7 @@ static int stm32_dmainterrupt(int irq, void *context)
if (dmast->callback)
{
dmast->callback(dmast, isr, dmast->arg);
dmast->callback(dmast, status, dmast->arg);
}
return OK;
}
@ -515,8 +539,12 @@ DMA_HANDLE stm32_dmachannel(unsigned int dmamap)
stm32_dmatake(dmast);
/* The caller now has exclusive use of the DMA channel */
/* The caller now has exclusive use of the DMA channel. Assign the
* channel to the stream and return an opaque reference to the stream
* structure.
*/
dmast->channel = STM32_DMA_CHANNEL(dmamap);
return (DMA_HANDLE)dmast;
}
@ -617,6 +645,11 @@ void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t 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."
*
* "When the peripheral flow controller is used for a given stream, the value
* written into the DMA_SxNDTR has no effect on the DMA transfer. Actually,
* whatever the value written, it will be forced by hardware to 0xFFFF as soon
* as the stream is enabled..."
*/
dmast_putreg(dmast, STM32_DMA_SNDTR_OFFSET, ntransfers);
@ -630,7 +663,7 @@ void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
regval = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
regval &= ~(DMA_SCR_PL_MASK|DMA_SCR_CHSEL_MASK);
regval |= scr & DMA_SCR_PL_MASK;
regval |= (uint32_t)dmast->stream << DMA_SCR_CHSEL_SHIFT;
regval |= (uint32_t)dmast->channel << DMA_SCR_CHSEL_SHIFT;
dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, regval);
/* "Configure the FIFO usage (enable or disable, threshold in transmission and

View File

@ -1,8 +1,8 @@
/****************************************************************************
* arch/arm/src/stm32/stm32f40xxx_rcc.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Copyright (C) 2011-2012 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