summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_mpuinit.c2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_start.c2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_userspace.h1
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S6
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs11
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_allocateheap.c133
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_mpuinit.c124
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_mpuinit.h90
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_start.c16
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_userspace.c119
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_userspace.h76
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_vectors.S37
12 files changed, 587 insertions, 30 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_mpuinit.c b/nuttx/arch/arm/src/lpc17xx/lpc17_mpuinit.c
index c5d1ab11c..046f6e703 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_mpuinit.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_mpuinit.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/src/common/lpc17_mpuinit.c
+ * arch/arm/src/lpc17xx/lpc17_mpuinit.c
*
* Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_start.c b/nuttx/arch/arm/src/lpc17xx/lpc17_start.c
index 57496ab2a..f5af4c913 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_start.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_start.c
@@ -236,7 +236,7 @@ void __start(void)
/* For the case of the separate user-/kernel-space build, perform whatever
* platform specific initialization of the user memory is required.
* Normally this just means initializing the user space .data and .bss
- * segements.
+ * segments.
*/
#ifdef CONFIG_NUTTX_KERNEL
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_userspace.h b/nuttx/arch/arm/src/lpc17xx/lpc17_userspace.h
index c4d265cc0..7f9c75dd4 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_userspace.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_userspace.h
@@ -41,7 +41,6 @@
************************************************************************************/
#include <nuttx/config.h>
-#include "chip/lpc17_qei.h"
/************************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S b/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S
index 9575e1f3e..06b6afdf6 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S
@@ -61,7 +61,7 @@
* 0x1000:7fff - End of CPU SRAM and end of heap (1st region)
*/
-#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
+#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
/* The Cortex-M3 return from interrupt is unusual. We provide the following special
@@ -306,8 +306,8 @@ lpc17_common:
#endif
/* We are returning with a pending context switch. This case is different
- * because in this case, the register save structure does not lie on the
- * stack but, rather, are within a TCB structure. We'll have to copy some
+ * because in this case, the register save structure does not lie in the
+ * stack but, rather, within a TCB structure. We'll have to copy some
* values to the stack.
*/
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index d51c360fe..c26843039 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -64,6 +64,13 @@ ifeq ($(CONFIG_ARCH_MEMCPY),y)
CMN_ASRCS += up_memcpy.S
endif
+ifeq ($(CONFIG_NUTTX_KERNEL),y)
+CMN_CSRCS += up_mpu.c up_task_start.c up_pthread_start.c up_stackframe.c
+ifneq ($(CONFIG_DISABLE_SIGNALS),y)
+CMN_CSRCS += up_signal_handler.c
+endif
+endif
+
ifeq ($(CONFIG_DEBUG_STACK),y)
CMN_CSRCS += up_checkstack.c
endif
@@ -87,6 +94,10 @@ ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
CHIP_ASRCS += stm32_vectors.S
endif
+ifeq ($(CONFIG_NUTTX_KERNEL),y)
+CHIP_CSRCS += stm32_userspace.c stm32_mpuinit.c
+endif
+
ifeq ($(CONFIG_USBDEV),y)
ifeq ($(CONFIG_STM32_USB),y)
CHIP_CSRCS += stm32_usbdev.c
diff --git a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
index 6a29fb16c..3eed90dd4 100644
--- a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
+++ b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
@@ -58,7 +58,7 @@
* following definitions must be provided to specify the size and
* location of internal(system) SRAM:
*
- * CONFIG_DRAM_END : End address (+1) of SRAM (F1 family only, the
+ * SRAM1_END : End address (+1) of SRAM (F1 family only, the
* : F4 family uses the a priori end of SRAM)
*
* The F4 family also contains internal CCM SRAM. This SRAM is different
@@ -88,7 +88,7 @@
#endif
/* For the STM312F10xxx family, all internal SRAM is in one contiguous block
- * starting at g_idle_topstack and extending through CONFIG_DRAM_END (my apologies for
+ * starting at g_idle_topstack and extending through SRAM1_END (my apologies for
* the bad naming). In addition, external FSMC SRAM may be available.
*/
@@ -96,7 +96,7 @@
/* Set the end of system SRAM */
-# define SRAM1_END CONFIG_DRAM_END
+# define SRAM1_END SRAM1_END
/* Check if external FSMC SRAM is provided */
@@ -130,7 +130,7 @@
/* Set the end of system SRAM */
-# define SRAM1_END CONFIG_DRAM_END
+# define SRAM1_END SRAM1_END
/* Set the range of CCM SRAM as well (although we may not use it) */
@@ -365,14 +365,113 @@
* If a protected kernel-space heap is provided, the kernel heap must be
* allocated (and protected) by an analogous up_allocate_kheap().
*
+ * The following memory map is assumed for the flat build:
+ *
+ * .data region. Size determined at link time.
+ * .bss region Size determined at link time.
+ * IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE.
+ * Heap. Extends to the end of SRAM.
+ *
+ * The following memory map is assumed for the kernel build:
+ *
+ * Kernel .data region. Size determined at link time.
+ * Kernel .bss region Size determined at link time.
+ * Kernel IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE.
+ * Padding for alignment
+ * User .data region. Size determined at link time.
+ * User .bss region Size determined at link time.
+ * Kernel heap. Size determined by CONFIG_MM_KERNEL_HEAPSIZE.
+ * User heap. Extends to the end of SRAM.
+ *
****************************************************************************/
void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
{
+#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP)
+ /* Get the unaligned size and position of the user-space heap.
+ * This heap begins after the user-space .bss section at an offset
+ * of CONFIG_MM_KERNEL_HEAPSIZE (subject to alignment).
+ */
+
+ uintptr_t ubase = (uintptr_t)USERSPACE->us_bssend + CONFIG_MM_KERNEL_HEAPSIZE;
+ size_t usize = SRAM1_END - ubase;
+ int log2;
+
+ DEBUGASSERT(ubase < (uintptr_t)SRAM1_END);
+
+ /* Adjust that size to account for MPU alignment requirements.
+ * NOTE that there is an implicit assumption that the SRAM1_END
+ * is aligned to the MPU requirement.
+ */
+
+ log2 = (int)mpu_log2regionfloor(usize);
+ DEBUGASSERT((SRAM1_END & ((1 << log2) - 1)) == 0);
+
+ usize = (1 << log2);
+ ubase = SRAM1_END - usize;
+
+ /* Return the user-space heap settings */
+
+ up_ledon(LED_HEAPALLOCATE);
+ *heap_start = (FAR void*)ubase;
+ *heap_size = usize;
+
+ /* Allow user-mode access to the user heap memory */
+
+ stm32_mpu_uheap((uintptr_t)ubase, usize);
+#else
+
+ /* Return the heap settings */
+
up_ledon(LED_HEAPALLOCATE);
*heap_start = (FAR void*)g_idle_topstack;
*heap_size = SRAM1_END - g_idle_topstack;
+#endif
+}
+
+/****************************************************************************
+ * Name: up_allocate_kheap
+ *
+ * Description:
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function allocates
+ * (and protects) the kernel-space heap.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP)
+void up_allocate_kheap(FAR void **heap_start, size_t *heap_size)
+{
+ /* Get the unaligned size and position of the user-space heap.
+ * This heap begins after the user-space .bss section at an offset
+ * of CONFIG_MM_KERNEL_HEAPSIZE (subject to alignment).
+ */
+
+ uintptr_t ubase = (uintptr_t)USERSPACE->us_bssend + CONFIG_MM_KERNEL_HEAPSIZE;
+ size_t usize = SRAM1_END - ubase;
+ int log2;
+
+ DEBUGASSERT(ubase < (uintptr_t)SRAM1_END);
+
+ /* Adjust that size to account for MPU alignment requirements.
+ * NOTE that there is an implicit assumption that the SRAM1_END
+ * is aligned to the MPU requirement.
+ */
+
+ log2 = (int)mpu_log2regionfloor(usize);
+ DEBUGASSERT((SRAM1_END & ((1 << log2) - 1)) == 0);
+
+ usize = (1 << log2);
+ ubase = SRAM1_END - usize;
+
+ /* Return the kernel heap settings (i.e., the part of the heap region
+ * that was not dedicated to the user heap).
+ */
+
+ *heap_start = (FAR void*)USERSPACE->us_bssend;
+ *heap_size = ubase - (uintptr_t)USERSPACE->us_bssend;
}
+#endif
/****************************************************************************
* Name: up_addregion
@@ -386,16 +485,32 @@ void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
#if CONFIG_MM_REGIONS > 1
void up_addregion(void)
{
- /* Add the STM32F20xxx/STM32F40xxx CCM SRAM heap region. */
-
#ifndef CONFIG_STM32_CCMEXCLUDE
- kmm_addregion((FAR void*)SRAM2_START, SRAM2_END-SRAM2_START);
+#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP)
+
+ /* Allow user-mode access to the STM32F20xxx/STM32F40xxx CCM SRAM heap */
+
+ stm32_mpu_uheap((uintptr_t)SRAM2_START, SRAM2_END-SRAM2_START);
+
#endif
- /* Add the external FSMC SRAM heap region. */
+ /* Add the STM32F20xxx/STM32F40xxx CCM SRAM user heap region. */
+
+ kumm_addregion((FAR void*)SRAM2_START, SRAM2_END-SRAM2_START);
+#endif
#ifdef CONFIG_STM32_FSMC_SRAM
- kmm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
+#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP)
+
+ /* Allow user-mode access to the FSMC SRAM user heap memory */
+
+ stm32_mpu_uheap((uintptr_t)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
+
+#endif
+
+ /* Add the external FSMC SRAM user heap region. */
+
+ kumm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
#endif
}
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32_mpuinit.c b/nuttx/arch/arm/src/stm32/stm32_mpuinit.c
new file mode 100644
index 000000000..0b44a32cc
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_mpuinit.c
@@ -0,0 +1,124 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32_mpuinit.c
+ *
+ * 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
+ * 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 <assert.h>
+
+#include <nuttx/userspace.h>
+
+#include "mpu.h"
+#include "stm32_mpuinit.h"
+
+#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_ARMV7M_MPU)
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+#ifndef MAX
+# define MAX(a,b) a > b ? a : b
+#endif
+
+#ifndef MIN
+# define MIN(a,b) a < b ? a : b
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_mpuinitialize
+ *
+ * Description:
+ * Configure the MPU to permit user-space access to only restricted SAM3U
+ * resources.
+ *
+ ****************************************************************************/
+
+void stm32_mpuinitialize(void)
+{
+ uintptr_t datastart = MIN(USERSPACE->us_datastart, USERSPACE->us_bssstart);
+ uintptr_t dataend = MAX(USERSPACE->us_dataend, USERSPACE->us_bssend);
+
+ DEBUGASSERT(USERSPACE->us_textend >= USERSPACE->us_textstart &&
+ dataend >= datastart);
+
+ /* Show MPU information */
+
+ mpu_showtype();
+
+ /* Configure user flash and SRAM space */
+
+ mpu_userflash(USERSPACE->us_textstart,
+ USERSPACE->us_textend - USERSPACE->us_textstart);
+
+ mpu_userintsram(datastart, dataend - datastart);
+
+ /* Then enable the MPU */
+
+ mpu_control(true, false, true);
+}
+
+/****************************************************************************
+ * Name: stm32_mpu_uheap
+ *
+ * Description:
+ * Map the user-heap region.
+ *
+ * This logic may need an extension to handle external SDRAM).
+ *
+ ****************************************************************************/
+
+void stm32_mpu_uheap(uintptr_t start, size_t size)
+{
+ mpu_userintsram(start, size);
+}
+
+#endif /* CONFIG_NUTTX_KERNEL && CONFIG_ARMV7M_MPU */
+
diff --git a/nuttx/arch/arm/src/stm32/stm32_mpuinit.h b/nuttx/arch/arm/src/stm32/stm32_mpuinit.h
new file mode 100644
index 000000000..009306947
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_mpuinit.h
@@ -0,0 +1,90 @@
+/************************************************************************************
+ * arch/arm/src/stm32/stm32_mpuinit.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_STM32_STM32_MPUINIT_H
+#define __ARCH_ARM_SRC_STM32_STM32_MPUINIT_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_mpuinitialize
+ *
+ * Description:
+ * Configure the MPU to permit user-space access to only unrestricted MCU
+ * resources.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NUTTX_KERNEL
+void stm32_mpuinitialize(void);
+#else
+# define stm32_mpuinitialize()
+#endif
+
+/****************************************************************************
+ * Name: stm32_mpu_uheap
+ *
+ * Description:
+ * Map the user heap region.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NUTTX_KERNEL
+void stm32_mpu_uheap(uintptr_t start, size_t size);
+#else
+# define stm32_mpu_uheap(start,size)
+#endif
+
+#endif /* __ARCH_ARM_SRC_STM32_STM32_MPUINIT_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32_start.c b/nuttx/arch/arm/src/stm32/stm32_start.c
index b90beeb16..a2f82f7b2 100644
--- a/nuttx/arch/arm/src/stm32/stm32_start.c
+++ b/nuttx/arch/arm/src/stm32/stm32_start.c
@@ -52,6 +52,7 @@
#include "stm32.h"
#include "stm32_gpio.h"
+#include "stm32_userspace.h"
#ifdef CONFIG_ARCH_FPU
# include "nvic.h"
@@ -198,6 +199,7 @@ void __start(void)
{
*dest++ = 0;
}
+
showprogress('B');
/* Move the intialized data section from his temporary holding spot in
@@ -210,6 +212,7 @@ void __start(void)
{
*dest++ = *src++;
}
+
showprogress('C');
/* Perform early serial initialization */
@@ -219,10 +222,21 @@ void __start(void)
#endif
showprogress('D');
+ /* For the case of the separate user-/kernel-space build, perform whatever
+ * platform specific initialization of the user memory is required.
+ * Normally this just means initializing the user space .data and .bss
+ * segments.
+ */
+
+#ifdef CONFIG_NUTTX_KERNEL
+ stm32_userspace();
+ showprogress('E');
+#endif
+
/* Initialize onboard resources */
stm32_boardinitialize();
- showprogress('E');
+ showprogress('F');
/* Then start NuttX */
diff --git a/nuttx/arch/arm/src/stm32/stm32_userspace.c b/nuttx/arch/arm/src/stm32/stm32_userspace.c
new file mode 100644
index 000000000..c51e9e725
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_userspace.c
@@ -0,0 +1,119 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32_userspace.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 <assert.h>
+
+#include <nuttx/userspace.h>
+
+#include "stm32_mpuinit.h"
+#include "stm32_userspace.h"
+
+#ifdef CONFIG_NUTTX_KERNEL
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_userspace
+ *
+ * Description:
+ * For the case of the separate user-/kernel-space build, perform whatever
+ * platform specific initialization of the user memory is required.
+ * Normally this just means initializing the user space .data and .bss
+ * segments.
+ *
+ ****************************************************************************/
+
+void stm32_userspace(void)
+{
+ uint8_t *src;
+ uint8_t *dest;
+ uint8_t *end;
+
+ /* Clear all of user-space .bss */
+
+ DEBUGASSERT(USERSPACE->us_bssstart != 0 && USERSPACE->us_bssend != 0 &&
+ USERSPACE->us_bssstart <= USERSPACE->us_bssend);
+
+ dest = (uint8_t*)USERSPACE->us_bssstart;
+ end = (uint8_t*)USERSPACE->us_bssend;
+
+ while (dest != end)
+ {
+ *dest++ = 0;
+ }
+
+ /* Initialize all of user-space .data */
+
+ DEBUGASSERT(USERSPACE->us_datasource != 0 &&
+ USERSPACE->us_datastart != 0 && USERSPACE->us_dataend != 0 &&
+ USERSPACE->us_datastart <= USERSPACE->us_dataend);
+
+ src = (uint8_t*)USERSPACE->us_datasource;
+ dest = (uint8_t*)USERSPACE->us_datastart;
+ end = (uint8_t*)USERSPACE->us_dataend;
+
+ while (dest != end)
+ {
+ *dest++ = *src++;
+ }
+
+ /* Configure the MPU to permit user-space access to its FLASH and RAM */
+
+ stm32_mpuinitialize();
+}
+
+#endif /* CONFIG_NUTTX_KERNEL */
+
diff --git a/nuttx/arch/arm/src/stm32/stm32_userspace.h b/nuttx/arch/arm/src/stm32/stm32_userspace.h
new file mode 100644
index 000000000..16cd3c8e2
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_userspace.h
@@ -0,0 +1,76 @@
+/************************************************************************************
+ * arch/arm/src/stm32/stm32_qei.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_STM32_STM32_USERSPACE_H
+#define __ARCH_ARM_SRC_STM32_STM32_USERSPACE_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_userspace
+ *
+ * Description:
+ * For the case of the separate user-/kernel-space build, perform whatever
+ * platform specific initialization of the user memory is required.
+ * Normally this just means initializing the user space .data and .bss
+ * segments.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NUTTX_KERNEL
+void stm32_userspace(void);
+#endif
+
+#endif /* __ARCH_ARM_SRC_STM32_STM32_USERSPACE_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32_vectors.S b/nuttx/arch/arm/src/stm32/stm32_vectors.S
index 6b9c0affe..c81ae74f5 100644
--- a/nuttx/arch/arm/src/stm32/stm32_vectors.S
+++ b/nuttx/arch/arm/src/stm32/stm32_vectors.S
@@ -69,8 +69,8 @@
* 0x2000:ffff - End of SRAM and end of heap
*/
-#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
-#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
+#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
+#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
/* The Cortex-M3 return from interrupt is unusual. We provide the following special
* address to the BX instruction. The particular value also forces a return to
@@ -219,7 +219,7 @@ stm32_common:
#ifdef CONFIG_NUTTX_KERNEL
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
- * (handler mode) if the state is on the MSP. It can only be on the PSP if
+ * (handler mode) if the stack is on the MSP. It can only be on the PSP if
* EXC_RETURN is 0xfffffffd (unprivileged thread)
*/
@@ -314,10 +314,10 @@ stm32_common:
bl up_restorefpu /* Restore the FPU registers */
#endif
- /* Returning with a pending context switch is different from the normal
- * return because in this case, the register save structure does not lie
- * on the stack but, rather, are within a TCB structure. We'll have to
- * copy somevalues to the new stack.
+ /* We are returning with a pending context switch. This case is different
+ * because in this case, the register save structure does not lie in the
+ * stack but, rather, within a TCB structure. We'll have to copy some
+ * values to the stack.
*/
add r1, r0, #SW_XCPT_SIZE /* R1=Address of HW save area in reg array */
@@ -343,6 +343,7 @@ stm32_common:
#else
ldmia r1!, {r2-r11} /* Recover R4-R11 + 2 temp values */
#endif
+
#ifdef CONFIG_ARCH_FPU
/* Skip over the block of memory reserved for floating pointer register
* save. Then R1 is the address of the HW save area
@@ -360,16 +361,25 @@ stm32_common:
* r4-r11 = restored register values
*/
2:
+
#ifdef CONFIG_NUTTX_KERNEL
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
- * (handler mode) if the state is on the MSP. It can only be on the PSP if
+ * (handler mode) if the stack is on the MSP. It can only be on the PSP if
* EXC_RETURN is 0xfffffffd (unprivileged thread)
*/
- adds r0, r14, #3 /* If R14=0xfffffffd, then r0 == 0 */
- ite ne /* Next two instructions are condition */
- msrne msp, r1 /* R1=The main stack pointer */
- msreq psp, r1 /* R1=The process stack pointer */
+ mrs r2, control /* R2=Contents of the control register */
+ tst r14, #EXC_RETURN_PROCESS_STACK /* nonzero if context on process stack */
+ beq 3f /* Branch if privileged */
+
+ orr r2, r2, #1 /* Unprivileged mode */
+ msr psp, r1 /* R1=The process stack pointer */
+ b 4f
+3:
+ bic r2, r2, #1 /* Privileged mode */
+ msr msp, r1 /* R1=The main stack pointer */
+4:
+ msr control, r2 /* Save the updated control register */
#else
msr msp, r1 /* Recover the return MSP value */
@@ -432,8 +442,7 @@ g_intstackbase:
.globl g_idle_topstack
.type g_idle_topstack, object
g_idle_topstack:
- .long _ebss+CONFIG_IDLETHREAD_STACKSIZE
+ .word HEAP_BASE
.size g_idle_topstack, .-g_idle_topstack
.end
-