forked from Archive/PX4-Autopilot
Various STM32 SDIO and DMA fixes (SDIO DMA still does not work)
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4406 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
parent
12fd26bd67
commit
bf06e16a5f
|
@ -1,7 +1,7 @@
|
||||||
/************************************************************************************
|
/************************************************************************************
|
||||||
* arch/arm/src/stm32/chip/stm32_sdio.h
|
* arch/arm/src/stm32/chip/stm32_sdio.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>
|
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
|
|
@ -355,6 +355,27 @@
|
||||||
#define DMA_SNDTR_NDT_SHIFT (0) /* Bits 15-0: Number of data to Transfer */
|
#define DMA_SNDTR_NDT_SHIFT (0) /* Bits 15-0: Number of data to Transfer */
|
||||||
#define DMA_SNDTR_NDT_MASK (0xffff << DMA_SNDTR_NDT_SHIFT)
|
#define DMA_SNDTR_NDT_MASK (0xffff << DMA_SNDTR_NDT_SHIFT)
|
||||||
|
|
||||||
|
/* DMA stream n FIFO control register */
|
||||||
|
|
||||||
|
#define DMA_SFCR_FTH_SHIFT (0) /* Bits 0-1: FIFO threshold selection */
|
||||||
|
#define DMA_SFCR_FTH_MASK (3 << DMA_SFCR_FTH_SHIFT)
|
||||||
|
# define DMA_SFCR_FTH_QUARTER (0 << DMA_SFCR_FTH_SHIFT) /* 1/4 full FIFO */
|
||||||
|
# define DMA_SFCR_FTH_HALF (1 << DMA_SFCR_FTH_SHIFT) /* 1/2 full FIFO */
|
||||||
|
# define DMA_SFCR_FTH_3QUARTER (2 << DMA_SFCR_FTH_SHIFT) /* 3/4 full FIFO */
|
||||||
|
# define DMA_SFCR_FTH_FULL (3 << DMA_SFCR_FTH_SHIFT) /* full FIFO */
|
||||||
|
#define DMA_SFCR_DMDIS (1 << 2) /* Bit 2: Direct mode disable */
|
||||||
|
#define DMA_SFCR_FS_SHIFT (3) /* Bits 3-5: FIFO status */
|
||||||
|
#define DMA_SFCR_FS_MASK (7 << DMA_SFCR_FS_SHIFT)
|
||||||
|
# define DMA_SFCR_FS_QUARTER (0 << DMA_SFCR_FS_SHIFT) /* 0 < fifo_level < 1/4 */
|
||||||
|
# define DMA_SFCR_FS_HALF (1 << DMA_SFCR_FS_SHIFT) /* 1/4 = fifo_level < 1/2 */
|
||||||
|
# define DMA_SFCR_FS_3QUARTER (2 << DMA_SFCR_FS_SHIFT) /* 1/2 = fifo_level < 3/4 */
|
||||||
|
# define DMA_SFCR_FS_ALMOSTFULL (3 << DMA_SFCR_FS_SHIFT) /* 3/4 = fifo_level < full */
|
||||||
|
# define DMA_SFCR_FS_EMPTY (4 << DMA_SFCR_FS_SHIFT) /* FIFO is empty */
|
||||||
|
# define DMA_SFCR_FS_FULL (5 << DMA_SFCR_FS_SHIFT) /* FIFO is full */
|
||||||
|
/* Bit 6: Reserved */
|
||||||
|
#define DMA_SFCR_FEIE (1 << 7) /* Bit 7: FIFO error interrupt enable */
|
||||||
|
/* Bits 8-31: Reserved */
|
||||||
|
|
||||||
/* DMA Stream mapping. Each DMA stream has a mapping to several possible
|
/* DMA Stream mapping. Each DMA stream has a mapping to several possible
|
||||||
* sources/sinks of data. The requests from peripherals assigned to a stream
|
* sources/sinks of data. The requests from peripherals assigned to a stream
|
||||||
* are simply OR'ed together before entering the DMA block. This means that only
|
* are simply OR'ed together before entering the DMA block. This means that only
|
||||||
|
@ -369,7 +390,7 @@
|
||||||
* #define DMAMAP_SPI3_RX DMAMAP_SPI3_RX_1
|
* #define DMAMAP_SPI3_RX DMAMAP_SPI3_RX_1
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define STM32_DMA_MAP(d,c,s) ((d) << 6 | (s) << 3 | (c))
|
#define STM32_DMA_MAP(d,s,c) ((d) << 6 | (s) << 3 | (c))
|
||||||
#define STM32_DMA_CONTROLLER(m) (((m) >> 6) & 1)
|
#define STM32_DMA_CONTROLLER(m) (((m) >> 6) & 1)
|
||||||
#define STM32_DMA_STREAM(m) (((m) >> 3) & 7)
|
#define STM32_DMA_STREAM(m) (((m) >> 3) & 7)
|
||||||
#define STM32_DMA_CHAN(c) ((c) & 7)
|
#define STM32_DMA_CHAN(c) ((c) & 7)
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
/************************************************************************************
|
/************************************************************************************
|
||||||
* arch/arm/src/stm32/chip/stm32f40xxx_memorymap.h
|
* arch/arm/src/stm32/chip/stm32f40xxx_memorymap.h
|
||||||
*
|
*
|
||||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
|
|
@ -54,9 +54,18 @@
|
||||||
************************************************************************************/
|
************************************************************************************/
|
||||||
|
|
||||||
/* Additional Configuration *********************************************************/
|
/* Additional Configuration *********************************************************/
|
||||||
|
/* Custom debug settings used in the STM32 port. These are managed by STM32-specific
|
||||||
|
* logic and not the common logic in include/debug.h. NOTE: Some of these also
|
||||||
|
* depend on CONFIG_DEBUG_VERBOSE
|
||||||
|
*/
|
||||||
|
|
||||||
#if !defined(CONFIG_DEBUG) || !defined(CONFIG_DEBUG_VERBOSE)
|
#ifndef CONFIG_DEBUG
|
||||||
# undef CONFIG_DEBUG_DMA
|
# undef CONFIG_DEBUG_DMA
|
||||||
|
# undef CONFIG_DEBUG_RTC
|
||||||
|
# undef CONFIG_DEBUG_I2C
|
||||||
|
# undef CONFIG_DEBUG_CAN
|
||||||
|
# undef CONFIG_DEBUG_PWM
|
||||||
|
# undef CONFIG_DEBUG_QENCODER
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* NVIC priority levels *************************************************************/
|
/* NVIC priority levels *************************************************************/
|
||||||
|
|
|
@ -71,6 +71,32 @@
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
/* Configuration ************************************************************/
|
/* Configuration ************************************************************/
|
||||||
|
/* Required system configuration options:
|
||||||
|
*
|
||||||
|
* CONFIG_ARCH_DMA - Enable architecture-specific DMA subsystem
|
||||||
|
* initialization. Required if CONFIG_SDIO_DMA is enabled.
|
||||||
|
* CONFIG_STM32_DMA2 - Enable STM32 DMA2 support. Required if
|
||||||
|
* CONFIG_SDIO_DMA is enabled
|
||||||
|
* CONFIG_SCHED_WORKQUEUE -- Callback support requires work queue support.
|
||||||
|
*
|
||||||
|
* Driver-specific configuration options:
|
||||||
|
*
|
||||||
|
* CONFIG_SDIO_MUXBUS - Setting this configuration enables some locking
|
||||||
|
* APIs to manage concurrent accesses on the SDIO bus. This is not
|
||||||
|
* needed for the simple case of a single SD card, for example.
|
||||||
|
* CONFIG_SDIO_DMA - Enable SDIO. This is a marginally optional. For
|
||||||
|
* most usages, SDIO will cause data overruns if used without DMA.
|
||||||
|
* NOTE the above system DMA configuration options.
|
||||||
|
* CONFIG_SDIO_WIDTH_D1_ONLY - This may be selected to force the driver
|
||||||
|
* operate with only a single data line (the default is to use all
|
||||||
|
* 4 SD data lines).
|
||||||
|
* CONFIG_SDIO_PRI - SDIO interrupt priority. This setting is not very
|
||||||
|
* important since interrupt nesting is not currently supported.
|
||||||
|
* CONFIG_SDM_DMAPRIO - SDIO DMA priority. This can be selecte if
|
||||||
|
* CONFIG_SDIO_DMA is enabled.
|
||||||
|
* CONFIG_SDIO_XFRDEBUG - Enables some very low-level debug output
|
||||||
|
* This also requires CONFIG_DEBUG_FS and CONFIG_DEBUG_VERBOSE
|
||||||
|
*/
|
||||||
|
|
||||||
#if defined(CONFIG_SDIO_DMA) && !defined(CONFIG_STM32_DMA2)
|
#if defined(CONFIG_SDIO_DMA) && !defined(CONFIG_STM32_DMA2)
|
||||||
# warning "CONFIG_SDIO_DMA support requires CONFIG_STM32_DMA2"
|
# warning "CONFIG_SDIO_DMA support requires CONFIG_STM32_DMA2"
|
||||||
|
@ -88,17 +114,32 @@
|
||||||
# define CONFIG_SDIO_PRI NVIC_SYSH_PRIORITY_DEFAULT
|
# define CONFIG_SDIO_PRI NVIC_SYSH_PRIORITY_DEFAULT
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef CONFIG_SDIO_DMAPRIO
|
#ifdef CONFIG_SDIO_DMA
|
||||||
|
# ifndef CONFIG_SDIO_DMAPRIO
|
||||||
|
# if defined(CONFIG_STM32_STM32F10XX)
|
||||||
|
# define CONFIG_SDIO_DMAPRIO DMA_CCR_PRIMED
|
||||||
|
# elif defined(CONFIG_STM32_STM32F40XX)
|
||||||
|
# define CONFIG_SDIO_DMAPRIO DMA_SCR_PRIMED
|
||||||
|
# else
|
||||||
|
# error "Unknown STM32 DMA"
|
||||||
|
# endif
|
||||||
|
# endif
|
||||||
# if defined(CONFIG_STM32_STM32F10XX)
|
# if defined(CONFIG_STM32_STM32F10XX)
|
||||||
# define CONFIG_SDIO_DMAPRIO DMA_CCR_PRIMED
|
# if (CONFIG_SDIO_DMAPRIO & ~DMA_CCR_PL_MASK) != 0
|
||||||
|
# error "Illegal value for CONFIG_SDIO_DMAPRIO"
|
||||||
|
# endif
|
||||||
# elif defined(CONFIG_STM32_STM32F40XX)
|
# elif defined(CONFIG_STM32_STM32F40XX)
|
||||||
# define CONFIG_SDIO_DMAPRIO DMA_SCR_PRIMED
|
# if (CONFIG_SDIO_DMAPRIO & ~DMA_SCR_PL_MASK) != 0
|
||||||
|
# error "Illegal value for CONFIG_SDIO_DMAPRIO"
|
||||||
|
# endif
|
||||||
# else
|
# else
|
||||||
# error "Unknown STM32 DMA"
|
# error "Unknown STM32 DMA"
|
||||||
# endif
|
# endif
|
||||||
|
#else
|
||||||
|
# undef CONFIG_SDIO_DMAPRIO
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !defined(CONFIG_DEBUG_FS) || !defined(CONFIG_DEBUG_VERBOSE)
|
#if !defined(CONFIG_DEBUG_FS) || !defined(CONFIG_DEBUG)
|
||||||
# undef CONFIG_SDIO_XFRDEBUG
|
# undef CONFIG_SDIO_XFRDEBUG
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -147,15 +188,17 @@
|
||||||
# define SDIO_TXDMA32_CONFIG (CONFIG_SDIO_DMAPRIO|DMA_CCR_MSIZE_32BITS|\
|
# define SDIO_TXDMA32_CONFIG (CONFIG_SDIO_DMAPRIO|DMA_CCR_MSIZE_32BITS|\
|
||||||
DMA_CCR_PSIZE_32BITS|DMA_CCR_MINC|DMA_CCR_DIR)
|
DMA_CCR_PSIZE_32BITS|DMA_CCR_MINC|DMA_CCR_DIR)
|
||||||
|
|
||||||
/* STM32 F4 stream configuration register (SCR) settings */
|
/* STM32 F4 stream configuration register (SCR) settings. */
|
||||||
|
|
||||||
#elif defined(CONFIG_STM32_STM32F40XX)
|
#elif defined(CONFIG_STM32_STM32F40XX)
|
||||||
# define SDIO_RXDMA32_CONFIG (CONFIG_SDIO_DMAPRIO|DMA_SCR_MSIZE_32BITS|\
|
# define SDIO_RXDMA32_CONFIG (DMA_SCR_PFCTRL|DMA_SCR_DIR_P2M|DMA_SCR_MINC|\
|
||||||
DMA_SCR_PSIZE_32BITS|DMA_SCR_MINC|DMA_SCR_DIR_P2M|\
|
DMA_SCR_PSIZE_32BITS|DMA_SCR_MSIZE_32BITS|\
|
||||||
DMA_SCR_PBURST_SINGLE|DMA_SCR_PBURST_INCR8)
|
CONFIG_SDIO_DMAPRIO|DMA_SCR_PBURST_INCR4|\
|
||||||
# define SDIO_TXDMA32_CONFIG (CONFIG_SDIO_DMAPRIO|DMA_SCR_MSIZE_32BITS|\
|
DMA_SCR_MBURST_INCR4)
|
||||||
DMA_SCR_PSIZE_32BITS|DMA_SCR_MINC|DMA_SCR_DIR_M2P|\
|
# define SDIO_TXDMA32_CONFIG (DMA_SCR_PFCTRL|DMA_SCR_DIR_M2P|DMA_SCR_MINC|\
|
||||||
DMA_SCR_PBURST_SINGLE|DMA_SCR_PBURST_INCR8)
|
DMA_SCR_PSIZE_32BITS|DMA_SCR_MSIZE_32BITS|\
|
||||||
|
CONFIG_SDIO_DMAPRIO|DMA_SCR_PBURST_INCR4|\
|
||||||
|
DMA_SCR_MBURST_INCR4)
|
||||||
#else
|
#else
|
||||||
# error "Unknown STM32 DMA"
|
# error "Unknown STM32 DMA"
|
||||||
#endif
|
#endif
|
||||||
|
@ -765,7 +808,7 @@ static void stm32_dumpsample(struct stm32_dev_s *priv,
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
#ifdef CONFIG_SDIO_XFRDEBUG
|
#ifdef CONFIG_SDIO_XFRDEBUG
|
||||||
static void stm32_dumpsamples(struct stm32_dev_s *priv)
|
static void stm32_dumpsamples(struct stm32_dev_s *priv)
|
||||||
{
|
{
|
||||||
stm32_dumpsample(priv, &g_sampleregs[SAMPLENDX_BEFORE_SETUP], "Before setup");
|
stm32_dumpsample(priv, &g_sampleregs[SAMPLENDX_BEFORE_SETUP], "Before setup");
|
||||||
#if defined(CONFIG_DEBUG_DMA) && defined(CONFIG_SDIO_DMA)
|
#if defined(CONFIG_DEBUG_DMA) && defined(CONFIG_SDIO_DMA)
|
||||||
|
@ -2282,6 +2325,7 @@ static sdio_eventset_t stm32_eventwait(FAR struct sdio_dev_s *dev,
|
||||||
|
|
||||||
errout:
|
errout:
|
||||||
irqrestore(flags);
|
irqrestore(flags);
|
||||||
|
stm32_dumpsamples(priv);
|
||||||
return wkupevent;
|
return wkupevent;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2438,7 +2482,7 @@ static int stm32_dmarecvsetup(FAR struct sdio_dev_s *dev, FAR uint8_t *buffer,
|
||||||
stm32_dmasetup(priv->dma, STM32_SDIO_FIFO, (uint32_t)buffer,
|
stm32_dmasetup(priv->dma, STM32_SDIO_FIFO, (uint32_t)buffer,
|
||||||
(buflen + 3) >> 2, SDIO_RXDMA32_CONFIG);
|
(buflen + 3) >> 2, SDIO_RXDMA32_CONFIG);
|
||||||
|
|
||||||
/* Start the DMA */
|
/* Start the DMA */
|
||||||
|
|
||||||
stm32_sample(priv, SAMPLENDX_BEFORE_ENABLE);
|
stm32_sample(priv, SAMPLENDX_BEFORE_ENABLE);
|
||||||
stm32_dmastart(priv->dma, stm32_dmacallback, priv, false);
|
stm32_dmastart(priv->dma, stm32_dmacallback, priv, false);
|
||||||
|
@ -2660,6 +2704,7 @@ FAR struct sdio_dev_s *sdio_initialize(int slotno)
|
||||||
|
|
||||||
#ifdef CONFIG_SDIO_DMA
|
#ifdef CONFIG_SDIO_DMA
|
||||||
priv->dma = stm32_dmachannel(SDIO_DMACHAN);
|
priv->dma = stm32_dmachannel(SDIO_DMACHAN);
|
||||||
|
DEBUGASSERT(priv->dma);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* Configure GPIOs for 4-bit, wide-bus operation (the chip is capable of
|
/* Configure GPIOs for 4-bit, wide-bus operation (the chip is capable of
|
||||||
|
|
|
@ -270,6 +270,59 @@ static inline void stm32_dmagive(FAR struct stm32_dma_s *dmast)
|
||||||
(void)sem_post(&dmast->sem);
|
(void)sem_post(&dmast->sem);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_dmastream
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Get the g_dma table entry associated with a DMA controller and a stream number
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
static inline FAR struct stm32_dma_s *stm32_dmastream(unsigned int stream,
|
||||||
|
unsigned int controller)
|
||||||
|
{
|
||||||
|
int index;
|
||||||
|
|
||||||
|
DEBUGASSERT(stream < DMA_NSTREAMS && controller < STM32_NDMA);
|
||||||
|
|
||||||
|
/* Convert the controller + stream based on the fact that there are 8 streams
|
||||||
|
* per controller.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if STM32_NDMA > 1
|
||||||
|
index = controller << 3 | stream;
|
||||||
|
#else
|
||||||
|
index = stream;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Then return the stream structure associated with the stream index */
|
||||||
|
|
||||||
|
return &g_dma[index];
|
||||||
|
}
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_dmamap
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Get the g_dma table entry associated with a bit-encoded DMA selection
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
static inline FAR struct stm32_dma_s *stm32_dmamap(unsigned long dmamap)
|
||||||
|
{
|
||||||
|
/* Extract the DMA controller number from the bit encoded value */
|
||||||
|
|
||||||
|
unsigned int controller = STM32_DMA_CONTROLLER(dmamap);
|
||||||
|
|
||||||
|
/* Extact the stream number from the bit encoded value */
|
||||||
|
|
||||||
|
unsigned int stream = STM32_DMA_STREAM(dmamap);
|
||||||
|
|
||||||
|
/* Return the table entry associated with the controller + stream */
|
||||||
|
|
||||||
|
return stm32_dmastream(stream, controller);
|
||||||
|
}
|
||||||
|
|
||||||
/************************************************************************************
|
/************************************************************************************
|
||||||
* Name: stm32_dmastreamdisable
|
* Name: stm32_dmastreamdisable
|
||||||
*
|
*
|
||||||
|
@ -322,28 +375,31 @@ static int stm32_dmainterrupt(int irq, void *context)
|
||||||
struct stm32_dma_s *dmast;
|
struct stm32_dma_s *dmast;
|
||||||
uint32_t isr;
|
uint32_t isr;
|
||||||
uint32_t regoffset = 0;
|
uint32_t regoffset = 0;
|
||||||
int stndx = 0;
|
unsigned int stream = 0;
|
||||||
|
unsigned int controller = 0;
|
||||||
|
|
||||||
/* Get the stream structure from the interrupt number */
|
/* Get the stream structure from the interrupt number */
|
||||||
|
|
||||||
if (irq >= STM32_IRQ_DMA1S0 && irq <= STM32_IRQ_DMA1S7)
|
if (irq >= STM32_IRQ_DMA1S0 && irq <= STM32_IRQ_DMA1S7)
|
||||||
{
|
{
|
||||||
stndx = irq - STM32_IRQ_DMA1S0;
|
stream = irq - STM32_IRQ_DMA1S0;
|
||||||
regoffset = STM32_DMA_LISR_OFFSET;
|
controller = DMA1;
|
||||||
|
regoffset = STM32_DMA_LISR_OFFSET;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
#if STM32_NDMA > 1
|
#if STM32_NDMA > 1
|
||||||
if (irq >= STM32_IRQ_DMA2S0 && irq <= STM32_IRQ_DMA2S7)
|
if (irq >= STM32_IRQ_DMA2S0 && irq <= STM32_IRQ_DMA2S7)
|
||||||
{
|
{
|
||||||
stndx = irq - STM32_IRQ_DMA2S0 + DMA1_NSTREAMS;
|
stream = irq - STM32_IRQ_DMA2S0 + DMA1_NSTREAMS;
|
||||||
regoffset = STM32_DMA_HISR_OFFSET;
|
controller = DMA2;
|
||||||
|
regoffset = STM32_DMA_HISR_OFFSET;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
#endif
|
#endif
|
||||||
{
|
{
|
||||||
PANIC(OSERR_INTERNAL);
|
PANIC(OSERR_INTERNAL);
|
||||||
}
|
}
|
||||||
dmast = &g_dma[stndx];
|
dmast = stm32_dmastream(stream, controller);
|
||||||
|
|
||||||
/* Get the interrupt status for this stream */
|
/* Get the interrupt status for this stream */
|
||||||
|
|
||||||
|
@ -380,13 +436,13 @@ static int stm32_dmainterrupt(int irq, void *context)
|
||||||
void weak_function up_dmainitialize(void)
|
void weak_function up_dmainitialize(void)
|
||||||
{
|
{
|
||||||
struct stm32_dma_s *dmast;
|
struct stm32_dma_s *dmast;
|
||||||
int stndx;
|
int stream;
|
||||||
|
|
||||||
/* Initialize each DMA stream */
|
/* Initialize each DMA stream */
|
||||||
|
|
||||||
for (stndx = 0; stndx < DMA_NSTREAMS; stndx++)
|
for (stream = 0; stream < DMA_NSTREAMS; stream++)
|
||||||
{
|
{
|
||||||
dmast = &g_dma[stndx];
|
dmast = &g_dma[stream];
|
||||||
sem_init(&dmast->sem, 0, 1);
|
sem_init(&dmast->sem, 0, 1);
|
||||||
|
|
||||||
/* Attach DMA interrupt vectors */
|
/* Attach DMA interrupt vectors */
|
||||||
|
@ -412,7 +468,7 @@ void weak_function up_dmainitialize(void)
|
||||||
*
|
*
|
||||||
* Description:
|
* Description:
|
||||||
* Allocate a DMA channel. This function gives the caller mutually
|
* Allocate a DMA channel. This function gives the caller mutually
|
||||||
* exclusive access to the DMA channel specified by the 'stndx' argument.
|
* exclusive access to the DMA channel specified by the 'dmamap' argument.
|
||||||
* DMA channels are shared on the STM32: Devices sharing the same DMA
|
* DMA channels are shared on the STM32: Devices sharing the same DMA
|
||||||
* channel cannot do DMA concurrently! See the DMACHAN_* definitions in
|
* channel cannot do DMA concurrently! See the DMACHAN_* definitions in
|
||||||
* stm32_dma.h.
|
* stm32_dma.h.
|
||||||
|
@ -428,13 +484,13 @@ void weak_function up_dmainitialize(void)
|
||||||
* version. Feel free to do that if that is what you need.
|
* version. Feel free to do that if that is what you need.
|
||||||
*
|
*
|
||||||
* Input parameter:
|
* Input parameter:
|
||||||
* chan - Identifies the stream/channel resource. For the STM32 F4, this
|
* dmamap - Identifies the stream/channel resource. For the STM32 F4, this
|
||||||
* is a bit-encoded value as provided by the the DMAMAP_* definitions
|
* is a bit-encoded value as provided by the the DMAMAP_* definitions
|
||||||
* in chip/stm32f40xxx_dma.h
|
* in chip/stm32f40xxx_dma.h
|
||||||
*
|
*
|
||||||
* Returned Value:
|
* Returned Value:
|
||||||
* Provided that 'stndx' is valid, this function ALWAYS returns a non-NULL,
|
* Provided that 'dmamap' is valid, this function ALWAYS returns a non-NULL,
|
||||||
* void* DMA channel handle. (If 'stndx' is invalid, the function will
|
* void* DMA channel handle. (If 'dmamap' is invalid, the function will
|
||||||
* assert if debug is enabled or do something ignorant otherwise).
|
* assert if debug is enabled or do something ignorant otherwise).
|
||||||
*
|
*
|
||||||
* Assumptions:
|
* Assumptions:
|
||||||
|
@ -444,19 +500,14 @@ void weak_function up_dmainitialize(void)
|
||||||
*
|
*
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
DMA_HANDLE stm32_dmachannel(unsigned int chan)
|
DMA_HANDLE stm32_dmachannel(unsigned int dmamap)
|
||||||
{
|
{
|
||||||
struct stm32_dma_s *dmast;
|
FAR struct stm32_dma_s *dmast;
|
||||||
int stndx;
|
|
||||||
|
|
||||||
/* Get the stream index from the bit-encoded channel value */
|
/* Get the stream index from the bit-encoded channel value */
|
||||||
|
|
||||||
stndx = STM32_DMA_STREAM(chan);
|
dmast = stm32_dmamap(dmamap);
|
||||||
DEBUGASSERT(stndx < DMA_NSTREAMS);
|
DEBUGASSERT(dmast != NULL);
|
||||||
|
|
||||||
/* Then get the stream structure associated with the stream index */
|
|
||||||
|
|
||||||
dmast = &g_dma[stndx];
|
|
||||||
|
|
||||||
/* Get exclusive access to the DMA channel -- OR wait until the channel
|
/* Get exclusive access to the DMA channel -- OR wait until the channel
|
||||||
* is available if it is currently being used by another driver
|
* is available if it is currently being used by another driver
|
||||||
|
@ -507,45 +558,110 @@ void stm32_dmafree(DMA_HANDLE handle)
|
||||||
*
|
*
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr, size_t ntransfers, uint32_t scr)
|
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;
|
struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
|
||||||
|
uint32_t regoffset;
|
||||||
uint32_t regval;
|
uint32_t regval;
|
||||||
|
|
||||||
/* Set the peripheral register address in the DMA_SPARx register. The data
|
dmadbg("paddr: %08x maddr: %08x ntransfers: %d scr: %08x\n",
|
||||||
* will be moved from/to this address to/from the memory after the
|
paddr, maddr, ntransfers, scr);
|
||||||
* peripheral event.
|
|
||||||
|
/* "If the stream is enabled, disable it by resetting the EN bit in the
|
||||||
|
* DMA_SxCR register, then read this bit in order to confirm that there is no
|
||||||
|
* ongoing stream operation. Writing this bit to 0 is not immediately
|
||||||
|
* effective since it is actually written to 0 once all the current transfers
|
||||||
|
* have finished. When the EN bit is read as 0, this means that the stream is
|
||||||
|
* ready to be configured. It is therefore necessary to wait for the EN bit
|
||||||
|
* to be cleared before starting any stream configuration. ..."
|
||||||
|
*/
|
||||||
|
|
||||||
|
while ((dmast_getreg(dmast, STM32_DMA_SCR_OFFSET) & DMA_SCR_EN) != 0);
|
||||||
|
|
||||||
|
/* "... All the stream dedicated bits set in the status register (DMA_LISR
|
||||||
|
* and DMA_HISR) from the previous data block DMA transfer should be cleared
|
||||||
|
* before the stream can be re-enabled."
|
||||||
|
*
|
||||||
|
* 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));
|
||||||
|
|
||||||
|
/* "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);
|
dmast_putreg(dmast, STM32_DMA_SPAR_OFFSET, paddr);
|
||||||
|
|
||||||
/* Set the memory address in the DMA_SM0ARx register. The data will be
|
/* "Set the memory address in the DMA_SM0ARx ... register. The data will be
|
||||||
* written to or read from this memory after the peripheral event.
|
* written to or read from this memory after the peripheral event."
|
||||||
|
*
|
||||||
* Note that only single-buffer mode is currently supported so SM1ARx
|
* Note that only single-buffer mode is currently supported so SM1ARx
|
||||||
* is not used.
|
* is not used."
|
||||||
*/
|
*/
|
||||||
|
|
||||||
dmast_putreg(dmast, STM32_DMA_SM0AR_OFFSET, maddr);
|
dmast_putreg(dmast, STM32_DMA_SM0AR_OFFSET, maddr);
|
||||||
|
|
||||||
/* Configure the total number of data items to be transferred in the DMA_SNDTRx
|
/* "Configure the total number of data items to be transferred in the
|
||||||
* register. After each peripheral event, this value will be decremented.
|
* DMA_SNDTRx register. After each peripheral event, this value will be
|
||||||
|
* decremented."
|
||||||
*/
|
*/
|
||||||
|
|
||||||
dmast_putreg(dmast, STM32_DMA_SNDTR_OFFSET, ntransfers);
|
dmast_putreg(dmast, STM32_DMA_SNDTR_OFFSET, ntransfers);
|
||||||
|
|
||||||
/* Configure the stream priority using the PL[1:0] bits in the DMA_SCRx
|
/* "Select the DMA channel (request) using CHSEL[2:0] in the DMA_SxCR register."
|
||||||
* register. Configure data transfer direction, circular mode, peripheral & memory
|
*
|
||||||
* incremented mode, peripheral & memory data size, and interrupt after
|
* "Configure the stream priority using the PL[1:0] bits in the DMA_SCRx"
|
||||||
* half and/or full transfer in the DMA_CCRx register.
|
* register."
|
||||||
*/
|
*/
|
||||||
|
|
||||||
regval = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
|
regval = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
|
||||||
regval &= ~(DMA_SCR_DIR_MASK|DMA_SCR_PINC|DMA_SCR_MINC|DMA_SCR_PSIZE_MASK|
|
regval &= ~(DMA_SCR_PL_MASK|DMA_SCR_CHSEL_MASK);
|
||||||
DMA_SCR_MSIZE_MASK|DMA_SCR_PINCOS|DMA_SCR_PL_MASK|DMA_SCR_PBURST_MASK|
|
regval |= scr & DMA_SCR_PL_MASK;
|
||||||
DMA_SCR_MBURST_MASK);
|
regval |= (uint32_t)dmast->stream << DMA_SCR_CHSEL_SHIFT;
|
||||||
scr &= (DMA_SCR_DIR_MASK|DMA_SCR_PINC|DMA_SCR_MINC|DMA_SCR_PSIZE_MASK|
|
dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, regval);
|
||||||
DMA_SCR_MSIZE_MASK|DMA_SCR_PINCOS|DMA_SCR_PL_MASK|DMA_SCR_PBURST_MASK|
|
|
||||||
DMA_SCR_MBURST_MASK);
|
/* "Configure the FIFO usage (enable or disable, threshold in transmission and
|
||||||
|
* reception)"
|
||||||
|
*
|
||||||
|
* "Caution is required when choosing the FIFO threshold (bits FTH[1:0] of the
|
||||||
|
* DMA_SxFCR register) and the size of the memory burst (MBURST[1:0] of the
|
||||||
|
* DMA_SxCR register): The content pointed by the FIFO threshold must exactly
|
||||||
|
* match to an integer number of memory burst transfers. If this is not in the
|
||||||
|
* case, a FIFO error (flag FEIFx of the DMA_HISR or DMA_LISR register) will be
|
||||||
|
* generated when the stream is enabled, then the stream will be automatically
|
||||||
|
* disabled."
|
||||||
|
*/
|
||||||
|
|
||||||
|
regval = dmast_getreg(dmast, STM32_DMA_SFCR_OFFSET);
|
||||||
|
regval &= ~(DMA_SFCR_FTH_MASK | DMA_SFCR_FS_MASK);
|
||||||
|
regval |= (DMA_SFCR_FTH_FULL | DMA_SFCR_DMDIS | DMA_SFCR_FEIE);
|
||||||
|
dmast_putreg(dmast, STM32_DMA_SFCR_OFFSET, regval);
|
||||||
|
|
||||||
|
/* "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_PFCTRL|DMA_SCR_DIR_MASK|DMA_SCR_PINC|DMA_SCR_MINC|
|
||||||
|
DMA_SCR_PSIZE_MASK|DMA_SCR_MSIZE_MASK|DMA_SCR_PINCOS|
|
||||||
|
DMA_SCR_PBURST_MASK|DMA_SCR_MBURST_MASK);
|
||||||
|
scr &= (DMA_SCR_PFCTRL|DMA_SCR_DIR_MASK|DMA_SCR_PINC|DMA_SCR_MINC|
|
||||||
|
DMA_SCR_PSIZE_MASK|DMA_SCR_MSIZE_MASK|DMA_SCR_PINCOS|
|
||||||
|
DMA_SCR_PBURST_MASK|DMA_SCR_MBURST_MASK);
|
||||||
regval |= scr;
|
regval |= scr;
|
||||||
dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, regval);
|
dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, regval);
|
||||||
}
|
}
|
||||||
|
@ -631,8 +747,8 @@ void stm32_dmasample(DMA_HANDLE handle, struct stm32_dmaregs_s *regs)
|
||||||
|
|
||||||
flags = irqsave();
|
flags = irqsave();
|
||||||
regs->lisr = dmabase_getreg(dmast, STM32_DMA_LISR_OFFSET);
|
regs->lisr = dmabase_getreg(dmast, STM32_DMA_LISR_OFFSET);
|
||||||
regs->hisr = dmabase_getreg(dmast, STM32_DMA_LISR_OFFSET);
|
regs->hisr = dmabase_getreg(dmast, STM32_DMA_HISR_OFFSET);
|
||||||
regs->scr = dmast_getreg(dmast, STM32_DMA_HISR_OFFSET);
|
regs->scr = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
|
||||||
regs->sndtr = dmast_getreg(dmast, STM32_DMA_SNDTR_OFFSET);
|
regs->sndtr = dmast_getreg(dmast, STM32_DMA_SNDTR_OFFSET);
|
||||||
regs->spar = dmast_getreg(dmast, STM32_DMA_SPAR_OFFSET);
|
regs->spar = dmast_getreg(dmast, STM32_DMA_SPAR_OFFSET);
|
||||||
regs->sm0ar = dmast_getreg(dmast, STM32_DMA_SM0AR_OFFSET);
|
regs->sm0ar = dmast_getreg(dmast, STM32_DMA_SM0AR_OFFSET);
|
||||||
|
@ -668,7 +784,7 @@ void stm32_dmadump(DMA_HANDLE handle, const struct stm32_dmaregs_s *regs,
|
||||||
dmadbg(" SPAR[%08x]: %08x\n", dmast->base + STM32_DMA_SPAR_OFFSET, regs->spar);
|
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(" 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(" 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);
|
dmadbg(" SFCR[%08x]: %08x\n", dmast->base + STM32_DMA_SFCR_OFFSET, regs->sfcr);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -2,7 +2,7 @@
|
||||||
* configs/stm3240g-eval/include/board.h
|
* configs/stm3240g-eval/include/board.h
|
||||||
* include/arch/board/board.h
|
* include/arch/board/board.h
|
||||||
*
|
*
|
||||||
* Copyright (C) 2011-12 Gregory Nutt. All rights reserved.
|
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -426,7 +426,7 @@
|
||||||
*
|
*
|
||||||
* SDIO DMA
|
* SDIO DMA
|
||||||
* DMAMAP_SDIO_1 = Channel 4, Stream 3
|
* DMAMAP_SDIO_1 = Channel 4, Stream 3
|
||||||
* DMAMAP_SDIO_2 = Channel 4, Stream 5
|
* DMAMAP_SDIO_2 = Channel 4, Stream 6
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define DMAMAP_SDIO DMAMAP_SDIO_1
|
#define DMAMAP_SDIO DMAMAP_SDIO_1
|
||||||
|
|
|
@ -1,8 +1,8 @@
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
* drivers/mmcsd/mmcsd_sdio.c
|
* drivers/mmcsd/mmcsd_sdio.c
|
||||||
*
|
*
|
||||||
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
|
* Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
|
||||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
|
|
@ -484,11 +484,14 @@ static ssize_t ramlog_write(FAR struct file *filep, FAR const char *buffer, size
|
||||||
#if !defined(CONFIG_RAMLOG_NONBLOCKING) || !defined(CONFIG_DISABLE_POLL)
|
#if !defined(CONFIG_RAMLOG_NONBLOCKING) || !defined(CONFIG_DISABLE_POLL)
|
||||||
if (nwritten > 0)
|
if (nwritten > 0)
|
||||||
{
|
{
|
||||||
|
irqstate_t flags;
|
||||||
|
#ifndef CONFIG_RAMLOG_NONBLOCKING
|
||||||
int i;
|
int i;
|
||||||
|
#endif
|
||||||
|
|
||||||
/* Are there threads waiting for read data? */
|
/* Are there threads waiting for read data? */
|
||||||
|
|
||||||
irqstate_t flags = irqsave();
|
flags = irqsave();
|
||||||
#ifndef CONFIG_RAMLOG_NONBLOCKING
|
#ifndef CONFIG_RAMLOG_NONBLOCKING
|
||||||
for (i = 0; i < priv->rl_nwaiters; i++)
|
for (i = 0; i < priv->rl_nwaiters; i++)
|
||||||
{
|
{
|
||||||
|
|
Loading…
Reference in New Issue