summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog4
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig11
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h1
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_dma.h41
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c43
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f20xxx_dma.c39
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c61
7 files changed, 174 insertions, 26 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index fd94f27ba..39a3aa27f 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4881,4 +4881,8 @@
support the SAM4L Xplained Pro developement board (2013-6-3).
* arch/arm/src/sam34/chip/sam4l_pinmap.h: Initial cut as SAM4L
pin mapping (2013-6-3).
+ * arch/arm/src/stm32/stm32*_dma.*: Add a new interface function,
+ stm32_dmacapable() that can be used to determine if DMA is
+ possible from the specified memory address. From Petteri Aimonen
+ (2013-6-4).
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index 458190745..7249b382f 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -1128,6 +1128,17 @@ config STM32_CCMEXCLUDE
and (2) it appears to be impossible to execute ELF modules from CCM
RAM.
+config STM32_DMACAPABLE
+ bool "Workaround non-DMA capable memory"
+ depends on ARCH_DMA
+ default y if STM32_STM32F40XX && !STM32_CCMEXCLUDE
+ default n if !STM32_STM32F40XX || STM32_CCMEXCLUDE
+ ---help---
+ This option enables the DMA interface stm32_dmacapable that can be
+ used to check if it is possible to do DMA from the selected address.
+ Drivers then may use this information to determine if they should
+ attempt the DMA or fall back to a different transfer method.
+
config STM32_FSMC_SRAM
bool "External SRAM on FSMC"
default n
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h
index c405a6dea..217836999 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h
@@ -42,6 +42,7 @@
/* FLASH and SRAM *******************************************************************/
+#define STM32_CODE_BASE 0x00000000 /* 0x00000000-0x1fffffff: 512Mb code block */
#define STM32_FLASH_BASE 0x08000000 /* 0x08000000 - Up to 512Kb */
#define STM32_SRAM_BASE 0x20000000 /* 0x20000000 - 64Kb SRAM */
#define STM32_SRAMBB_BASE 0x22000000
diff --git a/nuttx/arch/arm/src/stm32/stm32_dma.h b/nuttx/arch/arm/src/stm32/stm32_dma.h
index f40a757b5..771754bf9 100644
--- a/nuttx/arch/arm/src/stm32/stm32_dma.h
+++ b/nuttx/arch/arm/src/stm32/stm32_dma.h
@@ -146,7 +146,6 @@ extern "C" {
#define EXTERN extern
#endif
-
/************************************************************************************
* Public Functions
************************************************************************************/
@@ -211,7 +210,7 @@ EXTERN DMA_HANDLE stm32_dmachannel(unsigned int chan);
*
****************************************************************************/
-EXTERN void stm32_dmafree(DMA_HANDLE handle);
+void stm32_dmafree(DMA_HANDLE handle);
/****************************************************************************
* Name: stm32_dmasetup
@@ -221,8 +220,8 @@ EXTERN void stm32_dmafree(DMA_HANDLE handle);
*
****************************************************************************/
-EXTERN void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
- size_t ntransfers, uint32_t ccr);
+void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
+ size_t ntransfers, uint32_t ccr);
/****************************************************************************
* Name: stm32_dmastart
@@ -236,8 +235,8 @@ EXTERN void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
*
****************************************************************************/
-EXTERN void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback,
- void *arg, bool half);
+void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg,
+ bool half);
/****************************************************************************
* Name: stm32_dmastop
@@ -252,7 +251,7 @@ EXTERN void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback,
*
****************************************************************************/
-EXTERN void stm32_dmastop(DMA_HANDLE handle);
+void stm32_dmastop(DMA_HANDLE handle);
/****************************************************************************
* Name: stm32_dmaresidual
@@ -265,7 +264,27 @@ EXTERN void stm32_dmastop(DMA_HANDLE handle);
*
****************************************************************************/
-EXTERN size_t stm32_dmaresidual(DMA_HANDLE handle);
+size_t stm32_dmaresidual(DMA_HANDLE handle);
+
+/****************************************************************************
+ * Name: stm32_dmacapable
+ *
+ * Description:
+ * Check if the DMA controller can transfer data to/from given memory
+ * address. This depends on the internal connections in the ARM bus matrix
+ * of the processor. Note that this only applies to memory addresses, it
+ * will return false for any peripheral address.
+ *
+ * Returned value:
+ * True, if transfer is possible.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32_DMACAPABLE
+bool stm32_dmacapable(uintptr_t maddr);
+#else
+# define stm32_dmacapable(maddr) (true)
+#endif
/****************************************************************************
* Name: stm32_dmasample
@@ -279,7 +298,7 @@ EXTERN size_t stm32_dmaresidual(DMA_HANDLE handle);
****************************************************************************/
#ifdef CONFIG_DEBUG_DMA
-EXTERN void stm32_dmasample(DMA_HANDLE handle, struct stm32_dmaregs_s *regs);
+void stm32_dmasample(DMA_HANDLE handle, struct stm32_dmaregs_s *regs);
#else
# define stm32_dmasample(handle,regs)
#endif
@@ -296,8 +315,8 @@ EXTERN void stm32_dmasample(DMA_HANDLE handle, struct stm32_dmaregs_s *regs);
****************************************************************************/
#ifdef CONFIG_DEBUG_DMA
-EXTERN void stm32_dmadump(DMA_HANDLE handle, const struct stm32_dmaregs_s *regs,
- const char *msg);
+void stm32_dmadump(DMA_HANDLE handle, const struct stm32_dmaregs_s *regs,
+ const char *msg);
#else
# define stm32_dmadump(handle,regs,msg)
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c b/nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c
index 29b09150d..9ab64ce7e 100644
--- a/nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c
+++ b/nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32f10xxx_dma.c
*
- * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -77,7 +77,7 @@
#endif
/* Convert the DMA channel base address to the DMA register block address */
-
+
#define DMA_BASE(ch) (ch & 0xfffffc00)
/****************************************************************************
@@ -358,7 +358,7 @@ void weak_function up_dmainitialize(void)
/* Enable the IRQ at the NVIC (still disabled at the DMA controller) */
up_enable_irq(dmach->irq);
-
+
/* Set the interrrupt priority */
up_prioritize_irq(dmach->irq, CONFIG_DMA_PRI);
@@ -548,7 +548,7 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
{
/* 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
+ * 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.
*/
@@ -597,6 +597,41 @@ size_t stm32_dmaresidual(DMA_HANDLE handle)
}
/****************************************************************************
+ * Name: stm32_dmacapable
+ *
+ * Description:
+ * Check if the DMA controller can transfer data to/from given memory
+ * address. This depends on the internal connections in the ARM bus matrix
+ * of the processor. Note that this only applies to memory addresses, it
+ * will return false for any peripheral address.
+ *
+ * Returned value:
+ * True, if transfer is possible.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32_DMACAPABLE
+bool stm32_dmacapable(uint32_t maddr)
+{
+ switch (maddr & STM32_REGION_MASK)
+ {
+ case STM32_FSMC_BANK1:
+ case STM32_FSMC_BANK2:
+ case STM32_FSMC_BANK3:
+ case STM32_FSMC_BANK4:
+ case STM32_SRAM_BASE:
+ case STM32_CODE_BASE:
+ /* All RAM and flash is supported */
+ return true;
+
+ default:
+ /* Everything else is unsupported by DMA */
+ return false;
+ }
+}
+#endif
+
+/****************************************************************************
* Name: stm32_dmasample
*
* Description:
diff --git a/nuttx/arch/arm/src/stm32/stm32f20xxx_dma.c b/nuttx/arch/arm/src/stm32/stm32f20xxx_dma.c
index 844fa6a67..71ac263fb 100644
--- a/nuttx/arch/arm/src/stm32/stm32f20xxx_dma.c
+++ b/nuttx/arch/arm/src/stm32/stm32f20xxx_dma.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32f20xxx_dma.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -773,7 +773,7 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
* Interrupt Enable bit (TCIE) is set.
*/
- scr |= (half ? (DMA_SCR_HTIE|DMA_SCR_TEIE) : (DMA_SCR_TCIE|DMA_SCR_TEIE));
+ scr |= (half ? (DMA_SCR_HTIE|DMA_SCR_TEIE) : (DMA_SCR_TCIE|DMA_SCR_TEIE));
}
else
{
@@ -842,6 +842,41 @@ size_t stm32_dmaresidual(DMA_HANDLE handle)
}
/****************************************************************************
+ * Name: stm32_dmacapable
+ *
+ * Description:
+ * Check if the DMA controller can transfer data to/from given memory
+ * address. This depends on the internal connections in the ARM bus matrix
+ * of the processor. Note that this only applies to memory addresses, it
+ * will return false for any peripheral address.
+ *
+ * Returned value:
+ * True, if transfer is possible.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32_DMACAPABLE
+bool stm32_dmacapable(uint32_t maddr)
+{
+ switch (maddr & STM32_REGION_MASK)
+ {
+ case STM32_FSMC_BANK1:
+ case STM32_FSMC_BANK2:
+ case STM32_FSMC_BANK3:
+ case STM32_FSMC_BANK4:
+ case STM32_SRAM_BASE:
+ case STM32_CODE_BASE:
+ /* All RAM and flash is supported */
+ return true;
+
+ default:
+ /* Everything else is unsupported by DMA */
+ return false;
+ }
+}
+#endif
+
+/****************************************************************************
* Name: stm32_dmasample
*
* Description:
diff --git a/nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c b/nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c
index fd8164a32..5bff603b9 100644
--- a/nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c
+++ b/nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32f40xxx_dma.c
*
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -79,7 +79,7 @@
#endif
/* Convert the DMA stream base address to the DMA register block address */
-
+
#define DMA_BASE(ch) (ch & 0xfffffc00)
/****************************************************************************
@@ -358,7 +358,7 @@ static void stm32_dmastreamdisable(struct stm32_dma_s *dmast)
{
regoffset = STM32_DMA_HIFCR_OFFSET;
}
-
+
dmabase_putreg(dmast, regoffset, (DMA_STREAM_MASK << dmast->shift));
}
@@ -491,7 +491,7 @@ void weak_function up_dmainitialize(void)
/* Enable the IRQ at the NVIC (still disabled at the DMA controller) */
up_enable_irq(dmast->irq);
-
+
/* Set the interrrupt priority */
up_prioritize_irq(dmast->irq, CONFIG_DMA_PRI);
@@ -634,7 +634,7 @@ void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
{
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
@@ -692,7 +692,7 @@ void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
* generated when the stream is enabled, then the stream will be automatically
* disabled."
*
- * The FIFO is disabled in circular mode when transferring data from a
+ * The FIFO is disabled in circular mode when transferring data from a
* peripheral to memory, as in this case it is usually desirable to know that
* every byte from the peripheral is transferred immediately to memory. It is
* not practical to flush the DMA FIFO, as this requires disabling the channel
@@ -776,13 +776,13 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
* Interrupt Enable bit (TCIE) is set.
*/
- scr |= (half ? (DMA_SCR_HTIE|DMA_SCR_TEIE) : (DMA_SCR_TCIE|DMA_SCR_TEIE));
+ scr |= (half ? (DMA_SCR_HTIE|DMA_SCR_TEIE) : (DMA_SCR_TCIE|DMA_SCR_TEIE));
}
else
{
/* In non-stop modes, 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
+ * 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.
*/
@@ -828,7 +828,7 @@ size_t stm32_dmaresidual(DMA_HANDLE handle)
struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
uint32_t residual;
- /* Fetch the count of bytes remaining to be transferred.
+ /* Fetch the count of bytes remaining to be transferred.
*
* If the FIFO is enabled, this count may be inaccurate. ST don't
* appear to document whether this counts the peripheral or the memory
@@ -845,6 +845,49 @@ size_t stm32_dmaresidual(DMA_HANDLE handle)
}
/****************************************************************************
+ * Name: stm32_dmacapable
+ *
+ * Description:
+ * Check if the DMA controller can transfer data to/from given memory
+ * address. This depends on the internal connections in the ARM bus matrix
+ * of the processor. Note that this only applies to memory addresses, it
+ * will return false for any peripheral address.
+ *
+ * Returned value:
+ * True, if transfer is possible.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32_DMACAPABLE
+bool stm32_dmacapable(uint32_t maddr)
+{
+ switch (maddr & STM32_REGION_MASK)
+ {
+ case STM32_FSMC_BANK1:
+ case STM32_FSMC_BANK2:
+ case STM32_FSMC_BANK3:
+ case STM32_FSMC_BANK4:
+ case STM32_SRAM_BASE:
+ /* All RAM is supported */
+ return true;
+
+ case STM32_CODE_BASE:
+ /* Everything except the CCM ram is supported */
+ if (maddr >= STM32_CCMRAM_BASE &&
+ (maddr - STM32_CCMRAM_BASE) < 65536)
+ {
+ return false;
+ }
+ return true;
+
+ default:
+ /* Everything else is unsupported by DMA */
+ return false;
+ }
+}
+#endif
+
+/****************************************************************************
* Name: stm32_dmasample
*
* Description: