From 504178ba1726406e45d21a2824b34f216ee47af3 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 24 Mar 2013 17:28:38 +0000 Subject: Add kernel build support for Stellaris, Kinetis, LPC43, and NUC1xx MCUs git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5781 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/common/up_allocateheap.c | 83 +++++++++- nuttx/arch/arm/src/kinetis/Make.defs | 63 ++++--- nuttx/arch/arm/src/kinetis/kinetis_allocateheap.c | 192 ++++++++++++++++++++++ nuttx/arch/arm/src/kinetis/kinetis_mpuinit.c | 124 ++++++++++++++ nuttx/arch/arm/src/kinetis/kinetis_mpuinit.h | 90 ++++++++++ nuttx/arch/arm/src/kinetis/kinetis_start.c | 11 ++ nuttx/arch/arm/src/kinetis/kinetis_userspace.c | 119 ++++++++++++++ nuttx/arch/arm/src/kinetis/kinetis_userspace.h | 76 +++++++++ nuttx/arch/arm/src/kinetis/kinetis_vectors.S | 107 ++++++++++-- nuttx/arch/arm/src/lm/Make.defs | 47 ++++-- nuttx/arch/arm/src/lm/chip/lm4f_pinmap.h | 2 +- nuttx/arch/arm/src/lm/lm_allocateheap.c | 192 ++++++++++++++++++++++ nuttx/arch/arm/src/lm/lm_mpuinit.c | 124 ++++++++++++++ nuttx/arch/arm/src/lm/lm_mpuinit.h | 90 ++++++++++ nuttx/arch/arm/src/lm/lm_start.c | 14 +- nuttx/arch/arm/src/lm/lm_userspace.c | 119 ++++++++++++++ nuttx/arch/arm/src/lm/lm_userspace.h | 76 +++++++++ nuttx/arch/arm/src/lm/lm_vectors.S | 114 +++++++++++-- nuttx/arch/arm/src/lpc17xx/lpc17_userspace.h | 2 +- nuttx/arch/arm/src/lpc43xx/Make.defs | 12 ++ nuttx/arch/arm/src/lpc43xx/lpc43_allocateheap.c | 4 + nuttx/arch/arm/src/lpc43xx/lpc43_mpuinit.c | 124 ++++++++++++++ nuttx/arch/arm/src/lpc43xx/lpc43_mpuinit.h | 90 ++++++++++ nuttx/arch/arm/src/lpc43xx/lpc43_start.c | 14 +- nuttx/arch/arm/src/lpc43xx/lpc43_userspace.c | 119 ++++++++++++++ nuttx/arch/arm/src/lpc43xx/lpc43_userspace.h | 76 +++++++++ nuttx/arch/arm/src/nuc1xx/Make.defs | 12 ++ nuttx/arch/arm/src/nuc1xx/nuc_start.c | 14 +- nuttx/arch/arm/src/nuc1xx/nuc_userspace.c | 114 +++++++++++++ nuttx/arch/arm/src/nuc1xx/nuc_userspace.h | 76 +++++++++ nuttx/arch/arm/src/stm32/stm32_allocateheap.c | 3 + nuttx/arch/arm/src/stm32/stm32_userspace.h | 2 +- nuttx/arch/arm/src/stm32/stm32_vectors.S | 5 +- 33 files changed, 2226 insertions(+), 84 deletions(-) create mode 100644 nuttx/arch/arm/src/kinetis/kinetis_allocateheap.c create mode 100644 nuttx/arch/arm/src/kinetis/kinetis_mpuinit.c create mode 100644 nuttx/arch/arm/src/kinetis/kinetis_mpuinit.h create mode 100644 nuttx/arch/arm/src/kinetis/kinetis_userspace.c create mode 100644 nuttx/arch/arm/src/kinetis/kinetis_userspace.h create mode 100644 nuttx/arch/arm/src/lm/lm_allocateheap.c create mode 100644 nuttx/arch/arm/src/lm/lm_mpuinit.c create mode 100644 nuttx/arch/arm/src/lm/lm_mpuinit.h create mode 100644 nuttx/arch/arm/src/lm/lm_userspace.c create mode 100644 nuttx/arch/arm/src/lm/lm_userspace.h create mode 100644 nuttx/arch/arm/src/lpc43xx/lpc43_mpuinit.c create mode 100644 nuttx/arch/arm/src/lpc43xx/lpc43_mpuinit.h create mode 100644 nuttx/arch/arm/src/lpc43xx/lpc43_userspace.c create mode 100644 nuttx/arch/arm/src/lpc43xx/lpc43_userspace.h create mode 100644 nuttx/arch/arm/src/nuc1xx/nuc_userspace.c create mode 100644 nuttx/arch/arm/src/nuc1xx/nuc_userspace.h (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/common/up_allocateheap.c b/nuttx/arch/arm/src/common/up_allocateheap.c index 617bffd2e..ec61436e3 100644 --- a/nuttx/arch/arm/src/common/up_allocateheap.c +++ b/nuttx/arch/arm/src/common/up_allocateheap.c @@ -40,9 +40,13 @@ #include #include +#include +#include #include #include +#include + #include #include "up_arch.h" @@ -75,13 +79,88 @@ * size of the unprotected, user-space heap. * * If a protected kernel-space heap is provided, the kernel heap must be - * allocated (and protected) by an analogous up_allocate_kheap(). + * allocated by an analogous up_allocate_kheap(). A custom version of this + * file is needed if memory protection of the kernel heap is required. + * + * 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 = CONFIG_DRAM_END - ubase; + int log2; + + DEBUGASSERT(ubase < (uintptr_t)CONFIG_DRAM_END); + + /* Return the user-space heap settings */ + + up_ledon(LED_HEAPALLOCATE); + *heap_start = (FAR void*)ubase; + *heap_size = usize; +#else + + /* Return the heap settings */ + up_ledon(LED_HEAPALLOCATE); *heap_start = (FAR void*)g_idle_topstack; - *heap_size = CONFIG_DRAM_END - g_idle_topstack; + *heap_size = CONFIG_DRAM_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 + * the kernel-space heap. A custom version of this function is need if + * memory protection of the kernel heap is required. + * + ****************************************************************************/ + +#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 = CONFIG_DRAM_END - ubase; + int log2; + + DEBUGASSERT(ubase < (uintptr_t)CONFIG_DRAM_END); + + /* 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 diff --git a/nuttx/arch/arm/src/kinetis/Make.defs b/nuttx/arch/arm/src/kinetis/Make.defs index 1bfb8803e..1583b3cc2 100644 --- a/nuttx/arch/arm/src/kinetis/Make.defs +++ b/nuttx/arch/arm/src/kinetis/Make.defs @@ -35,32 +35,40 @@ # The start-up, "head", file -HEAD_ASRC = kinetis_vectors.S +HEAD_ASRC = kinetis_vectors.S # Common ARM and Cortex-M3 files -CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S \ - vfork.S -CMN_CSRCS = up_allocateheap.c 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_memfault.c up_initialstate.c up_interruptcontext.c \ - up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \ - up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \ - up_releasepending.c up_sigdeliver.c up_unblocktask.c up_usestack.c \ - up_doirq.c up_hardfault.c up_svcall.c up_checkstack.c \ - up_vfork.c +CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S +CMN_ASRCS += vfork.S + +CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c +CMN_CSRCS += up_mdelay.c up_udelay.c up_exit.c up_initialize.c up_memfault.c +CMN_CSRCS += up_initialstate.c up_interruptcontext.c up_modifyreg8.c +CMN_CSRCS += up_modifyreg16.c up_modifyreg32.c up_releasestack.c +CMN_CSRCS += up_reprioritizertr.c up_schedulesigaction.c up_releasepending.c +CMN_CSRCS += up_sigdeliver.c up_unblocktask.c up_usestack.c up_doirq.c +CMN_CSRCS += up_hardfault.c up_svcall.c up_checkstack.c up_vfork.c ifeq ($(CONFIG_ARCH_RAMVECTORS),y) CMN_CSRCS += up_ramvec_initialize.c up_ramvec_attach.c endif ifeq ($(CONFIG_ARCH_MEMCPY),y) -CMN_ASRCS += up_memcpy.S +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_dispatch.c +CMN_UASRCS += up_signal_handler.S +endif endif ifeq ($(CONFIG_NET),y) ifneq ($(CONFIG_KINETIS_ENET),y) -CMN_CSRCS += up_etherstub.c +CMN_CSRCS += up_etherstub.c endif endif @@ -70,39 +78,46 @@ endif # Required Kinetis files -CHIP_ASRCS = -CHIP_CSRCS = kinetis_clockconfig.c kinetis_clrpend.c kinetis_idle.c \ - kinetis_irq.c kinetis_lowputc.c kinetis_pin.c kinetis_pingpio.c \ - kinetis_serial.c kinetis_start.c kinetis_timerisr.c kinetis_wdog.c +CHIP_ASRCS = + +CHIP_CSRCS = kinetis_allocateheap.c kinetis_clockconfig.c +CHIP_CSRCS += kinetis_clrpend.c kinetis_idle.c kinetis_irq.c +CHIP_CSRCS += kinetis_lowputc.c kinetis_pin.c kinetis_pingpio.c +CHIP_CSRCS += kinetis_serial.c kinetis_start.c kinetis_timerisr.c +CHIP_CSRCS += kinetis_wdog.c # Configuration-dependent Kinetis files +ifeq ($(CONFIG_NUTTX_KERNEL),y) +CHIP_CSRCS += kinetis_userspace.c kinetis_mpuinit.c +endif + ifeq ($(CONFIG_GPIO_IRQ),y) -CHIP_CSRCS += kinetis_pinirq.c +CHIP_CSRCS += kinetis_pinirq.c endif ifeq ($(CONFIG_DEBUG_GPIO),y) -CHIP_CSRCS += kinetis_pindbg.c +CHIP_CSRCS += kinetis_pindbg.c endif ifeq ($(CONFIG_KINETIS_SDHC),y) -CHIP_CSRCS += kinetis_sdhc.c +CHIP_CSRCS += kinetis_sdhc.c endif ifeq ($(CONFIG_USBDEV),y) -CHIP_CSRCS += kinetis_usbdev.c +CHIP_CSRCS += kinetis_usbdev.c endif ifeq ($(CONFIG_USBHOST),y) -CHIP_CSRCS += kinetis_usbhost.c +CHIP_CSRCS += kinetis_usbhost.c endif ifeq ($(CONFIG_KINETIS_DMA),y) -CHIP_CSRCS += kinetis_dma.c kinetis_pindma.c +CHIP_CSRCS += kinetis_dma.c kinetis_pindma.c endif ifeq ($(CONFIG_NET),y) ifeq ($(CONFIG_KINETIS_ENET),y) -CHIP_CSRCS += kinetis_enet.c +CHIP_CSRCS += kinetis_enet.c endif endif diff --git a/nuttx/arch/arm/src/kinetis/kinetis_allocateheap.c b/nuttx/arch/arm/src/kinetis/kinetis_allocateheap.c new file mode 100644 index 000000000..8984217c7 --- /dev/null +++ b/nuttx/arch/arm/src/kinetis/kinetis_allocateheap.c @@ -0,0 +1,192 @@ +/**************************************************************************** + * arch/arm/src/kinetis/kinetis_allocateheap.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include + +#include +#include + +#include + +#include "mpu.h" +#include "up_arch.h" +#include "up_internal.h" +#include "kinetis_mpuinit.h" + +/**************************************************************************** + * Private Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_allocate_heap + * + * Description: + * This function will be called to dynamically set aside the heap region. + * + * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and + * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the + * size of the unprotected, user-space heap. + * + * 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 = CONFIG_DRAM_END - ubase; + int log2; + + DEBUGASSERT(ubase < (uintptr_t)CONFIG_DRAM_END); + + /* Adjust that size to account for MPU alignment requirements. + * NOTE that there is an implicit assumption that the CONFIG_DRAM_END + * is aligned to the MPU requirement. + */ + + log2 = (int)mpu_log2regionfloor(usize); + DEBUGASSERT((CONFIG_DRAM_END & ((1 << log2) - 1)) == 0); + + usize = (1 << log2); + ubase = CONFIG_DRAM_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 */ + + kinetis_mpu_uheap((uintptr_t)ubase, usize); +#else + + /* Return the heap settings */ + + up_ledon(LED_HEAPALLOCATE); + *heap_start = (FAR void*)g_idle_topstack; + *heap_size = CONFIG_DRAM_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 = CONFIG_DRAM_END - ubase; + int log2; + + DEBUGASSERT(ubase < (uintptr_t)CONFIG_DRAM_END); + + /* Adjust that size to account for MPU alignment requirements. + * NOTE that there is an implicit assumption that the CONFIG_DRAM_END + * is aligned to the MPU requirement. + */ + + log2 = (int)mpu_log2regionfloor(usize); + DEBUGASSERT((CONFIG_DRAM_END & ((1 << log2) - 1)) == 0); + + usize = (1 << log2); + ubase = CONFIG_DRAM_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 diff --git a/nuttx/arch/arm/src/kinetis/kinetis_mpuinit.c b/nuttx/arch/arm/src/kinetis/kinetis_mpuinit.c new file mode 100644 index 000000000..bd81374ff --- /dev/null +++ b/nuttx/arch/arm/src/kinetis/kinetis_mpuinit.c @@ -0,0 +1,124 @@ +/**************************************************************************** + * arch/arm/src/kinetis/kinetis_mpuinit.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include + +#include + +#include "mpu.h" +#include "kinetis_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: kinetis_mpuinitialize + * + * Description: + * Configure the MPU to permit user-space access to only restricted SAM3U + * resources. + * + ****************************************************************************/ + +void kinetis_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: kinetis_mpu_uheap + * + * Description: + * Map the user-heap region. + * + * This logic may need an extension to handle external SDRAM). + * + ****************************************************************************/ + +void kinetis_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/kinetis/kinetis_mpuinit.h b/nuttx/arch/arm/src/kinetis/kinetis_mpuinit.h new file mode 100644 index 000000000..1e88b67a2 --- /dev/null +++ b/nuttx/arch/arm/src/kinetis/kinetis_mpuinit.h @@ -0,0 +1,90 @@ +/************************************************************************************ + * arch/arm/src/kinetis/kinetis_mpuinit.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_KINETIS_KINETIS_MPUINIT_H +#define __ARCH_ARM_SRC_KINETIS_KINETIS_MPUINIT_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: kinetis_mpuinitialize + * + * Description: + * Configure the MPU to permit user-space access to only unrestricted MCU + * resources. + * + ****************************************************************************/ + +#ifdef CONFIG_NUTTX_KERNEL +void kinetis_mpuinitialize(void); +#else +# define kinetis_mpuinitialize() +#endif + +/**************************************************************************** + * Name: kinetis_mpu_uheap + * + * Description: + * Map the user heap region. + * + ****************************************************************************/ + +#ifdef CONFIG_NUTTX_KERNEL +void kinetis_mpu_uheap(uintptr_t start, size_t size); +#else +# define kinetis_mpu_uheap(start,size) +#endif + +#endif /* __ARCH_ARM_SRC_KINETIS_KINETIS_MPUINIT_H */ diff --git a/nuttx/arch/arm/src/kinetis/kinetis_start.c b/nuttx/arch/arm/src/kinetis/kinetis_start.c index 2f73cb2e6..9748f1fc3 100644 --- a/nuttx/arch/arm/src/kinetis/kinetis_start.c +++ b/nuttx/arch/arm/src/kinetis/kinetis_start.c @@ -52,6 +52,7 @@ #include "kinetis_internal.h" #include "kinetis_smc.h" +#include "kinetis_userspace.h" /**************************************************************************** * Private Definitions @@ -139,6 +140,16 @@ void __start(void) up_earlyserialinit(); #endif + /* 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 + kinetis_userspace(); +#endif + /* Initialize other on-board resources */ kinetis_boardinitialize(); diff --git a/nuttx/arch/arm/src/kinetis/kinetis_userspace.c b/nuttx/arch/arm/src/kinetis/kinetis_userspace.c new file mode 100644 index 000000000..75b3c08fd --- /dev/null +++ b/nuttx/arch/arm/src/kinetis/kinetis_userspace.c @@ -0,0 +1,119 @@ +/**************************************************************************** + * arch/arm/src/kinetis/kinetis_userspace.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include + +#include "kinetis_mpuinit.h" +#include "kinetis_userspace.h" + +#ifdef CONFIG_NUTTX_KERNEL + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: kinetis_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 kinetis_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 */ + + kinetis_mpuinitialize(); +} + +#endif /* CONFIG_NUTTX_KERNEL */ + diff --git a/nuttx/arch/arm/src/kinetis/kinetis_userspace.h b/nuttx/arch/arm/src/kinetis/kinetis_userspace.h new file mode 100644 index 000000000..ecad3b609 --- /dev/null +++ b/nuttx/arch/arm/src/kinetis/kinetis_userspace.h @@ -0,0 +1,76 @@ +/************************************************************************************ + * arch/arm/src/kinetis/kinetis_userspace.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_KINETIS_KINETIS_USERSPACE_H +#define __ARCH_ARM_SRC_KINETIS_KINETIS_USERSPACE_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: kinetis_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 kinetis_userspace(void); +#endif + +#endif /* __ARCH_ARM_SRC_KINETIS_KINETIS_USERSPACE_H */ diff --git a/nuttx/arch/arm/src/kinetis/kinetis_vectors.S b/nuttx/arch/arm/src/kinetis/kinetis_vectors.S index 055841d5a..220c64053 100644 --- a/nuttx/arch/arm/src/kinetis/kinetis_vectors.S +++ b/nuttx/arch/arm/src/kinetis/kinetis_vectors.S @@ -2,7 +2,7 @@ * arch/arm/src/kinetis/kinetis_vectors.S * arch/arm/src/chip/kinetis_vectors.S * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -39,6 +39,7 @@ ************************************************************************************************/ #include + #include #include "exc_return.h" @@ -58,19 +59,23 @@ * - Heap ends at the configured end of SRAM. */ -#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE) +#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4) #define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE) /************************************************************************************************ * Global Symbols ************************************************************************************************/ - .globl __start - .syntax unified .thumb .file "kinetis_vectors.S" +/* Check if common ARMv7 interrupt vectoring is used (see arch/arm/src/armv7-m/up_vectors.S) */ + +#ifndef CONFIG_ARMV7M_CMNVECTOR + + .globl __start + /************************************************************************************************ * Macros ************************************************************************************************/ @@ -586,18 +591,23 @@ kinetis_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) */ adds r2, r14, #3 /* If R14=0xfffffffd, then r2 == 0 */ - ite ne /* Next two instructions are condition */ + ite ne /* Next two instructions are conditional */ mrsne r1, msp /* R1=The main stack pointer */ mrseq r1, psp /* R1=The process stack pointer */ #else mrs r1, msp /* R1=The main stack pointer */ #endif + /* r1 holds the value of the stack pointer AFTER the excption handling logic + * pushed the various registers onto the stack. Get r2 = the value of the + * stack pointer BEFORE the interrupt modified it. + */ + mov r2, r1 /* R2=Copy of the main/process stack pointer */ add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */ #ifdef CONFIG_ARMV7M_USEBASEPRI @@ -605,7 +615,23 @@ kinetis_common: #else mrs r3, primask /* R3=Current PRIMASK setting */ #endif -#ifdef CONFIG_NUTTX_KERNEL + +#ifdef CONFIG_ARCH_FPU + /* Skip over the block of memory reserved for floating pointer register save. + * Lazy FPU register saving is used. FPU registers will be saved in this + * block only if a context switch occurs (this means, of course, that the FPU + * cannot be used in interrupt processing). + */ + + sub r1, #(4*SW_FPU_REGS) +#endif + + /* Save the the remaining registers on the stack after the registers pushed + * by the exception handling logic. r2=SP and r3=primask or basepri, r4-r11, + * r14=register values. + */ + +#ifdef CONFIG_NUTTX_KERNEL stmdb r1!, {r2-r11,r14} /* Save the remaining registers plus the SP value */ #else stmdb r1!, {r2-r11} /* Save the remaining registers plus the SP value */ @@ -641,9 +667,28 @@ kinetis_common: cmp r0, r1 /* Context switch? */ beq 1f /* Branch if no context switch */ + /* We are returning with a pending context switch. + * + * If the FPU is enabled, then we will need to restore FPU registers. + * This is not done in normal interrupt save/restore because the cost + * is prohibitive. This is only done when switching contexts. A + * consequence of this is that floating point operations may not be + * performed in interrupt handling logic. + * + * Here: + * r0 = Address of the register save area + + * NOTE: It is a requirement that up_restorefpu() preserve the value of + * r0! + */ + +#ifdef CONFIG_ARCH_FPU + bl up_restorefpu /* Restore the FPU registers */ +#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. */ @@ -651,7 +696,7 @@ kinetis_common: ldmia r1, {r4-r11} /* Fetch eight registers in HW save area */ ldr r1, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */ stmdb r1!, {r4-r11} /* Store eight registers in HW save area */ -#ifdef CONFIG_NUTTX_KERNEL +#ifdef CONFIG_NUTTX_KERNEL ldmia r0, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */ #else ldmia r0, {r2-r11} /* Recover R4-R11 + 2 temp values */ @@ -660,24 +705,53 @@ kinetis_common: /* We are returning with no context switch. We simply need to "unwind" * the same stack frame that we created + * + * Here: + * r1 = Address of the return stack (same as r0) */ 1: -#ifdef CONFIG_NUTTX_KERNEL +#ifdef CONFIG_NUTTX_KERNEL ldmia r1!, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */ #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 + */ + + add r1, #(4*SW_FPU_REGS) +#endif + + /* Set up to return from the exception + * + * Here: + * r1 = Address on the target thread's stack position at the start of + * the registers saved by hardware + * r3 = primask or basepri + * 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 */ @@ -721,6 +795,7 @@ up_interruptstack: g_intstackbase: .size up_interruptstack, .-up_interruptstack #endif +#endif /* CONFIG_ARMV7M_CMNVECTOR */ /************************************************************************************************ * .rodata diff --git a/nuttx/arch/arm/src/lm/Make.defs b/nuttx/arch/arm/src/lm/Make.defs index cb367e879..8884554d9 100644 --- a/nuttx/arch/arm/src/lm/Make.defs +++ b/nuttx/arch/arm/src/lm/Make.defs @@ -33,35 +33,50 @@ # ############################################################################ -HEAD_ASRC = lm_vectors.S +HEAD_ASRC = lm_vectors.S -CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S \ - vfork.S -CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ - up_createstack.c up_mdelay.c up_udelay.c up_exit.c \ - up_idle.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_unblocktask.c \ - up_usestack.c up_doirq.c up_hardfault.c up_svcall.c \ - up_vfork.c +CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S +CMN_ASRCS += vfork.S + +CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c +CMN_CSRCS += up_mdelay.c up_udelay.c up_exit.c up_idle.c up_initialize.c +CMN_CSRCS += up_initialstate.c up_interruptcontext.c up_memfault.c +CMN_CSRCS += up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c +CMN_CSRCS += up_releasepending.c up_releasestack.c up_reprioritizertr.c +CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c +CMN_CSRCS += up_usestack.c up_doirq.c up_hardfault.c up_svcall.c up_vfork.c ifeq ($(CONFIG_ARCH_RAMVECTORS),y) CMN_CSRCS += up_ramvec_initialize.c up_ramvec_attach.c endif ifeq ($(CONFIG_ARCH_MEMCPY),y) -CMN_ASRCS += up_memcpy.S +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_dispatch.c +CMN_UASRCS += up_signal_handler.S +endif +else +CMN_CSRCS += up_allocateheap.c endif ifeq ($(CONFIG_ELF),y) CMN_CSRCS += up_elf.c endif -CHIP_ASRCS = -CHIP_CSRCS = lm_start.c lm_syscontrol.c lm_irq.c lm_gpio.c lm_gpioirq.c \ - lm_timerisr.c lm_lowputc.c lm_serial.c lm_ssi.c lm_dumpgpio.c +CHIP_ASRCS = +CHIP_CSRCS = lm_allocateheap.c lm_start.c lm_syscontrol.c lm_irq.c +CHIP_CSRCS += lm_gpio.c lm_gpioirq.c lm_timerisr.c lm_lowputc.c lm_serial.c +CHIP_CSRCS += lm_ssi.c lm_dumpgpio.c + +ifeq ($(CONFIG_NUTTX_KERNEL),y) +CHIP_CSRCS += lm_userspace.c lm_mpuinit.c +endif ifdef CONFIG_NET -CHIP_CSRCS += lm_ethernet.c +CHIP_CSRCS += lm_ethernet.c endif diff --git a/nuttx/arch/arm/src/lm/chip/lm4f_pinmap.h b/nuttx/arch/arm/src/lm/chip/lm4f_pinmap.h index 567ca4c1c..771eb9d2c 100644 --- a/nuttx/arch/arm/src/lm/chip/lm4f_pinmap.h +++ b/nuttx/arch/arm/src/lm/chip/lm4f_pinmap.h @@ -162,7 +162,7 @@ # define GPIO_UART1_CTS_1 (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTF | GPIO_PIN_1) # define GPIO_UART1_CTS_2 (GPIO_FUNC_PFINPUT | GPIO_ALT_8 | GPIO_PORTC | GPIO_PIN_5) # define GPIO_UART1_RTS_1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTF | GPIO_PIN_0) -# define GPIO_UART1_RTS_1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_8 | GPIO_PORTC | GPIO_PIN_4) +# define GPIO_UART1_RTS_2 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_8 | GPIO_PORTC | GPIO_PIN_4) # define GPIO_UART1_RX_1 (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTB | GPIO_PIN_0) # define GPIO_UART1_RX_2 (GPIO_FUNC_PFINPUT | GPIO_ALT_2 | GPIO_PORTC | GPIO_PIN_4) # define GPIO_UART1_TX_1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTB | GPIO_PIN_1) diff --git a/nuttx/arch/arm/src/lm/lm_allocateheap.c b/nuttx/arch/arm/src/lm/lm_allocateheap.c new file mode 100644 index 000000000..1ac064f0f --- /dev/null +++ b/nuttx/arch/arm/src/lm/lm_allocateheap.c @@ -0,0 +1,192 @@ +/**************************************************************************** + * arch/arm/src/lm/lm_allocateheap.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include + +#include +#include + +#include + +#include "mpu.h" +#include "up_arch.h" +#include "up_internal.h" +#include "lm_mpuinit.h" + +/**************************************************************************** + * Private Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_allocate_heap + * + * Description: + * This function will be called to dynamically set aside the heap region. + * + * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and + * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the + * size of the unprotected, user-space heap. + * + * 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 = CONFIG_DRAM_END - ubase; + int log2; + + DEBUGASSERT(ubase < (uintptr_t)CONFIG_DRAM_END); + + /* Adjust that size to account for MPU alignment requirements. + * NOTE that there is an implicit assumption that the CONFIG_DRAM_END + * is aligned to the MPU requirement. + */ + + log2 = (int)mpu_log2regionfloor(usize); + DEBUGASSERT((CONFIG_DRAM_END & ((1 << log2) - 1)) == 0); + + usize = (1 << log2); + ubase = CONFIG_DRAM_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 */ + + lm_mpu_uheap((uintptr_t)ubase, usize); +#else + + /* Return the heap settings */ + + up_ledon(LED_HEAPALLOCATE); + *heap_start = (FAR void*)g_idle_topstack; + *heap_size = CONFIG_DRAM_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 = CONFIG_DRAM_END - ubase; + int log2; + + DEBUGASSERT(ubase < (uintptr_t)CONFIG_DRAM_END); + + /* Adjust that size to account for MPU alignment requirements. + * NOTE that there is an implicit assumption that the CONFIG_DRAM_END + * is aligned to the MPU requirement. + */ + + log2 = (int)mpu_log2regionfloor(usize); + DEBUGASSERT((CONFIG_DRAM_END & ((1 << log2) - 1)) == 0); + + usize = (1 << log2); + ubase = CONFIG_DRAM_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 diff --git a/nuttx/arch/arm/src/lm/lm_mpuinit.c b/nuttx/arch/arm/src/lm/lm_mpuinit.c new file mode 100644 index 000000000..db06de1c1 --- /dev/null +++ b/nuttx/arch/arm/src/lm/lm_mpuinit.c @@ -0,0 +1,124 @@ +/**************************************************************************** + * arch/arm/src/lm/lm_mpuinit.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include + +#include + +#include "mpu.h" +#include "lm_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: lm_mpuinitialize + * + * Description: + * Configure the MPU to permit user-space access to only restricted SAM3U + * resources. + * + ****************************************************************************/ + +void lm_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: lm_mpu_uheap + * + * Description: + * Map the user-heap region. + * + * This logic may need an extension to handle external SDRAM). + * + ****************************************************************************/ + +void lm_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/lm/lm_mpuinit.h b/nuttx/arch/arm/src/lm/lm_mpuinit.h new file mode 100644 index 000000000..3c9a06c21 --- /dev/null +++ b/nuttx/arch/arm/src/lm/lm_mpuinit.h @@ -0,0 +1,90 @@ +/************************************************************************************ + * arch/arm/src/lm/lm_mpuinit.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LM_LM_MPUINIT_H +#define __ARCH_ARM_SRC_LM_LM_MPUINIT_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: lm_mpuinitialize + * + * Description: + * Configure the MPU to permit user-space access to only unrestricted MCU + * resources. + * + ****************************************************************************/ + +#ifdef CONFIG_NUTTX_KERNEL +void lm_mpuinitialize(void); +#else +# define lm_mpuinitialize() +#endif + +/**************************************************************************** + * Name: lm_mpu_uheap + * + * Description: + * Map the user heap region. + * + ****************************************************************************/ + +#ifdef CONFIG_NUTTX_KERNEL +void lm_mpu_uheap(uintptr_t start, size_t size); +#else +# define lm_mpu_uheap(start,size) +#endif + +#endif /* __ARCH_ARM_SRC_LM_LM_MPUINIT_H */ diff --git a/nuttx/arch/arm/src/lm/lm_start.c b/nuttx/arch/arm/src/lm/lm_start.c index f4985709e..5ab07684c 100644 --- a/nuttx/arch/arm/src/lm/lm_start.c +++ b/nuttx/arch/arm/src/lm/lm_start.c @@ -52,6 +52,7 @@ #include "lm_lowputc.h" #include "lm_syscontrol.h" +#include "lm_userspace.h" /**************************************************************************** * Pre-processor Definitions @@ -137,10 +138,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 + lm_userspace(); + showprogress('E'); +#endif + /* Initialize onboard resources */ lm_boardinitialize(); - showprogress('E'); + showprogress('F'); /* Then start NuttX */ diff --git a/nuttx/arch/arm/src/lm/lm_userspace.c b/nuttx/arch/arm/src/lm/lm_userspace.c new file mode 100644 index 000000000..f198f5c2f --- /dev/null +++ b/nuttx/arch/arm/src/lm/lm_userspace.c @@ -0,0 +1,119 @@ +/**************************************************************************** + * arch/arm/src/lm/lm_userspace.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include + +#include "lm_mpuinit.h" +#include "lm_userspace.h" + +#ifdef CONFIG_NUTTX_KERNEL + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lm_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 lm_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 */ + + lm_mpuinitialize(); +} + +#endif /* CONFIG_NUTTX_KERNEL */ + diff --git a/nuttx/arch/arm/src/lm/lm_userspace.h b/nuttx/arch/arm/src/lm/lm_userspace.h new file mode 100644 index 000000000..37c0aff31 --- /dev/null +++ b/nuttx/arch/arm/src/lm/lm_userspace.h @@ -0,0 +1,76 @@ +/************************************************************************************ + * arch/arm/src/lm/lm_userspace.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LM_LM_USERSPACE_H +#define __ARCH_ARM_SRC_LM_LM_USERSPACE_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: lm_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 lm_userspace(void); +#endif + +#endif /* __ARCH_ARM_SRC_LM_LM_USERSPACE_H */ diff --git a/nuttx/arch/arm/src/lm/lm_vectors.S b/nuttx/arch/arm/src/lm/lm_vectors.S index 4459d49a7..0f5a8e555 100644 --- a/nuttx/arch/arm/src/lm/lm_vectors.S +++ b/nuttx/arch/arm/src/lm/lm_vectors.S @@ -39,8 +39,16 @@ ************************************************************************************/ #include + #include +#include "chip.h" +#include "exc_return.h" + +/************************************************************************************ + * Configuration + ************************************************************************************/ + /************************************************************************************ * Preprocessor Definitions ************************************************************************************/ @@ -58,18 +66,22 @@ */ #define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4) -#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4) +#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE) /************************************************************************************ * Global Symbols ************************************************************************************/ - .globl __start - .syntax unified .thumb .file "lm_vectors.S" +/* Check if common ARMv7 interrupt vectoring is used (see arch/arm/src/armv7-m/up_vectors.S) */ + +#ifndef CONFIG_ARMV7M_CMNVECTOR + + .globl __start + /************************************************************************************ * Macros ************************************************************************************/ @@ -182,18 +194,23 @@ lm_irqcommon: #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 r2, r14, #3 /* If R14=0xfffffffd, then r2 == 0 */ - ite ne /* Next two instructions are condition */ + ite ne /* Next two instructions are conditional */ mrsne r1, msp /* R1=The main stack pointer */ mrseq r1, psp /* R1=The process stack pointer */ #else mrs r1, msp /* R1=The main stack pointer */ #endif + /* r1 holds the value of the stack pointer AFTER the excption handling logic + * pushed the various registers onto the stack. Get r2 = the value of the + * stack pointer BEFORE the interrupt modified it. + */ + mov r2, r1 /* R2=Copy of the main/process stack pointer */ add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */ #ifdef CONFIG_ARMV7M_USEBASEPRI @@ -201,7 +218,23 @@ lm_irqcommon: #else mrs r3, primask /* R3=Current PRIMASK setting */ #endif -#ifdef CONFIG_NUTTX_KERNEL + +#ifdef CONFIG_ARCH_FPU + /* Skip over the block of memory reserved for floating pointer register save. + * Lazy FPU register saving is used. FPU registers will be saved in this + * block only if a context switch occurs (this means, of course, that the FPU + * cannot be used in interrupt processing). + */ + + sub r1, #(4*SW_FPU_REGS) +#endif + + /* Save the the remaining registers on the stack after the registers pushed + * by the exception handling logic. r2=SP and r3=primask or basepri, r4-r11, + * r14=register values. + */ + +#ifdef CONFIG_NUTTX_KERNEL stmdb r1!, {r2-r11,r14} /* Save the remaining registers plus the SP value */ #else stmdb r1!, {r2-r11} /* Save the remaining registers plus the SP value */ @@ -237,9 +270,28 @@ lm_irqcommon: cmp r0, r1 /* Context switch? */ beq 1f /* Branch if no context switch */ + /* We are returning with a pending context switch. + * + * If the FPU is enabled, then we will need to restore FPU registers. + * This is not done in normal interrupt save/restore because the cost + * is prohibitive. This is only done when switching contexts. A + * consequence of this is that floating point operations may not be + * performed in interrupt handling logic. + * + * Here: + * r0 = Address of the register save area + + * NOTE: It is a requirement that up_restorefpu() preserve the value of + * r0! + */ + +#ifdef CONFIG_ARCH_FPU + bl up_restorefpu /* Restore the FPU registers */ +#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. */ @@ -247,7 +299,7 @@ lm_irqcommon: ldmia r1, {r4-r11} /* Fetch eight registers in HW save area */ ldr r1, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */ stmdb r1!, {r4-r11} /* Store eight registers in HW save area */ -#ifdef CONFIG_NUTTX_KERNEL +#ifdef CONFIG_NUTTX_KERNEL ldmia r0, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */ #else ldmia r0, {r2-r11} /* Recover R4-R11 + 2 temp values */ @@ -256,24 +308,53 @@ lm_irqcommon: /* We are returning with no context switch. We simply need to "unwind" * the same stack frame that we created + * + * Here: + * r1 = Address of the return stack (same as r0) */ 1: -#ifdef CONFIG_NUTTX_KERNEL +#ifdef CONFIG_NUTTX_KERNEL ldmia r1!, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */ #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 + */ + + add r1, #(4*SW_FPU_REGS) +#endif + + /* Set up to return from the exception + * + * Here: + * r1 = Address on the target thread's stack position at the start of + * the registers saved by hardware + * r3 = primask or basepri + * 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 */ @@ -317,6 +398,7 @@ up_interruptstack: g_intstackbase: .size up_interruptstack, .-up_interruptstack #endif +#endif /* CONFIG_ARMV7M_CMNVECTOR */ /************************************************************************************ * .rodata @@ -335,7 +417,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 diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_userspace.h b/nuttx/arch/arm/src/lpc17xx/lpc17_userspace.h index 7f9c75dd4..880e52eda 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_userspace.h +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_userspace.h @@ -1,5 +1,5 @@ /************************************************************************************ - * arch/arm/src/lpc17xx/lpc17_qei.h + * arch/arm/src/lpc17xx/lpc17_userspace.h * * Copyright (C) 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/nuttx/arch/arm/src/lpc43xx/Make.defs b/nuttx/arch/arm/src/lpc43xx/Make.defs index 0354b698b..e3fe984b3 100644 --- a/nuttx/arch/arm/src/lpc43xx/Make.defs +++ b/nuttx/arch/arm/src/lpc43xx/Make.defs @@ -59,6 +59,14 @@ 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_dispatch.c +CMN_UASRCS += up_signal_handler.S +endif +endif + ifeq ($(CONFIG_DEBUG_STACK),y) CMN_CSRCS += up_checkstack.c endif @@ -76,6 +84,10 @@ CHIP_CSRCS = lpc43_allocateheap.c lpc43_cgu.c lpc43_clrpend.c lpc43_gpio.c CHIP_CSRCS += lpc43_irq.c lpc43_pinconfig.c lpc43_rgu.c lpc43_serial.c CHIP_CSRCS += lpc43_start.c lpc43_timerisr.c lpc43_uart.c +ifeq ($(CONFIG_NUTTX_KERNEL),y) +CHIP_CSRCS += lpc43_userspace.c lpc43_mpuinit.c +endif + ifneq ($(CONFIG_IDLE_CUSTOM),y) CHIP_CSRCS += lpc43_idle.c endif diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_allocateheap.c b/nuttx/arch/arm/src/lpc43xx/lpc43_allocateheap.c index 4d9d7b21c..7304bc04c 100644 --- a/nuttx/arch/arm/src/lpc43xx/lpc43_allocateheap.c +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_allocateheap.c @@ -40,10 +40,14 @@ #include #include +#include +#include #include #include #include +#include + #include #include "chip.h" diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_mpuinit.c b/nuttx/arch/arm/src/lpc43xx/lpc43_mpuinit.c new file mode 100644 index 000000000..02e8fb04e --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_mpuinit.c @@ -0,0 +1,124 @@ +/**************************************************************************** + * arch/arm/src/lpc43xx/lpc43_mpuinit.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include + +#include + +#include "mpu.h" +#include "lpc43_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: lpc43_mpuinitialize + * + * Description: + * Configure the MPU to permit user-space access to only restricted SAM3U + * resources. + * + ****************************************************************************/ + +void lpc43_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: lpc43_mpu_uheap + * + * Description: + * Map the user-heap region. + * + * This logic may need an extension to handle external SDRAM). + * + ****************************************************************************/ + +void lpc43_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/lpc43xx/lpc43_mpuinit.h b/nuttx/arch/arm/src/lpc43xx/lpc43_mpuinit.h new file mode 100644 index 000000000..1759e0dcd --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_mpuinit.h @@ -0,0 +1,90 @@ +/************************************************************************************ + * arch/arm/src/lpc43xx/lpc43_mpuinit.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC43XX_LPC43_MPUINIT_H +#define __ARCH_ARM_SRC_LPC43XX_LPC43_MPUINIT_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: lpc43_mpuinitialize + * + * Description: + * Configure the MPU to permit user-space access to only unrestricted MCU + * resources. + * + ****************************************************************************/ + +#ifdef CONFIG_NUTTX_KERNEL +void lpc43_mpuinitialize(void); +#else +# define lpc43_mpuinitialize() +#endif + +/**************************************************************************** + * Name: lpc43_mpu_uheap + * + * Description: + * Map the user heap region. + * + ****************************************************************************/ + +#ifdef CONFIG_NUTTX_KERNEL +void lpc43_mpu_uheap(uintptr_t start, size_t size); +#else +# define lpc43_mpu_uheap(start,size) +#endif + +#endif /* __ARCH_ARM_SRC_LPC43XX_LPC43_MPUINIT_H */ diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_start.c b/nuttx/arch/arm/src/lpc43xx/lpc43_start.c index 88976e03d..abb1a6fa3 100644 --- a/nuttx/arch/arm/src/lpc43xx/lpc43_start.c +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_start.c @@ -74,6 +74,7 @@ #include "lpc43_cgu.h" #include "lpc43_emc.h" #include "lpc43_uart.h" +#include "lpc43_userspace.h" /**************************************************************************** * Preprocessor Definitions @@ -332,10 +333,21 @@ void __start(void) #endif showprogress('E'); + /* 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 + lpc43_userspace(); + showprogress('F'); +#endif + /* Initialize onboard resources */ lpc43_boardinitialize(); - showprogress('F'); + showprogress('G'); /* Then start NuttX */ diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_userspace.c b/nuttx/arch/arm/src/lpc43xx/lpc43_userspace.c new file mode 100644 index 000000000..c5c62f716 --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_userspace.c @@ -0,0 +1,119 @@ +/**************************************************************************** + * arch/arm/src/lpc43xx/lpc43_userspace.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include + +#include "lpc43_mpuinit.h" +#include "lpc43_userspace.h" + +#ifdef CONFIG_NUTTX_KERNEL + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc43_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 lpc43_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 */ + + lpc43_mpuinitialize(); +} + +#endif /* CONFIG_NUTTX_KERNEL */ + diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_userspace.h b/nuttx/arch/arm/src/lpc43xx/lpc43_userspace.h new file mode 100644 index 000000000..f7632388f --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_userspace.h @@ -0,0 +1,76 @@ +/************************************************************************************ + * arch/arm/src/lpc43xx/lpc43_qei.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC43XX_LPC43_USERSPACE_H +#define __ARCH_ARM_SRC_LPC43XX_LPC43_USERSPACE_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: lpc43_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 lpc43_userspace(void); +#endif + +#endif /* __ARCH_ARM_SRC_LPC43XX_LPC43_USERSPACE_H */ diff --git a/nuttx/arch/arm/src/nuc1xx/Make.defs b/nuttx/arch/arm/src/nuc1xx/Make.defs index d491a15c9..fa83d8aad 100644 --- a/nuttx/arch/arm/src/nuc1xx/Make.defs +++ b/nuttx/arch/arm/src/nuc1xx/Make.defs @@ -47,6 +47,14 @@ CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c up_systemreset.c CMN_CSRCS += up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c CMN_CSRCS += up_svcall.c up_vectors.c up_vfork.c +ifeq ($(CONFIG_NUTTX_KERNEL),y) +CMN_CSRCS += up_task_start.c up_pthread_start.c up_stackframe.c +ifneq ($(CONFIG_DISABLE_SIGNALS),y) +CMN_CSRCS += up_signal_dispatch.c +CMN_UASRCS += up_signal_handler.S +endif +endif + ifeq ($(CONFIG_DEBUG_STACK),y) CMN_CSRCS += up_checkstack.c endif @@ -63,6 +71,10 @@ CHIP_ASRCS = CHIP_CSRCS = nuc_clockconfig.c nuc_gpio.c nuc_idle.c nuc_irq.c nuc_lowputc.c CHIP_CSRCS += nuc_serial.c nuc_start.c nuc_timerisr.c +ifeq ($(CONFIG_NUTTX_KERNEL),y) +CHIP_CSRCS += nuc_userspace.c +endif + ifeq ($(CONFIG_DEBUG),y) CHIP_CSRCS += nuc_dumpgpio.c endif diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_start.c b/nuttx/arch/arm/src/nuc1xx/nuc_start.c index fa5f249a3..b21e8b86d 100644 --- a/nuttx/arch/arm/src/nuc1xx/nuc_start.c +++ b/nuttx/arch/arm/src/nuc1xx/nuc_start.c @@ -53,6 +53,7 @@ #include "nuc_config.h" #include "nuc_lowputc.h" #include "nuc_clockconfig.h" +#include "nuc_userspace.h" /**************************************************************************** * Pre-processor Definitions @@ -149,10 +150,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 + nuc_userspace(); + showprogress('E'); +#endif + /* Initialize onboard resources */ nuc_boardinitialize(); - showprogress('E'); + showprogress('F'); /* Then start NuttX */ diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_userspace.c b/nuttx/arch/arm/src/nuc1xx/nuc_userspace.c new file mode 100644 index 000000000..0a60059ba --- /dev/null +++ b/nuttx/arch/arm/src/nuc1xx/nuc_userspace.c @@ -0,0 +1,114 @@ +/**************************************************************************** + * arch/arm/src/nuc1xx/nuc_userspace.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include + +#include "nuc_userspace.h" + +#ifdef CONFIG_NUTTX_KERNEL + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nuc_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 nuc_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++; + } +} + +#endif /* CONFIG_NUTTX_KERNEL */ + diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_userspace.h b/nuttx/arch/arm/src/nuc1xx/nuc_userspace.h new file mode 100644 index 000000000..9123ce8e1 --- /dev/null +++ b/nuttx/arch/arm/src/nuc1xx/nuc_userspace.h @@ -0,0 +1,76 @@ +/************************************************************************************ + * arch/arm/src/nuc1xx/nuc_userspace.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_NUC1XX_NUC_USERSPACE_H +#define __ARCH_ARM_SRC_NUC1XX_NUC_USERSPACE_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: nuc_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 nuc_userspace(void); +#endif + +#endif /* __ARCH_ARM_SRC_NUC1XX_NUC_USERSPACE_H */ diff --git a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c index f79e6eedb..a5fa847d8 100644 --- a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c +++ b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c @@ -40,10 +40,13 @@ #include #include +#include +#include #include #include #include +#include #include diff --git a/nuttx/arch/arm/src/stm32/stm32_userspace.h b/nuttx/arch/arm/src/stm32/stm32_userspace.h index 16cd3c8e2..297ceeaa0 100644 --- a/nuttx/arch/arm/src/stm32/stm32_userspace.h +++ b/nuttx/arch/arm/src/stm32/stm32_userspace.h @@ -1,5 +1,5 @@ /************************************************************************************ - * arch/arm/src/stm32/stm32_qei.h + * arch/arm/src/stm32/stm32_userspace.h * * Copyright (C) 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/nuttx/arch/arm/src/stm32/stm32_vectors.S b/nuttx/arch/arm/src/stm32/stm32_vectors.S index b624e09c9..61a1ea83a 100644 --- a/nuttx/arch/arm/src/stm32/stm32_vectors.S +++ b/nuttx/arch/arm/src/stm32/stm32_vectors.S @@ -48,9 +48,6 @@ /************************************************************************************ * Configuration ************************************************************************************/ -/* Check if common ARMv7 interrupt vectoring is used (see - * arch/arm/src/armv7-m/up_vectors.S) - */ /************************************************************************************ * Preprocessor Definitions @@ -83,7 +80,7 @@ #ifndef CONFIG_ARMV7M_CMNVECTOR - globl __start + .globl __start /************************************************************************************ * Macros -- cgit v1.2.3