summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpdma.h144
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.c164
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.h16
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.c12
5 files changed, 299 insertions, 40 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 4c969711e..23ca473c8 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4468,3 +4468,6 @@
configs/open1788/READMT.txt (2103-3-27).
* configs/open1788/nxlines: Add a configuration to test both the
Open1788 LCD and SDRAM which is used as a framebuffer (2013-3-27).
+ * arch/arm/src/lpc17xx/lpc17_gdma.c and lpc17_sdcard.c: Began
+ implementation of the LPC17 DMA and integration into the SDCARD
+ driver (2013-3029).
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpdma.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpdma.h
index fa7d13c32..dc80b8e05 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpdma.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpdma.h
@@ -69,7 +69,8 @@
/* Channel Registers */
-#define LPC17_DMA_CHAN_OFFSET(n) (0x0100 + ((n) << 5)) /* n=0,1,...7 */
+#define LPC17_NDMACH 8 /* Eight DMA channels */
+#define LPC17_DMA_CHAN_OFFSET(n) (0x0100 + ((n) << 5)) /* n=0,1,...,(LPC17_NDMACH-1) */
#define LPC17_DMACH_SRCADDR_OFFSET 0x0000 /* DMA Channel Source Address Register */
#define LPC17_DMACH_DESTADDR_OFFSET 0x0004 /* DMA Channel Destination Address Register */
@@ -204,7 +205,10 @@
/* Register bit definitions *********************************************************/
/* DMA Request Connections **********************************************************/
+#define LPC17_NDMAREQ (16) /* The number of DMA requests */
#if defined(LPC176x)
+/* Request Numbers */
+
# define DMA_REQ_SSP0TX (0)
# define DMA_REQ_SSP0RX (1)
# define DMA_REQ_SSP1TX (2)
@@ -217,25 +221,61 @@
# define DMA_REQ_DAC (7)
-# define DMA_REQ_UART0TX (8)
-# define DMA_REQ_UART0RX (9)
-# define DMA_REQ_UART1TX (10)
-# define DMA_REQ_UART1RX (11)
-# define DMA_REQ_UART2TX (12)
-# define DMA_REQ_UART2RX (13)
-# define DMA_REQ_UART3TX (14)
-# define DMA_REQ_UART3RX (15)
-
-# define DMA_REQ_MAT0p0 (8)
-# define DMA_REQ_MAT0p1 (9)
-# define DMA_REQ_MAT1p0 (10)
-# define DMA_REQ_MAT1p1 (11)
-# define DMA_REQ_MAT2p0 (12)
-# define DMA_REQ_MAT2p1 (13)
-# define DMA_REQ_MAT3p0 (14)
-# define DMA_REQ_MAT3p1 (15)
+# define DMA_REQ_UART0TX (8) /* DMASEL08=0*/
+# define DMA_REQ_UART0RX (9) /* DMASEL09=0*/
+# define DMA_REQ_UART1TX (10) /* DMASEL010=0*/
+# define DMA_REQ_UART1RX (11) /* DMASEL011=0*/
+# define DMA_REQ_UART2TX (12) /* DMASEL012=0*/
+# define DMA_REQ_UART2RX (13) /* DMASEL013=0*/
+# define DMA_REQ_UART3TX (14) /* DMASEL014=0*/
+# define DMA_REQ_UART3RX (15) /* DMASEL015=0*/
+
+# define DMA_REQ_MAT0p0 (8) /* DMASEL08=1 */
+# define DMA_REQ_MAT0p1 (9) /* DMASEL09=1 */
+# define DMA_REQ_MAT1p0 (10) /* DMASEL010=1 */
+# define DMA_REQ_MAT1p1 (11) /* DMASEL011=1 */
+# define DMA_REQ_MAT2p0 (12) /* DMASEL012=1 */
+# define DMA_REQ_MAT2p1 (13) /* DMASEL013=1 */
+# define DMA_REQ_MAT3p0 (14) /* DMASEL014=1 */
+# define DMA_REQ_MAT3p1 (15) /* DMASEL015=1 */
+
+/* DMASEL values. For the LPC176x family, only request numbers 8-15 have
+ * DMASEL bits.
+ */
+
+# define DMA_DMASEL_SSP0TX (0) /* Not applicable */
+# define DMA_DMASEL_SSP0RX (0) /* Not applicable */
+# define DMA_DMASEL_SSP1TX (0) /* Not applicable */
+# define DMA_DMASEL_SSP1RX (0) /* Not applicable */
+
+# define DMA_DMASEL_ADC (0) /* Not applicable */
+
+# define DMA_DMASEL_I2SCH0 (0) /* Not applicable */
+# define DMA_DMASEL_I2SCH1 (0) /* Not applicable */
+
+# define DMA_DMASEL_DAC (0) /* Not applicable */
+
+# define DMA_DMASEL_UART0TX (0)
+# define DMA_DMASEL_UART0RX (0)
+# define DMA_DMASEL_UART1TX (0)
+# define DMA_DMASEL_UART1RX (0)
+# define DMA_DMASEL_UART2TX (0)
+# define DMA_DMASEL_UART2RX (0)
+# define DMA_DMASEL_UART3TX (0)
+# define DMA_DMASEL_UART3RX (0)
+
+# define DMA_DMASEL_MAT0p0 (1)
+# define DMA_DMASEL_MAT0p1 (1)
+# define DMA_DMASEL_MAT1p0 (1)
+# define DMA_DMASEL_MAT1p1 (1)
+# define DMA_DMASEL_MAT2p0 (1)
+# define DMA_DMASEL_MAT2p1 (1)
+# define DMA_DMASEL_MAT3p0 (1)
+# define DMA_DMASEL_MAT3p1 (1)
#elif defined(LPC178x)
+/* Request Numbers */
+
# define DMA_REQ_SDCARD (1) /* DMASEL01=0 */
# define DMA_REQ_SSP0TX (2) /* DMASEL02=0 */
@@ -251,25 +291,62 @@
# define DMA_REQ_MAT1p1 (3) /* DMASEL03=1 */
# define DMA_REQ_MAT2p0 (4) /* DMASEL04=1 */
# define DMA_REQ_MAT2p1 (5) /* DMASEL05=1 */
-# define DMA_REQ_MAT3p0 (14) /* DMASEL14=0 */
-# define DMA_REQ_MAT3p1 (15) /* DMASEL15=0 */
+# define DMA_REQ_MAT3p0 (14) /* DMASEL14=1 */
+# define DMA_REQ_MAT3p1 (15) /* DMASEL15=1 */
# define DMA_REQ_I2SCH0 (6) /* DMASEL06=1 */
# define DMA_REQ_I2SCH1 (7) /* DMASEL07=1 */
-# define DMA_REQ_ADC (8)
-# define DMA_REQ_DAC (9)
-
-# define DMA_REQ_UART0TX (10) /* DMASEL10=1 */
-# define DMA_REQ_UART0RX (11) /* DMASEL11=1 */
-# define DMA_REQ_UART1TX (12) /* DMASEL12=1 */
-# define DMA_REQ_UART1RX (13) /* DMASEL13=1 */
-# define DMA_REQ_UART2TX (14) /* DMASEL14=1 */
-# define DMA_REQ_UART2RX (15) /* DMASEL15=1 */
-# define DMA_REQ_UART3TX (10) /* DMASEL10=0 */
-# define DMA_REQ_UART3RX (11) /* DMASEL11=0 */
-# define DMA_REQ_UART4TX (12) /* DMASEL12=0 */
-# define DMA_REQ_UART4RX (13) /* DMASEL13=0 */
+# define DMA_REQ_ADC (8) /* Not applicable */
+# define DMA_REQ_DAC (9) /* Not applicable */
+
+# define DMA_REQ_UART0TX (10) /* DMASEL10=0 */
+# define DMA_REQ_UART0RX (11) /* DMASEL11=0 */
+# define DMA_REQ_UART1TX (12) /* DMASEL12=0 */
+# define DMA_REQ_UART1RX (13) /* DMASEL13=0 */
+# define DMA_REQ_UART2TX (14) /* DMASEL14=0 */
+# define DMA_REQ_UART2RX (15) /* DMASEL15=0 */
+# define DMA_REQ_UART3TX (10) /* DMASEL10=1 */
+# define DMA_REQ_UART3RX (11) /* DMASEL11=1 */
+# define DMA_REQ_UART4TX (12) /* DMASEL12=1 */
+# define DMA_REQ_UART4RX (13) /* DMASEL13=1 */
+
+/* DMASEL values */
+
+# define DMA_DMASEL_SDCARD (0)
+
+# define DMA_DMASEL_SSP0TX (0)
+# define DMA_DMASEL_SSP0RX (0)
+# define DMA_DMASEL_SSP1TX (0)
+# define DMA_DMASEL_SSP1RX (0)
+# define DMA_DMASEL_SSP2TX (0)
+# define DMA_DMASEL_SSP2RX (0)
+
+# define DMA_DMASEL_MAT0p0 (1)
+# define DMA_DMASEL_MAT0p1 (1)
+# define DMA_DMASEL_MAT1p0 (1)
+# define DMA_DMASEL_MAT1p1 (1)
+# define DMA_DMASEL_MAT2p0 (1)
+# define DMA_DMASEL_MAT2p1 (1)
+# define DMA_DMASEL_MAT3p0 (1)
+# define DMA_DMASEL_MAT3p1 (1)
+
+# define DMA_DMASEL_I2SCH0 (1)
+# define DMA_DMASEL_I2SCH1 (1)
+
+# define DMA_DMASEL_ADC (0) /* Not applicable */
+# define DMA_DMASEL_DAC (0) /* Not applicable */
+
+# define DMA_DMASEL_UART0TX (0)
+# define DMA_DMASEL_UART0RX (0)
+# define DMA_DMASEL_UART1TX (0)
+# define DMA_DMASEL_UART1RX (0)
+# define DMA_DMASEL_UART2TX (0)
+# define DMA_DMASEL_UART2RX (0)
+# define DMA_DMASEL_UART3TX (1)
+# define DMA_DMASEL_UART3RX (1)
+# define DMA_DMASEL_UART4TX (1)
+# define DMA_DMASEL_UART4RX (1)
#endif
/* General registers (see also LPC17_SYSCON_DMAREQSEL in lpc17_syscon.h) */
@@ -287,6 +364,7 @@
*/
#define DMACH(n) (1 << (n)) /* n=0,1,...7 */
+#define DMACH_ALL (0xff)
/* For each of the following registers, bits 0-15 represent a set of encoded
* DMA sources. Bits 16-31 are reserved in each case.
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.c
index 87ea30afb..696309b5f 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.c
@@ -42,7 +42,9 @@
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
+#include <semaphore.h>
#include <errno.h>
+#include <assert.h>
#include <debug.h>
#include <nuttx/arch.h>
@@ -82,6 +84,25 @@
/****************************************************************************
* Private Types
****************************************************************************/
+/* This structure represents the state of one DMA channel */
+
+struct lpc17_dmach_s
+{
+ bool inuse; /* True: The channel is in use */
+ dma_callback_t callback; /* DMA completion callback function */
+ void *arg; /* Argument to pass to the callback function */
+};
+
+/* This structure represents the state of the LPC17 DMA block */
+
+struct lpc17_gpdma_s
+{
+ sem_t exclsem; /* For exclusive access to the DMA channel list */
+
+ /* This is the state of each DMA channel */
+
+ struct lpc17_dmach_s dmach[LPC17_NDMACH];
+};
/****************************************************************************
* Private Function Prototypes
@@ -90,6 +111,9 @@
/****************************************************************************
* Private Data
****************************************************************************/
+/* The state of the LPC17 DMA block */
+
+static struct lpc17_gpdma_s g_gpdma;
/****************************************************************************
* Public Data
@@ -116,6 +140,75 @@
void lpc17_dmainitilaize(void)
{
+ uint32_t regval;
+ int i;
+
+ /* Enable clocking to the GPDMA block */
+
+ regval = getreg32(LPC17_SYSCON_PCONP);
+ regval |= SYSCON_PCONP_PCGPDMA;
+ putreg32(regval, LPC17_SYSCON_PCONP);
+
+ /* Reset all channel configurations */
+
+ for (i = 0; i < LPC17_NDMACH; i++)
+ {
+ putreg32(0, LPC17_DMACH_CONFIG(i));
+ }
+
+ /* Clear all DMA interrupts */
+
+ putreg32(DMACH_ALL, LPC17_DMA_INTTCCLR);
+ putreg32(DMACH_ALL, LPC17_DMA_INTERRCLR);
+
+ /* Initialize the DMA state structure */
+
+ sem_init(&g_gpdma.exclsem, 0, 1);
+}
+
+/****************************************************************************
+ * Name: lpc17_dmaconfigure
+ *
+ * Description:
+ * Configure a DMA request. Each DMA request may have two different DMA
+ * request sources. This associates one of the sources with a DMA request.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void lpc17_dmaconfigure(uint8_t dmarequest, bool alternate)
+{
+ uint32_t regval;
+
+ DEBUGASSERT(dmarequest < LPC17_NDMAREQ);
+
+#ifdef LPC176x
+ /* For the LPC176x family, only request numbers 8-15 have DMASEL bits */
+
+ if (dmarequest < 8)
+ {
+ return;
+ }
+
+ dmarequest -= 8;
+#endif
+
+ /* Set or clear the DMASEL bit corresponding to the request number */
+
+ regval = getreg32(LPC17_SYSCON_DMAREQSEL);
+
+ if (alternate)
+ {
+ regval |= (1 << dmarequest);
+ }
+ else
+ {
+ regval &= ~(1 << dmarequest);
+ }
+
+ putreg32(regval, LPC17_SYSCON_DMAREQSEL);
}
/****************************************************************************
@@ -134,7 +227,37 @@ void lpc17_dmainitilaize(void)
DMA_HANDLE lpc17_dmachannel(void)
{
- return NULL;
+ struct lpc17_dmach_s *dmach = NULL;
+ int ret;
+ int i;
+
+ /* Get exclusive access to the GPDMA state structure */
+
+ do
+ {
+ ret = sem_wait(&g_gpdma.exclsem);
+ DEBUGASSERT(ret == 0 || errno == EINTR);
+ }
+ while (ret < 0);
+
+ /* Find an available DMA channel */
+
+ for (i = 0; i < LPC17_NDMACH; i++)
+ {
+ if (!g_gpdma.dmach[i].inuse)
+ {
+ /* Found one! */
+
+ dmach = &g_gpdma.dmach[i];
+ g_gpdma.dmach[i].inuse = true;
+ break;
+ }
+ }
+
+ /* Return what we found (or not) */
+
+ sem_post(&g_gpdma.exclsem);
+ return (DMA_HANDLE)dmach;
}
/****************************************************************************
@@ -152,6 +275,15 @@ DMA_HANDLE lpc17_dmachannel(void)
void lpc17_dmafree(DMA_HANDLE handle)
{
+ struct lpc17_dmach_s *dmach = (DMA_HANDLE)handle;
+
+ DEBUGASSERT(dmach && dmach->inuse);
+
+ /* Mark the channel available. This is an atomic operation and needs no
+ * special protection.
+ */
+
+ dmach->inuse = false;
}
/****************************************************************************
@@ -163,8 +295,13 @@ void lpc17_dmafree(DMA_HANDLE handle)
****************************************************************************/
int lpc17_dmasetup(DMA_HANDLE handle, uint32_t control, uint32_t config,
- uint32_t srcaddr, uint32_t destaddr, size_t nbytes)
+ uint32_t srcaddr, uint32_t destaddr, size_t nxfrs)
{
+ struct lpc17_dmach_s *dmach = (DMA_HANDLE)handle;
+
+ DEBUGASSERT(dmach && dmach->inuse);
+#warning "Missing logic"
+
return -ENOSYS;
}
@@ -178,6 +315,17 @@ int lpc17_dmasetup(DMA_HANDLE handle, uint32_t control, uint32_t config,
int lpc17_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg)
{
+ struct lpc17_dmach_s *dmach = (DMA_HANDLE)handle;
+
+ DEBUGASSERT(dmach && dmach->inuse && callback);
+
+ /* Save the callback information */
+
+ dmach->callback = callback;
+ dmach->arg = arg;
+
+ /* Start the DMA */
+#warning "Missing logic"
return -ENOSYS;
}
@@ -193,6 +341,10 @@ int lpc17_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg)
void lpc17_dmastop(DMA_HANDLE handle)
{
+ struct lpc17_dmach_s *dmach = (DMA_HANDLE)handle;
+
+ DEBUGASSERT(dmach && dmach->inuse);
+#warning "Missing logic"
}
/****************************************************************************
@@ -206,6 +358,10 @@ void lpc17_dmastop(DMA_HANDLE handle)
#ifdef CONFIG_DEBUG_DMA
void lpc17_dmasample(DMA_HANDLE handle, struct lpc17_dmaregs_s *regs)
{
+ struct lpc17_dmach_s *dmach = (DMA_HANDLE)handle;
+
+ DEBUGASSERT(dmach && dmach->inuse);
+#warning "Missing logic"
}
#endif /* CONFIG_DEBUG_DMA */
@@ -220,6 +376,10 @@ void lpc17_dmasample(DMA_HANDLE handle, struct lpc17_dmaregs_s *regs)
#ifdef CONFIG_DEBUG_DMA
void lpc17_dmadump(DMA_HANDLE handle, const struct lpc17_dmaregs_s *regs, const char *msg)
{
+ struct lpc17_dmach_s *dmach = (DMA_HANDLE)handle;
+
+ DEBUGASSERT(dmach && dmach->inuse);
+#warning "Missing logic"
}
#endif /* CONFIG_DEBUG_DMA */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.h b/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.h
index d5a27c793..77ac811ab 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.h
@@ -138,6 +138,20 @@ extern "C"
void lpc17_dmainitilaize(void);
/****************************************************************************
+ * Name: lpc17_dmaconfigure
+ *
+ * Description:
+ * Configure a DMA request. Each DMA request may have two different DMA
+ * request sources. This associates one of the sources with a DMA request.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void lpc17_dmaconfigure(uint8_t dmarequest, bool alternate);
+
+/****************************************************************************
* Name: lpc17_dmachannel
*
* Description:
@@ -177,7 +191,7 @@ void lpc17_dmafree(DMA_HANDLE handle);
****************************************************************************/
int lpc17_dmasetup(DMA_HANDLE handle, uint32_t control, uint32_t config,
- uint32_t srcaddr, uint32_t destaddr, size_t nbytes);
+ uint32_t srcaddr, uint32_t destaddr, size_t nxfrs);
/****************************************************************************
* Name: lpc17_dmastart
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.c b/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.c
index 14ba07bf6..f449685de 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.c
@@ -2475,7 +2475,7 @@ static int lpc17_dmarecvsetup(FAR struct sdio_dev_s *dev, FAR uint8_t *buffer,
ret = lpc17_dmasetup(priv->dma, SDCARD_RXDMA32_CONTROL,
SDCARD_RXDMA32_CONFIG, LPC17_SDCARD_FIFO,
- (uint32_t)buffer, buflen);
+ (uint32_t)buffer, (buflen + 3) >> 2);
if (ret == OK)
{
/* Start the DMA */
@@ -2547,7 +2547,7 @@ static int lpc17_dmasendsetup(FAR struct sdio_dev_s *dev,
ret = lpc17_dmasetup(priv->dma, SDCARD_TXDMA32_CONTROL,
SDCARD_TXDMA32_CONFIG, (uint32_t)buffer,
- LPC17_SDCARD_FIFO, buflen);
+ LPC17_SDCARD_FIFO, (buflen + 3) >> 2);
if (ret == OK)
{
lpc17_sample(priv, SAMPLENDX_BEFORE_ENABLE);
@@ -2711,9 +2711,13 @@ FAR struct sdio_dev_s *sdio_initialize(int slotno)
priv->waitwdog = wd_create();
DEBUGASSERT(priv->waitwdog);
- /* Allocate a DMA channel */
-
#ifdef CONFIG_SDIO_DMA
+ /* Configure the SDCARD DMA request */
+
+ lpc17_dmaconfigure(DMA_REQ_SDCARD, DMA_DMASEL_SDCARD);
+
+ /* Allocate a DMA channel for SDCARD DMA */
+
priv->dma = lpc17_dmachannel();
DEBUGASSERT(priv->dma);
#endif