aboutsummaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-01-23 18:46:12 -0800
committerpx4dev <px4@purgatory.org>2013-01-23 18:46:12 -0800
commit1ce1d4460b1c7884490118ea356bf61ffbd31163 (patch)
tree92c2fdbf63bd517b5a954f267ebdefdb23445df0 /nuttx/arch
parent72a0a4a71cd48c268d581436461a1f97db85f1d3 (diff)
parent8685f63c72259d18304fd9a04099e5cfa17829ba (diff)
downloadpx4-firmware-1ce1d4460b1c7884490118ea356bf61ffbd31163.tar.gz
px4-firmware-1ce1d4460b1c7884490118ea356bf61ffbd31163.tar.bz2
px4-firmware-1ce1d4460b1c7884490118ea356bf61ffbd31163.zip
Merge pull request #183 from PX4/nuttx-merge-5527
Nuttx merge 5527
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/Kconfig23
-rw-r--r--nuttx/arch/README.txt12
-rw-r--r--nuttx/arch/arm/Kconfig11
-rw-r--r--nuttx/arch/arm/src/armv7-m/Kconfig8
-rw-r--r--nuttx/arch/arm/src/armv7-m/Toolchain.defs19
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_doirq.c8
-rw-r--r--nuttx/arch/arm/src/armv7-m/vfork.S142
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h4
-rw-r--r--nuttx/arch/arm/src/common/up_vfork.c233
-rw-r--r--nuttx/arch/arm/src/common/up_vfork.h88
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs9
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_flash.c37
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c108
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_uart.h7
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c56
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c11
16 files changed, 680 insertions, 96 deletions
diff --git a/nuttx/arch/Kconfig b/nuttx/arch/Kconfig
index f19228143..d43137adb 100644
--- a/nuttx/arch/Kconfig
+++ b/nuttx/arch/Kconfig
@@ -16,6 +16,7 @@ config ARCH_8051
config ARCH_ARM
bool "ARM"
select ARCH_HAVE_INTERRUPTSTACK
+ select ARCH_HAVE_VFORK
---help---
The ARM architectures
@@ -108,6 +109,10 @@ config ARCH_NOINTC
bool
default n
+config ARCH_VECNOTIRQ
+ bool
+ default n
+
config ARCH_DMA
bool
default n
@@ -124,6 +129,10 @@ config ADDRENV
bool
default n
+config ARCH_HAVE_VFORK
+ bool
+ default n
+
config ARCH_STACKDUMP
bool "Dump stack on assertions"
default n
@@ -136,6 +145,20 @@ config ENDIAN_BIG
---help---
Select if architecture operates using big-endian byte ordering.
+config ARCH_HAVE_RAMFUNCS
+ bool
+ default n
+
+config ARCH_RAMFUNCS
+ bool "Copy functions to RAM on startup"
+ default n
+ depends on ARCH_HAVE_RAMFUNCS
+ ---help---
+ Copy some functions to RAM at boot time. This is done in some
+ architectures to improve performance. In other cases, it is done
+ so that FLASH can be reconfigured while the MCU executes out of
+ SRAM.
+
comment "Board Settings"
config BOARD_LOOPSPERMSEC
diff --git a/nuttx/arch/README.txt b/nuttx/arch/README.txt
index 67b99b255..14704aa76 100644
--- a/nuttx/arch/README.txt
+++ b/nuttx/arch/README.txt
@@ -170,12 +170,12 @@ arch/arm - ARM-based micro-controllers
STATUS: This port has stalled because of development tool issues. Coding
is complete on the basic port (timer, serial console, SPI).
- arch/arm/include/lm3s and arch/arm/src/lm3s
- These directories contain support for the Luminary LMS family, particularly
- for the LM3S6918. The initial, release of this port was included in NuttX version
- 0.4.6. The current port includes timer, serial console, Ethernet, SSI, and microSD
- support. There are working configurations the NuttX OS test, to run the NuttShell
- (NSH), the NuttX networking test, and the uIP web server.
+ arch/arm/include/lm and arch/arm/src/lm
+ These directories contain support for the Luminary LM3S/4F family. The
+ initial, release of this port was included in NuttX version 0.4.6. The
+ current port includes timer, serial console, Ethernet, SSI, and microSD
+ support. There are working configurations the NuttX OS test, to run the
+ NuttShell (NSH), the NuttX networking test, and the uIP web server.
arch/arm/include/lpc214x and arch/arm/src/lpc214x
These directories provide support for NXP LPC214x family of
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index 4fce8efbf..36343e319 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -47,12 +47,13 @@ config ARCH_CHIP_KINETIS
select ARCH_CORTEXM4
select ARCH_HAVE_MPU
select ARCH_IRQPRIO
+ select ARCH_HAVE_RAMFUNCS
+ select ARCH_RAMFUNCS
---help---
Freescale Kinetis Architectures (ARM Cortex-M4)
-config ARCH_CHIP_LM3S
+config ARCH_CHIP_LM
bool "TI Stellaris"
- select ARCH_CORTEXM3
select ARCH_HAVE_MPU
select ARCH_IRQPRIO
---help---
@@ -151,7 +152,7 @@ config ARCH_CHIP
default "dm320" if ARCH_CHIP_DM320
default "imx" if ARCH_CHIP_IMX
default "kinetis" if ARCH_CHIP_KINETIS
- default "lm3s" if ARCH_CHIP_LM3S
+ default "lm" if ARCH_CHIP_LM
default "lpc17xx" if ARCH_CHIP_LPC17XX
default "lpc214x" if ARCH_CHIP_LPC214X
default "lpc2378" if ARCH_CHIP_LPC2378
@@ -274,8 +275,8 @@ endif
if ARCH_CHIP_KINETIS
source arch/arm/src/kinetis/Kconfig
endif
-if ARCH_CHIP_LM3S
-source arch/arm/src/lm3s/Kconfig
+if ARCH_CHIP_LM
+source arch/arm/src/lm/Kconfig
endif
if ARCH_CHIP_LPC17XX
source arch/arm/src/lpc17xx/Kconfig
diff --git a/nuttx/arch/arm/src/armv7-m/Kconfig b/nuttx/arch/arm/src/armv7-m/Kconfig
index dc5aa3915..a154a4c5c 100644
--- a/nuttx/arch/arm/src/armv7-m/Kconfig
+++ b/nuttx/arch/arm/src/armv7-m/Kconfig
@@ -49,3 +49,11 @@ config ARMV7M_TOOLCHAIN_RAISONANCE
depends on HOST_WINDOWS
endchoice
+
+config ARMV7M_OABI_TOOLCHAIN
+ bool "OABI (vs EABI)"
+ default y
+ depends on ARMV7M_TOOLCHAIN_BUILDROOT
+ ---help---
+ Most of the older buildroot toolchains are OABI and are named arm-nuttx-elf- vs. arm-nuttx-eabi-
+
diff --git a/nuttx/arch/arm/src/armv7-m/Toolchain.defs b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
index e214ce8bd..45ee9e36c 100644
--- a/nuttx/arch/arm/src/armv7-m/Toolchain.defs
+++ b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
@@ -53,7 +53,7 @@ ifeq ($(filter y, \
endif
ifeq ($(filter y, \
$(CONFIG_KINETIS_BUILDROOT) \
- $(CONFIG_LM3S_BUILDROOT) \
+ $(CONFIG_LM_BUILDROOT) \
$(CONFIG_LPC17_BUILDROOT) \
$(CONFIG_LPC43_BUILDROOT) \
$(CONFIG_SAM3U_BUILDROOT) \
@@ -77,7 +77,7 @@ ifeq ($(filter y, \
endif
ifeq ($(filter y, \
$(CONFIG_KINETIS_CODESOURCERYL) \
- $(CONFIG_LM3S_CODESOURCERYL) \
+ $(CONFIG_LM_CODESOURCERYL) \
$(CONFIG_LPC17_CODESOURCERYL) \
$(CONFIG_LPC43_CODESOURCERYL) \
$(CONFIG_SAM3U_CODESOURCERYL) \
@@ -88,7 +88,7 @@ ifeq ($(filter y, \
endif
ifeq ($(filter y, \
$(CONFIG_KINETIS_CODESOURCERYW) \
- $(CONFIG_LM3S_CODESOURCERYW) \
+ $(CONFIG_LM_CODESOURCERYW) \
$(CONFIG_LPC17_CODESOURCERYW) \
$(CONFIG_LPC43_CODESOURCERYW) \
$(CONFIG_SAM3U_CODESOURCERYW) \
@@ -99,7 +99,7 @@ ifeq ($(filter y, \
endif
ifeq ($(filter y, \
$(CONFIG_KINETIS_DEVKITARM) \
- $(CONFIG_LM3S_DEVKITARM) \
+ $(CONFIG_LM_DEVKITARM) \
$(CONFIG_LPC17_DEVKITARM) \
$(CONFIG_LPC43_DEVKITARM) \
$(CONFIG_SAM3U_DEVKITARM) \
@@ -160,14 +160,15 @@ endif
# NuttX buildroot under Linux or Cygwin
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),BUILDROOT)
- # OABI
- # CROSSDEV = arm-nuttx-elf-
- # ARCROSSDEV = arm-nuttx-elf-
- # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
- # EABI
+ifeq ($(CONFIG_ARMV7M_OABI_TOOLCHAIN),y)
+ CROSSDEV = arm-nuttx-elf-
+ ARCROSSDEV = arm-nuttx-elf-
+ ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
+else
CROSSDEV = arm-nuttx-eabi-
ARCROSSDEV = arm-nuttx-eabi-
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
+endif
MAXOPTIMIZATION = -Os
endif
diff --git a/nuttx/arch/arm/src/armv7-m/up_doirq.c b/nuttx/arch/arm/src/armv7-m/up_doirq.c
index 375054fba..6063f9ca1 100644
--- a/nuttx/arch/arm/src/armv7-m/up_doirq.c
+++ b/nuttx/arch/arm/src/armv7-m/up_doirq.c
@@ -79,9 +79,11 @@ uint32_t *up_doirq(int irq, uint32_t *regs)
uint32_t *savestate;
/* Nested interrupts are not supported in this implementation. If you want
- * implemented nested interrupts, you would have to (1) change the way that
- * current regs is handled and (2) the design associated with
- * CONFIG_ARCH_INTERRUPTSTACK.
+ * to implement nested interrupts, you would have to (1) change the way that
+ * current_regs is handled and (2) the design associated with
+ * CONFIG_ARCH_INTERRUPTSTACK. The savestate variable will not work for
+ * that purpose as implemented here because only the outermost nested
+ * interrupt can result in a context switch (it can probably be deleted).
*/
/* Current regs non-zero indicates that we are processing an interrupt;
diff --git a/nuttx/arch/arm/src/armv7-m/vfork.S b/nuttx/arch/arm/src/armv7-m/vfork.S
new file mode 100644
index 000000000..f36ff23aa
--- /dev/null
+++ b/nuttx/arch/arm/src/armv7-m/vfork.S
@@ -0,0 +1,142 @@
+/************************************************************************************
+ * arch/arm/src/armv7-m/vfork.S
+ *
+ * Copyright (C) 2013 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "up_vfork.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Global Symbols
+ ************************************************************************************/
+
+ .syntax unified
+ .thumb
+ .file "vfork.S"
+ .globl up_vfork
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: vfork
+ *
+ * Description:
+ * The vfork() function has the same effect as fork(), except that the behavior is
+ * undefined if the process created by vfork() either modifies any data other than
+ * a variable of type pid_t used to store the return value from vfork(), or returns
+ * from the function in which vfork() was called, or calls any other function before
+ * successfully calling _exit() or one of the exec family of functions.
+ *
+ * This thin layer implements vfork by simply calling up_vfork() with the vfork()
+ * context as an argument. The overall sequence is:
+ *
+ * 1) User code calls vfork(). vfork() collects context information and
+ * transfers control up up_vfork().
+ * 2) up_vfork()and calls task_vforksetup().
+ * 3) task_vforksetup() allocates and configures the child task's TCB. This
+ * consists of:
+ * - Allocation of the child task's TCB.
+ * - Initialization of file descriptors and streams
+ * - Configuration of environment variables
+ * - Setup the intput parameters for the task.
+ * - Initialization of the TCB (including call to up_initial_state()
+ * 4) up_vfork() provides any additional operating context. up_vfork must:
+ * - Allocate and initialize the stack
+ * - Initialize special values in any CPU registers that were not
+ * already configured by up_initial_state()
+ * 5) up_vfork() then calls task_vforkstart()
+ * 6) task_vforkstart() then executes the child thread.
+ *
+ * Input Paremeters:
+ * None
+ *
+ * Return:
+ * Upon successful completion, vfork() returns 0 to the child process and returns
+ * the process ID of the child process to the parent process. Otherwise, -1 is
+ * returned to the parent, no child process is created, and errno is set to
+ * indicate the error.
+ *
+ ************************************************************************************/
+
+ .thumb_func
+ .globl vfork
+ .type vfork, function
+vfork:
+ /* Create a stack frame */
+
+ mov r0, sp /* Save the value of the stack on entry */
+ sub sp, sp, #VFORK_SIZEOF /* Allocate the structure on the stack */
+
+ /* CPU registers */
+ /* Save the volatile registers */
+
+ str r4, [sp, #VFORK_R4_OFFSET]
+ str r5, [sp, #VFORK_R5_OFFSET]
+ str r6, [sp, #VFORK_R6_OFFSET]
+ str r7, [sp, #VFORK_R7_OFFSET]
+ str r8, [sp, #VFORK_R8_OFFSET]
+ str r9, [sp, #VFORK_R9_OFFSET]
+ str r10, [sp, #VFORK_R10_OFFSET]
+
+ /* Save the frame pointer, stack pointer, and return address */
+
+ str fp, [sp, #VFORK_FP_OFFSET]
+ str r0, [sp, #VFORK_SP_OFFSET]
+ str lr, [sp, #VFORK_LR_OFFSET]
+
+ /* Floating point registers (not yet) */
+
+ /* Then, call up_vfork(), passing it a pointer to the stack structure */
+
+ mov r0, sp
+ bl up_vfork
+
+ /* Release the stack data and return the value returned by up_vfork */
+
+ ldr lr, [sp, #VFORK_LR_OFFSET]
+ add sp, sp, #VFORK_SIZEOF
+ bx lr
+ .size vfork, .-vfork
+ .end
+
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 0d3c5b1f2..55071345f 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -188,7 +188,7 @@ extern uint32_t _ebss; /* End+1 of .bss */
* will create a function named foo that will execute from RAM.
*/
-#ifdef CONFIG_BOOT_RAMFUNCS
+#ifdef CONFIG_ARCH_RAMFUNCS
# define __ramfunc__ __attribute__ ((section(".ramfunc")))
@@ -204,7 +204,7 @@ extern const uint32_t _framfuncs; /* Copy source address in FLASH */
extern uint32_t _sramfuncs; /* Copy destination start address in RAM */
extern uint32_t _eramfuncs; /* Copy destination start address in RAM */
-#endif /* CONFIG_BOOT_RAMFUNCS */
+#endif /* CONFIG_ARCH_RAMFUNCS */
#endif /* __ASSEMBLY__ */
/****************************************************************************
diff --git a/nuttx/arch/arm/src/common/up_vfork.c b/nuttx/arch/arm/src/common/up_vfork.c
new file mode 100644
index 000000000..3b653e317
--- /dev/null
+++ b/nuttx/arch/arm/src/common/up_vfork.c
@@ -0,0 +1,233 @@
+/****************************************************************************
+ * arch/arm/src/common/up_vfork.c
+ *
+ * Copyright (C) 2013 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/sched.h>
+#include <nuttx/arch.h>
+#include <arch/irq.h>
+
+#include "up_vfork.h"
+#include "os_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* ARM requires at least a 4-byte stack alignment. For use with EABI and
+ * floating point, the stack must be aligned to 8-byte addresses.
+ */
+
+#ifndef CONFIG_STACK_ALIGNMENT
+
+/* The symbol __ARM_EABI__ is defined by GCC if EABI is being used. If you
+ * are not using GCC, make sure that CONFIG_STACK_ALIGNMENT is set correctly!
+ */
+
+# ifdef __ARM_EABI__
+# define CONFIG_STACK_ALIGNMENT 8
+# else
+# define CONFIG_STACK_ALIGNMENT 4
+# endif
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_vfork
+ *
+ * Description:
+ * The vfork() function has the same effect as fork(), except that the
+ * behavior is undefined if the process created by vfork() either modifies
+ * any data other than a variable of type pid_t used to store the return
+ * value from vfork(), or returns from the function in which vfork() was
+ * called, or calls any other function before successfully calling _exit()
+ * or one of the exec family of functions.
+ *
+ * The overall sequence is:
+ *
+ * 1) User code calls vfork(). vfork() collects context information and
+ * transfers control up up_vfork().
+ * 2) up_vfork()and calls task_vforksetup().
+ * 3) task_vforksetup() allocates and configures the child task's TCB. This
+ * consists of:
+ * - Allocation of the child task's TCB.
+ * - Initialization of file descriptors and streams
+ * - Configuration of environment variables
+ * - Setup the intput parameters for the task.
+ * - Initialization of the TCB (including call to up_initial_state()
+ * 4) up_vfork() provides any additional operating context. up_vfork must:
+ * - Allocate and initialize the stack
+ * - Initialize special values in any CPU registers that were not
+ * already configured by up_initial_state()
+ * 5) up_vfork() then calls task_vforkstart()
+ * 6) task_vforkstart() then executes the child thread.
+ *
+ * task_vforkabort() may be called if an error occurs between steps 3 and 6.
+ *
+ * Input Paremeters:
+ * context - Caller context information saved by vfork()
+ *
+ * Return:
+ * Upon successful completion, vfork() returns 0 to the child process and
+ * returns the process ID of the child process to the parent process.
+ * Otherwise, -1 is returned to the parent, no child process is created,
+ * and errno is set to indicate the error.
+ *
+ ****************************************************************************/
+
+pid_t up_vfork(const struct vfork_s *context)
+{
+ _TCB *parent = (FAR _TCB *)g_readytorun.head;
+ _TCB *child;
+ size_t stacksize;
+ uint32_t newsp;
+ uint32_t newfp;
+ uint32_t stackutil;
+ int ret;
+
+ svdbg("r4:%08x r5:%08x r6:%08x r7:%08x\n",
+ context->r4, context->r5, context->r6, context->r7);
+ svdbg("r8:%08x r9:%08x r10:%08x\n",
+ context->r8, context->r9, context->r10);
+ svdbg("fp:%08x sp:%08x lr:%08x\n",
+ context->fp, context->sp, context->lr);
+
+ /* Allocate and initialize a TCB for the child task. */
+
+ child = task_vforksetup((start_t)(context->lr & ~1));
+ if (!child)
+ {
+ sdbg("task_vforksetup failed\n");
+ return (pid_t)ERROR;
+ }
+
+ svdbg("Parent=%p Child=%p\n", parent, child);
+
+ /* Get the size of the parent task's stack. Due to alignment operations,
+ * the adjusted stack size may be smaller than the stack size originally
+ * requrested.
+ */
+
+ stacksize = parent->adj_stack_size + CONFIG_STACK_ALIGNMENT - 1;
+
+ /* Allocate the stack for the TCB */
+
+ ret = up_create_stack(child, stacksize);
+ if (ret != OK)
+ {
+ sdbg("up_create_stack failed: %d\n", ret);
+ task_vforkabort(child, -ret);
+ return (pid_t)ERROR;
+ }
+
+ /* How much of the parent's stack was utilized? The ARM uses
+ * a push-down stack so that the current stack pointer should
+ * be lower than the initial, adjusted stack pointer. The
+ * stack usage should be the difference between those two.
+ */
+
+ DEBUGASSERT((uint32_t)parent->adj_stack_ptr > context->sp);
+ stackutil = (uint32_t)parent->adj_stack_ptr - context->sp;
+
+ svdbg("stacksize:%d stackutil:%d\n", stacksize, stackutil);
+
+ /* Make some feeble effort to perserve the stack contents. This is
+ * feeble because the stack surely contains invalid pointers and other
+ * content that will not work in the child context. However, if the
+ * user follows all of the caveats of vfor() usage, even this feeble
+ * effort is overkill.
+ */
+
+ newsp = (uint32_t)child->adj_stack_ptr - stackutil;
+ memcpy((void *)newsp, (const void *)context->sp, stackutil);
+
+ /* Was there a frame pointer in place before? */
+
+ if (context->fp <= (uint32_t)parent->adj_stack_ptr &&
+ context->fp >= (uint32_t)parent->adj_stack_ptr - stacksize)
+ {
+ uint32_t frameutil = (uint32_t)parent->adj_stack_ptr - context->fp;
+ newfp = (uint32_t)child->adj_stack_ptr - frameutil;
+ }
+ else
+ {
+ newfp = context->fp;
+ }
+
+ svdbg("Old stack base:%08x SP:%08x FP:%08x\n",
+ parent->adj_stack_ptr, context->sp, context->fp);
+ svdbg("New stack base:%08x SP:%08x FP:%08x\n",
+ child->adj_stack_ptr, newsp, newfp);
+
+ /* Update the stack pointer, frame pointer, and volatile registers. When
+ * the child TCB was initialized, all of the values were set to zero.
+ * up_initial_state() altered a few values, but the return value in R0
+ * should be cleared to zero, providing the indication to the newly started
+ * child thread.
+ */
+
+ child->xcp.regs[REG_R4] = context->r4; /* Volatile register r4 */
+ child->xcp.regs[REG_R5] = context->r5; /* Volatile register r5 */
+ child->xcp.regs[REG_R6] = context->r6; /* Volatile register r6 */
+ child->xcp.regs[REG_R7] = context->r7; /* Volatile register r7 */
+ child->xcp.regs[REG_R8] = context->r8; /* Volatile register r8 */
+ child->xcp.regs[REG_R9] = context->r9; /* Volatile register r9 */
+ child->xcp.regs[REG_R10] = context->r10; /* Volatile register r10 */
+ child->xcp.regs[REG_FP] = newfp; /* Frame pointer */
+ child->xcp.regs[REG_SP] = newsp; /* Stack pointer */
+
+ /* And, finally, start the child task. On a failure, task_vforkstart()
+ * will discard the TCB by calling task_vforkabort().
+ */
+
+ return task_vforkstart(child);
+}
diff --git a/nuttx/arch/arm/src/common/up_vfork.h b/nuttx/arch/arm/src/common/up_vfork.h
new file mode 100644
index 000000000..97edf9aaa
--- /dev/null
+++ b/nuttx/arch/arm/src/common/up_vfork.h
@@ -0,0 +1,88 @@
+/****************************************************************************
+ * arch/arm/src/common/up_vfork.h
+ *
+ * Copyright (C) 2013 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_ARM_VFORK_H
+#define __ARCH_ARM_SRC_ARM_VFORK_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define VFORK_R4_OFFSET (0*4) /* Volatile register r4 */
+#define VFORK_R5_OFFSET (1*4) /* Volatile register r5 */
+#define VFORK_R6_OFFSET (2*4) /* Volatile register r6 */
+#define VFORK_R7_OFFSET (3*4) /* Volatile register r7 */
+#define VFORK_R8_OFFSET (4*4) /* Volatile register r8 */
+#define VFORK_R9_OFFSET (5*4) /* Volatile register r9 */
+#define VFORK_R10_OFFSET (6*4) /* Volatile register r10 */
+
+#define VFORK_FP_OFFSET (7*4) /* Frame pointer */
+#define VFORK_SP_OFFSET (8*4) /* Stack pointer*/
+#define VFORK_LR_OFFSET (9*4) /* Return address*/
+
+#define VFORK_SIZEOF (10*4)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+struct vfork_s
+{
+ /* CPU registers */
+
+ uint32_t r4; /* Volatile register r4 */
+ uint32_t r5; /* Volatile register r5 */
+ uint32_t r6; /* Volatile register r6 */
+ uint32_t r7; /* Volatile register r7 */
+ uint32_t r8; /* Volatile register r8 */
+ uint32_t r9; /* Volatile register r9 */
+ uint32_t r10; /* Volatile register r10 */
+
+ uint32_t fp; /* Frame pointer */
+ uint32_t sp; /* Stack pointer*/
+ uint32_t lr; /* Return address*/
+
+ /* Floating point registers (not yet) */
+};
+#endif
+
+#endif /* __ARCH_ARM_SRC_ARM_VFORK_H */
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index baa751c7d..940ff6517 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# arch/arm/src/stm32/Make.defs
#
-# 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
@@ -39,15 +39,16 @@ else
HEAD_ASRC = stm32_vectors.S
endif
-CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S
+CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S \
+ vfork.S
CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \
up_createstack.c up_mdelay.c up_udelay.c up_exit.c \
up_initialize.c up_initialstate.c up_interruptcontext.c \
up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
up_releasepending.c up_releasestack.c up_reprioritizertr.c \
up_schedulesigaction.c up_sigdeliver.c up_systemreset.c \
- up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c up_svcall.c \
- up_stackcheck.c
+ up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c \
+ up_svcall.c up_stackcheck.c up_vfork.c
ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
CMN_ASRCS += up_exception.S
diff --git a/nuttx/arch/arm/src/stm32/stm32_flash.c b/nuttx/arch/arm/src/stm32/stm32_flash.c
index 83fcc6172..20b0cfe10 100644
--- a/nuttx/arch/arm/src/stm32/stm32_flash.c
+++ b/nuttx/arch/arm/src/stm32/stm32_flash.c
@@ -35,7 +35,7 @@
/* Provides standard flash access functions, to be used by the flash mtd driver.
* The interface is defined in the include/nuttx/progmem.h
- *
+ *
* Requirements during write/erase operations on FLASH:
* - HSI must be ON.
* - Low Power Modes are not permitted during write/erase
@@ -80,7 +80,7 @@ void stm32_flash_unlock(void)
if (getreg32(STM32_FLASH_CR) & FLASH_CR_LOCK)
{
/* Unlock sequence */
-
+
putreg32(FLASH_KEY1, STM32_FLASH_KEYR);
putreg32(FLASH_KEY2, STM32_FLASH_KEYR);
}
@@ -112,6 +112,11 @@ uint16_t up_progmem_pagesize(uint16_t page)
int up_progmem_getpage(uint32_t addr)
{
+ if (addr >= STM32_FLASH_BASE)
+ {
+ addr -= STM32_FLASH_BASE;
+ }
+
if (addr >= STM32_FLASH_SIZE)
{
return -EFAULT;
@@ -131,14 +136,14 @@ int up_progmem_erasepage(uint16_t page)
}
/* Get flash ready and begin erasing single page */
-
+
if (!(getreg32(STM32_RCC_CR) & RCC_CR_HSION))
{
return -EPERM;
}
-
+
stm32_flash_unlock();
-
+
modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_PER);
putreg32(page * STM32_FLASH_PAGESIZE, STM32_FLASH_AR);
modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_STRT);
@@ -146,10 +151,10 @@ int up_progmem_erasepage(uint16_t page)
while(getreg32(STM32_FLASH_SR) & FLASH_SR_BSY) up_waste();
modifyreg32(STM32_FLASH_CR, FLASH_CR_PER, 0);
-
+
/* Verify */
-
- for (addr = page * STM32_FLASH_PAGESIZE + STM32_FLASH_BASE, count = STM32_FLASH_PAGESIZE;
+
+ for (addr = page * STM32_FLASH_PAGESIZE + STM32_FLASH_BASE, count = STM32_FLASH_PAGESIZE;
count; count-=4, addr += 4)
{
if (getreg32(addr) != 0xffffffff)
@@ -173,8 +178,8 @@ int up_progmem_ispageerased(uint16_t page)
}
/* Verify */
-
- for (addr = page * STM32_FLASH_PAGESIZE + STM32_FLASH_BASE, count = STM32_FLASH_PAGESIZE;
+
+ for (addr = page * STM32_FLASH_PAGESIZE + STM32_FLASH_BASE, count = STM32_FLASH_PAGESIZE;
count; count--, addr++)
{
if (getreg8(addr) != 0xff)
@@ -200,6 +205,11 @@ int up_progmem_write(uint32_t addr, const void *buf, size_t count)
/* Check for valid address range */
+ if (addr >= STM32_FLASH_BASE)
+ {
+ addr -= STM32_FLASH_BASE;
+ }
+
if ((addr+count) >= STM32_FLASH_SIZE)
{
return -EFAULT;
@@ -213,10 +223,10 @@ int up_progmem_write(uint32_t addr, const void *buf, size_t count)
}
stm32_flash_unlock();
-
+
modifyreg32(STM32_FLASH_CR, 0, FLASH_CR_PG);
-
- for (addr += STM32_FLASH_BASE; count; count--, hword++, addr+=2)
+
+ for (addr += STM32_FLASH_BASE; count; count-=2, hword++, addr+=2)
{
/* Write half-word and wait to complete */
@@ -237,7 +247,6 @@ int up_progmem_write(uint32_t addr, const void *buf, size_t count)
modifyreg32(STM32_FLASH_CR, FLASH_CR_PG, 0);
return -EIO;
}
-
}
modifyreg32(STM32_FLASH_CR, FLASH_CR_PG, 0);
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index aa46a8987..bfb64b26a 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -79,22 +79,22 @@
#if SERIAL_HAVE_DMA
-/* Verify that DMA has been enabled an the DMA channel has been defined.
- * NOTE: These assignments may only be true for the F4.
+# if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+/* Verify that DMA has been enabled and the DMA channel has been defined.
*/
-# if defined(CONFIG_USART1_RXDMA) || defined(CONFIG_USART6_RXDMA)
-# ifndef CONFIG_STM32_DMA2
-# error STM32 USART1/6 receive DMA requires CONFIG_STM32_DMA2
+# if defined(CONFIG_USART1_RXDMA) || defined(CONFIG_USART6_RXDMA)
+# ifndef CONFIG_STM32_DMA2
+# error STM32 USART1/6 receive DMA requires CONFIG_STM32_DMA2
+# endif
# endif
-# endif
-# if defined(CONFIG_USART2_RXDMA) || defined(CONFIG_USART3_RXDMA) || \
+# if defined(CONFIG_USART2_RXDMA) || defined(CONFIG_USART3_RXDMA) || \
defined(CONFIG_UART4_RXDMA) || defined(CONFIG_UART5_RXDMA)
-# ifndef CONFIG_STM32_DMA1
-# error STM32 USART2/3/4/5 receive DMA requires CONFIG_STM32_DMA1
+# ifndef CONFIG_STM32_DMA1
+# error STM32 USART2/3/4/5 receive DMA requires CONFIG_STM32_DMA1
+# endif
# endif
-# endif
/* Currently RS-485 support cannot be enabled when RXDMA is in use due to lack
* of testing - RS-485 support was developed on STM32F1x
@@ -114,28 +114,52 @@
* the following in the board.h file.
*/
-# if defined(CONFIG_USART1_RXDMA) && !defined(DMAMAP_USART1_RX)
-# error "USART1 DMA channel not defined (DMAMAP_USART1_RX)"
-# endif
+# if defined(CONFIG_USART1_RXDMA) && !defined(DMAMAP_USART1_RX)
+# error "USART1 DMA channel not defined (DMAMAP_USART1_RX)"
+# endif
-# if defined(CONFIG_USART2_RXDMA) && !defined(DMAMAP_USART2_RX)
-# error "USART2 DMA channel not defined (DMAMAP_USART2_RX)"
-# endif
+# if defined(CONFIG_USART2_RXDMA) && !defined(DMAMAP_USART2_RX)
+# error "USART2 DMA channel not defined (DMAMAP_USART2_RX)"
+# endif
-# if defined(CONFIG_USART3_RXDMA) && !defined(DMAMAP_USART3_RX)
-# error "USART3 DMA channel not defined (DMAMAP_USART3_RX)"
-# endif
+# if defined(CONFIG_USART3_RXDMA) && !defined(DMAMAP_USART3_RX)
+# error "USART3 DMA channel not defined (DMAMAP_USART3_RX)"
+# endif
-# if defined(CONFIG_UART4_RXDMA) && !defined(DMAMAP_UART4_RX)
-# error "UART4 DMA channel not defined (DMAMAP_UART4_RX)"
-# endif
+# if defined(CONFIG_UART4_RXDMA) && !defined(DMAMAP_UART4_RX)
+# error "UART4 DMA channel not defined (DMAMAP_UART4_RX)"
+# endif
-# if defined(CONFIG_UART5_RXDMA) && !defined(DMAMAP_UART5_RX)
-# error "UART5 DMA channel not defined (DMAMAP_UART5_RX)"
-# endif
+# if defined(CONFIG_UART5_RXDMA) && !defined(DMAMAP_UART5_RX)
+# error "UART5 DMA channel not defined (DMAMAP_UART5_RX)"
+# endif
+
+# if defined(CONFIG_USART6_RXDMA) && !defined(DMAMAP_USART6_RX)
+# error "USART6 DMA channel not defined (DMAMAP_USART6_RX)"
+# endif
+
+# elif defined(CONFIG_STM32_STM32F10XX)
+
+# if defined(CONFIG_USART1_RXDMA) || defined(CONFIG_USART2_RXDMA) || \
+ defined(CONFIG_USART3_RXDMA)
+# ifndef CONFIG_STM32_DMA1
+# error STM32 USART1/2/3 receive DMA requires CONFIG_STM32_DMA1
+# endif
+# endif
+
+# if defined(CONFIG_UART4_RXDMA)
+# ifndef CONFIG_STM32_DMA2
+# error STM32 USART4 receive DMA requires CONFIG_STM32_DMA2
+# endif
+# endif
+
+/* There are no optional DMA channel assignments for the F1 */
+
+# define DMAMAP_USART1_RX DMACHAN_USART1_RX
+# define DMAMAP_USART2_RX DMACHAN_USART2_RX
+# define DMAMAP_USART3_RX DMACHAN_USART3_RX
+# define DMAMAP_UART4_RX DMACHAN_USART4_RX
-# if defined(CONFIG_USART6_RXDMA) && !defined(DMAMAP_USART6_RX)
-# error "USART6 DMA channel not defined (DMAMAP_USART6_RX)"
# endif
/* The DMA buffer size when using RX DMA to emulate a FIFO.
@@ -169,6 +193,27 @@
# error "Unknown STM32 DMA"
# endif
+/* DMA control word */
+
+# if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+# define SERIAL_DMA_CONTROL_WORD \
+ (DMA_SCR_DIR_P2M | \
+ DMA_SCR_CIRC | \
+ DMA_SCR_MINC | \
+ DMA_SCR_PSIZE_8BITS | \
+ DMA_SCR_MSIZE_8BITS | \
+ CONFIG_USART_DMAPRIO | \
+ DMA_SCR_PBURST_SINGLE | \
+ DMA_SCR_MBURST_SINGLE)
+# else
+# define SERIAL_DMA_CONTROL_WORD \
+ (DMA_CCR_CIRC | \
+ DMA_CCR_MINC | \
+ DMA_CCR_PSIZE_8BITS | \
+ DMA_CCR_MSIZE_8BITS | \
+ CONFIG_USART_DMAPRIO)
+# endif
+
#endif
/* Power management definitions */
@@ -1115,14 +1160,7 @@ static int up_dma_setup(struct uart_dev_s *dev)
priv->usartbase + STM32_USART_DR_OFFSET,
(uint32_t)priv->rxfifo,
RXDMA_BUFFER_SIZE,
- DMA_SCR_DIR_P2M |
- DMA_SCR_CIRC |
- DMA_SCR_MINC |
- DMA_SCR_PSIZE_8BITS |
- DMA_SCR_MSIZE_8BITS |
- CONFIG_USART_DMAPRIO |
- DMA_SCR_PBURST_SINGLE |
- DMA_SCR_MBURST_SINGLE);
+ SERIAL_DMA_CONTROL_WORD);
/* Reset our DMA shadow pointer to match the address just
* programmed above.
diff --git a/nuttx/arch/arm/src/stm32/stm32_uart.h b/nuttx/arch/arm/src/stm32/stm32_uart.h
index 8ff6a9975..a26ea2009 100644
--- a/nuttx/arch/arm/src/stm32/stm32_uart.h
+++ b/nuttx/arch/arm/src/stm32/stm32_uart.h
@@ -140,12 +140,9 @@
# undef HAVE_CONSOLE
#endif
-/* DMA support is only provided if CONFIG_ARCH_DMA is in the NuttX configuration.
- * Furthermore, DMA support is currently only implemented for the F4 (but could be
- * extended to the F1 and F2 with a little effort in the DMA code.
- */
+/* DMA support is only provided if CONFIG_ARCH_DMA is in the NuttX configuration */
-#if !defined(HAVE_UART) || !defined(CONFIG_ARCH_DMA) || !defined(CONFIG_STM32_STM32F40XX)
+#if !defined(HAVE_UART) || !defined(CONFIG_ARCH_DMA)
# undef CONFIG_USART1_RXDMA
# undef CONFIG_USART2_RXDMA
# undef CONFIG_USART3_RXDMA
diff --git a/nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c b/nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c
index 89b279bea..13324b8ac 100644
--- a/nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c
+++ b/nuttx/arch/arm/src/stm32/stm32f10xxx_dma.c
@@ -303,13 +303,13 @@ 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 */
+ /* Clear the interrupts we are handling */
- stm32_dmachandisable(dmach);
+ dmabase_putreg(dmach, STM32_DMA_IFCR_OFFSET, isr);
/* Invoke the callback */
@@ -528,14 +528,34 @@ 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.
+ /* In normal mode, interrupt at either half or full completion. In circular mode,
+ * always interrupt on buffer wrap, and optionally interrupt at the halfway point.
*/
- ccr |= (half ? (DMA_CCR_HTIE|DMA_CCR_TEIE) : (DMA_CCR_TCIE|DMA_CCR_TEIE));
+ if ((ccr & DMA_CCR_CIRC) == 0)
+ {
+ /* 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;
+ }
+
dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, ccr);
}
@@ -559,6 +579,24 @@ void stm32_dmastop(DMA_HANDLE handle)
}
/****************************************************************************
+ * Name: stm32_dmaresidual
+ *
+ * Description:
+ * Returns the number of bytes remaining to be transferred
+ *
+ * Assumptions:
+ * - DMA handle allocated by stm32_dmachannel()
+ *
+ ****************************************************************************/
+
+size_t stm32_dmaresidual(DMA_HANDLE handle)
+{
+ struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
+
+ return dmachan_getreg(dmach, STM32_DMACHAN_CNDTR_OFFSET);
+}
+
+/****************************************************************************
* 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 dcbbf1856..40fce8cb5 100644
--- a/nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c
+++ b/nuttx/arch/arm/src/stm32/stm32f40xxx_dma.c
@@ -94,7 +94,6 @@ struct stm32_dma_s
uint8_t irq; /* DMA stream IRQ number */
uint8_t shift; /* ISR/IFCR bit shift value */
uint8_t channel; /* DMA channel number (0-7) */
- bool nonstop; /* Stream is configured in a 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 */
@@ -728,7 +727,6 @@ void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
DMA_SCR_DBM|DMA_SCR_CIRC|
DMA_SCR_PBURST_MASK|DMA_SCR_MBURST_MASK);
regval |= scr;
- dmast->nonstop = (scr & (DMA_SCR_DBM|DMA_SCR_CIRC)) != 0;
dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, regval);
}
@@ -764,7 +762,12 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
scr = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
scr |= DMA_SCR_EN;
- if (!dmast->nonstop)
+ /* In normal mode, interrupt at either half or full completion. In circular
+ * and double-buffered modes, always interrupt on buffer wrap, and optionally
+ * interrupt at the halfway point.
+ */
+
+ if ((scr & (DMA_SCR_DBM|DMA_SCR_CIRC)) == 0)
{
/* 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
@@ -777,7 +780,7 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
}
else
{
- /* In nonstop mode, when the transfer completes it immediately resets
+ /* 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
* mode to determine when the buffer is half-full, or in double-buffered