Add kernel build support to the STM32 family and to the STM32F4Discovery board

git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5774 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
patacongo 2013-03-22 14:49:21 +00:00
parent f6206367fb
commit d7c53aa6e4
21 changed files with 1365 additions and 32 deletions

View File

@ -4416,3 +4416,13 @@
is allocated from kernel memory; however, the current stack is
the user's stack and the user code will be able to access the
signinfo_t data from the stack copy (2013-03-21).
* arch/arm/src/stm32: Added support for the kernel mode build
(cloned from the lpc17xx). (2013-03-21).
* configs/stme32f4discovery/kernel and scripts: Add support for
the kernel mode build on the STM32F4Discovery (2013-03-21).
* drivers/st7567.c/h and include/nuttx/lcd/st7567.h: Driver for
the the ST7567 LCD Display Module from Univision Technology Inc.
contributed by Manikandan.S (2013-03-22).
* configs/zkit-arm-1769: Now supports the ST7567 LCD display\
module. Added an nxhello configurtion for testing (Manikandan.S,
2013-03-22).

View File

@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/common/lpc17_mpuinit.c
* arch/arm/src/lpc17xx/lpc17_mpuinit.c
*
* Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -236,7 +236,7 @@ void __start(void)
/* For the case of the separate user-/kernel-space build, perform whatever
* platform specific initialization of the user memory is required.
* Normally this just means initializing the user space .data and .bss
* segements.
* segments.
*/
#ifdef CONFIG_NUTTX_KERNEL

View File

@ -41,7 +41,6 @@
************************************************************************************/
#include <nuttx/config.h>
#include "chip/lpc17_qei.h"
/************************************************************************************
* Pre-processor Definitions

View File

@ -61,7 +61,7 @@
* 0x1000:7fff - End of CPU SRAM and end of heap (1st region)
*/
#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
/* The Cortex-M3 return from interrupt is unusual. We provide the following special
@ -306,8 +306,8 @@ lpc17_common:
#endif
/* We are returning with a pending context switch. This case is different
* because in this case, the register save structure does not lie on the
* stack but, rather, are within a TCB structure. We'll have to copy some
* because in this case, the register save structure does not lie in the
* stack but, rather, within a TCB structure. We'll have to copy some
* values to the stack.
*/

View File

@ -64,6 +64,13 @@ ifeq ($(CONFIG_ARCH_MEMCPY),y)
CMN_ASRCS += up_memcpy.S
endif
ifeq ($(CONFIG_NUTTX_KERNEL),y)
CMN_CSRCS += up_mpu.c up_task_start.c up_pthread_start.c up_stackframe.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
CMN_CSRCS += up_signal_handler.c
endif
endif
ifeq ($(CONFIG_DEBUG_STACK),y)
CMN_CSRCS += up_checkstack.c
endif
@ -87,6 +94,10 @@ ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
CHIP_ASRCS += stm32_vectors.S
endif
ifeq ($(CONFIG_NUTTX_KERNEL),y)
CHIP_CSRCS += stm32_userspace.c stm32_mpuinit.c
endif
ifeq ($(CONFIG_USBDEV),y)
ifeq ($(CONFIG_STM32_USB),y)
CHIP_CSRCS += stm32_usbdev.c

View File

@ -58,7 +58,7 @@
* following definitions must be provided to specify the size and
* location of internal(system) SRAM:
*
* CONFIG_DRAM_END : End address (+1) of SRAM (F1 family only, the
* SRAM1_END : End address (+1) of SRAM (F1 family only, the
* : F4 family uses the a priori end of SRAM)
*
* The F4 family also contains internal CCM SRAM. This SRAM is different
@ -88,7 +88,7 @@
#endif
/* For the STM312F10xxx family, all internal SRAM is in one contiguous block
* starting at g_idle_topstack and extending through CONFIG_DRAM_END (my apologies for
* starting at g_idle_topstack and extending through SRAM1_END (my apologies for
* the bad naming). In addition, external FSMC SRAM may be available.
*/
@ -96,7 +96,7 @@
/* Set the end of system SRAM */
# define SRAM1_END CONFIG_DRAM_END
# define SRAM1_END SRAM1_END
/* Check if external FSMC SRAM is provided */
@ -130,7 +130,7 @@
/* Set the end of system SRAM */
# define SRAM1_END CONFIG_DRAM_END
# define SRAM1_END SRAM1_END
/* Set the range of CCM SRAM as well (although we may not use it) */
@ -365,15 +365,114 @@
* If a protected kernel-space heap is provided, the kernel heap must be
* allocated (and protected) by an analogous up_allocate_kheap().
*
* The following memory map is assumed for the flat build:
*
* .data region. Size determined at link time.
* .bss region Size determined at link time.
* IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE.
* Heap. Extends to the end of SRAM.
*
* The following memory map is assumed for the kernel build:
*
* Kernel .data region. Size determined at link time.
* Kernel .bss region Size determined at link time.
* Kernel IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE.
* Padding for alignment
* User .data region. Size determined at link time.
* User .bss region Size determined at link time.
* Kernel heap. Size determined by CONFIG_MM_KERNEL_HEAPSIZE.
* User heap. Extends to the end of SRAM.
*
****************************************************************************/
void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
{
#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP)
/* Get the unaligned size and position of the user-space heap.
* This heap begins after the user-space .bss section at an offset
* of CONFIG_MM_KERNEL_HEAPSIZE (subject to alignment).
*/
uintptr_t ubase = (uintptr_t)USERSPACE->us_bssend + CONFIG_MM_KERNEL_HEAPSIZE;
size_t usize = SRAM1_END - ubase;
int log2;
DEBUGASSERT(ubase < (uintptr_t)SRAM1_END);
/* Adjust that size to account for MPU alignment requirements.
* NOTE that there is an implicit assumption that the SRAM1_END
* is aligned to the MPU requirement.
*/
log2 = (int)mpu_log2regionfloor(usize);
DEBUGASSERT((SRAM1_END & ((1 << log2) - 1)) == 0);
usize = (1 << log2);
ubase = SRAM1_END - usize;
/* Return the user-space heap settings */
up_ledon(LED_HEAPALLOCATE);
*heap_start = (FAR void*)ubase;
*heap_size = usize;
/* Allow user-mode access to the user heap memory */
stm32_mpu_uheap((uintptr_t)ubase, usize);
#else
/* Return the heap settings */
up_ledon(LED_HEAPALLOCATE);
*heap_start = (FAR void*)g_idle_topstack;
*heap_size = SRAM1_END - g_idle_topstack;
#endif
}
/****************************************************************************
* Name: up_allocate_kheap
*
* Description:
* For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
* user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function allocates
* (and protects) the kernel-space heap.
*
****************************************************************************/
#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP)
void up_allocate_kheap(FAR void **heap_start, size_t *heap_size)
{
/* Get the unaligned size and position of the user-space heap.
* This heap begins after the user-space .bss section at an offset
* of CONFIG_MM_KERNEL_HEAPSIZE (subject to alignment).
*/
uintptr_t ubase = (uintptr_t)USERSPACE->us_bssend + CONFIG_MM_KERNEL_HEAPSIZE;
size_t usize = SRAM1_END - ubase;
int log2;
DEBUGASSERT(ubase < (uintptr_t)SRAM1_END);
/* Adjust that size to account for MPU alignment requirements.
* NOTE that there is an implicit assumption that the SRAM1_END
* is aligned to the MPU requirement.
*/
log2 = (int)mpu_log2regionfloor(usize);
DEBUGASSERT((SRAM1_END & ((1 << log2) - 1)) == 0);
usize = (1 << log2);
ubase = SRAM1_END - usize;
/* Return the kernel heap settings (i.e., the part of the heap region
* that was not dedicated to the user heap).
*/
*heap_start = (FAR void*)USERSPACE->us_bssend;
*heap_size = ubase - (uintptr_t)USERSPACE->us_bssend;
}
#endif
/****************************************************************************
* Name: up_addregion
*
@ -386,16 +485,32 @@ void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
#if CONFIG_MM_REGIONS > 1
void up_addregion(void)
{
/* Add the STM32F20xxx/STM32F40xxx CCM SRAM heap region. */
#ifndef CONFIG_STM32_CCMEXCLUDE
kmm_addregion((FAR void*)SRAM2_START, SRAM2_END-SRAM2_START);
#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP)
/* Allow user-mode access to the STM32F20xxx/STM32F40xxx CCM SRAM heap */
stm32_mpu_uheap((uintptr_t)SRAM2_START, SRAM2_END-SRAM2_START);
#endif
/* Add the external FSMC SRAM heap region. */
/* Add the STM32F20xxx/STM32F40xxx CCM SRAM user heap region. */
kumm_addregion((FAR void*)SRAM2_START, SRAM2_END-SRAM2_START);
#endif
#ifdef CONFIG_STM32_FSMC_SRAM
kmm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP)
/* Allow user-mode access to the FSMC SRAM user heap memory */
stm32_mpu_uheap((uintptr_t)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
#endif
/* Add the external FSMC SRAM user heap region. */
kumm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_SIZE);
#endif
}
#endif

View File

@ -0,0 +1,124 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_mpuinit.c
*
* Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <assert.h>
#include <nuttx/userspace.h>
#include "mpu.h"
#include "stm32_mpuinit.h"
#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_ARMV7M_MPU)
/****************************************************************************
* Private Definitions
****************************************************************************/
#ifndef MAX
# define MAX(a,b) a > b ? a : b
#endif
#ifndef MIN
# define MIN(a,b) a < b ? a : b
#endif
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_mpuinitialize
*
* Description:
* Configure the MPU to permit user-space access to only restricted SAM3U
* resources.
*
****************************************************************************/
void stm32_mpuinitialize(void)
{
uintptr_t datastart = MIN(USERSPACE->us_datastart, USERSPACE->us_bssstart);
uintptr_t dataend = MAX(USERSPACE->us_dataend, USERSPACE->us_bssend);
DEBUGASSERT(USERSPACE->us_textend >= USERSPACE->us_textstart &&
dataend >= datastart);
/* Show MPU information */
mpu_showtype();
/* Configure user flash and SRAM space */
mpu_userflash(USERSPACE->us_textstart,
USERSPACE->us_textend - USERSPACE->us_textstart);
mpu_userintsram(datastart, dataend - datastart);
/* Then enable the MPU */
mpu_control(true, false, true);
}
/****************************************************************************
* Name: stm32_mpu_uheap
*
* Description:
* Map the user-heap region.
*
* This logic may need an extension to handle external SDRAM).
*
****************************************************************************/
void stm32_mpu_uheap(uintptr_t start, size_t size)
{
mpu_userintsram(start, size);
}
#endif /* CONFIG_NUTTX_KERNEL && CONFIG_ARMV7M_MPU */

View File

@ -0,0 +1,90 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_mpuinit.h
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32_STM32_MPUINIT_H
#define __ARCH_ARM_SRC_STM32_STM32_MPUINIT_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/****************************************************************************
* Name: stm32_mpuinitialize
*
* Description:
* Configure the MPU to permit user-space access to only unrestricted MCU
* resources.
*
****************************************************************************/
#ifdef CONFIG_NUTTX_KERNEL
void stm32_mpuinitialize(void);
#else
# define stm32_mpuinitialize()
#endif
/****************************************************************************
* Name: stm32_mpu_uheap
*
* Description:
* Map the user heap region.
*
****************************************************************************/
#ifdef CONFIG_NUTTX_KERNEL
void stm32_mpu_uheap(uintptr_t start, size_t size);
#else
# define stm32_mpu_uheap(start,size)
#endif
#endif /* __ARCH_ARM_SRC_STM32_STM32_MPUINIT_H */

View File

@ -52,6 +52,7 @@
#include "stm32.h"
#include "stm32_gpio.h"
#include "stm32_userspace.h"
#ifdef CONFIG_ARCH_FPU
# include "nvic.h"
@ -198,6 +199,7 @@ void __start(void)
{
*dest++ = 0;
}
showprogress('B');
/* Move the intialized data section from his temporary holding spot in
@ -210,6 +212,7 @@ void __start(void)
{
*dest++ = *src++;
}
showprogress('C');
/* Perform early serial initialization */
@ -219,10 +222,21 @@ void __start(void)
#endif
showprogress('D');
/* For the case of the separate user-/kernel-space build, perform whatever
* platform specific initialization of the user memory is required.
* Normally this just means initializing the user space .data and .bss
* segments.
*/
#ifdef CONFIG_NUTTX_KERNEL
stm32_userspace();
showprogress('E');
#endif
/* Initialize onboard resources */
stm32_boardinitialize();
showprogress('E');
showprogress('F');
/* Then start NuttX */

View File

@ -0,0 +1,119 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_userspace.c
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <assert.h>
#include <nuttx/userspace.h>
#include "stm32_mpuinit.h"
#include "stm32_userspace.h"
#ifdef CONFIG_NUTTX_KERNEL
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_userspace
*
* Description:
* For the case of the separate user-/kernel-space build, perform whatever
* platform specific initialization of the user memory is required.
* Normally this just means initializing the user space .data and .bss
* segments.
*
****************************************************************************/
void stm32_userspace(void)
{
uint8_t *src;
uint8_t *dest;
uint8_t *end;
/* Clear all of user-space .bss */
DEBUGASSERT(USERSPACE->us_bssstart != 0 && USERSPACE->us_bssend != 0 &&
USERSPACE->us_bssstart <= USERSPACE->us_bssend);
dest = (uint8_t*)USERSPACE->us_bssstart;
end = (uint8_t*)USERSPACE->us_bssend;
while (dest != end)
{
*dest++ = 0;
}
/* Initialize all of user-space .data */
DEBUGASSERT(USERSPACE->us_datasource != 0 &&
USERSPACE->us_datastart != 0 && USERSPACE->us_dataend != 0 &&
USERSPACE->us_datastart <= USERSPACE->us_dataend);
src = (uint8_t*)USERSPACE->us_datasource;
dest = (uint8_t*)USERSPACE->us_datastart;
end = (uint8_t*)USERSPACE->us_dataend;
while (dest != end)
{
*dest++ = *src++;
}
/* Configure the MPU to permit user-space access to its FLASH and RAM */
stm32_mpuinitialize();
}
#endif /* CONFIG_NUTTX_KERNEL */

View File

@ -0,0 +1,76 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_qei.h
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32_STM32_USERSPACE_H
#define __ARCH_ARM_SRC_STM32_STM32_USERSPACE_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/****************************************************************************
* Name: stm32_userspace
*
* Description:
* For the case of the separate user-/kernel-space build, perform whatever
* platform specific initialization of the user memory is required.
* Normally this just means initializing the user space .data and .bss
* segments.
*
****************************************************************************/
#ifdef CONFIG_NUTTX_KERNEL
void stm32_userspace(void);
#endif
#endif /* __ARCH_ARM_SRC_STM32_STM32_USERSPACE_H */

View File

@ -69,8 +69,8 @@
* 0x2000:ffff - End of SRAM and end of heap
*/
#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
/* The Cortex-M3 return from interrupt is unusual. We provide the following special
* address to the BX instruction. The particular value also forces a return to
@ -219,7 +219,7 @@ stm32_common:
#ifdef CONFIG_NUTTX_KERNEL
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
* (handler mode) if the state is on the MSP. It can only be on the PSP if
* (handler mode) if the stack is on the MSP. It can only be on the PSP if
* EXC_RETURN is 0xfffffffd (unprivileged thread)
*/
@ -314,10 +314,10 @@ stm32_common:
bl up_restorefpu /* Restore the FPU registers */
#endif
/* Returning with a pending context switch is different from the normal
* return because in this case, the register save structure does not lie
* on the stack but, rather, are within a TCB structure. We'll have to
* copy somevalues to the new stack.
/* We are returning with a pending context switch. This case is different
* because in this case, the register save structure does not lie in the
* stack but, rather, within a TCB structure. We'll have to copy some
* values to the stack.
*/
add r1, r0, #SW_XCPT_SIZE /* R1=Address of HW save area in reg array */
@ -343,6 +343,7 @@ stm32_common:
#else
ldmia r1!, {r2-r11} /* Recover R4-R11 + 2 temp values */
#endif
#ifdef CONFIG_ARCH_FPU
/* Skip over the block of memory reserved for floating pointer register
* save. Then R1 is the address of the HW save area
@ -360,16 +361,25 @@ stm32_common:
* r4-r11 = restored register values
*/
2:
#ifdef CONFIG_NUTTX_KERNEL
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
* (handler mode) if the state is on the MSP. It can only be on the PSP if
* (handler mode) if the stack is on the MSP. It can only be on the PSP if
* EXC_RETURN is 0xfffffffd (unprivileged thread)
*/
adds r0, r14, #3 /* If R14=0xfffffffd, then r0 == 0 */
ite ne /* Next two instructions are condition */
msrne msp, r1 /* R1=The main stack pointer */
msreq psp, r1 /* R1=The process stack pointer */
mrs r2, control /* R2=Contents of the control register */
tst r14, #EXC_RETURN_PROCESS_STACK /* nonzero if context on process stack */
beq 3f /* Branch if privileged */
orr r2, r2, #1 /* Unprivileged mode */
msr psp, r1 /* R1=The process stack pointer */
b 4f
3:
bic r2, r2, #1 /* Privileged mode */
msr msp, r1 /* R1=The main stack pointer */
4:
msr control, r2 /* Save the updated control register */
#else
msr msp, r1 /* Recover the return MSP value */
@ -432,8 +442,7 @@ g_intstackbase:
.globl g_idle_topstack
.type g_idle_topstack, object
g_idle_topstack:
.long _ebss+CONFIG_IDLETHREAD_STACKSIZE
.word HEAP_BASE
.size g_idle_topstack, .-g_idle_topstack
.end

View File

@ -57,7 +57,7 @@
#endif
#if CONFIG_NUTTX_USERSPACE != 0x00010000
# error "CONFIG_NUTTX_USERSPACE must be 0x00010000 to match user-space.ld"
# error "CONFIG_NUTTX_USERSPACE must be 0x00010000 to match memory.ld"
#endif
/****************************************************************************

View File

@ -1,5 +1,5 @@
/****************************************************************************
* configs/open1788/knsh/memory.ld
* configs/open1788/scripts/memory.ld
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -0,0 +1,116 @@
############################################################################
# configs/stm32f4discovery/kernel/Makefile
#
# Copyright (C) 2013 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
-include $(TOPDIR)/Make.defs
# This is the directory for the board-specific header files
BOARD_INCLUDE = $(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)include
# The entry point name (if none is provided in the .config file)
CONFIG_USER_ENTRYPOINT ?= user_start
ENTRYPT = $(patsubst "%",%,$(CONFIG_USER_ENTRYPOINT))
# Get the paths to the libraries and the links script path in format that
# is appropriate for the host OS
ifeq ($(WINTOOL),y)
# Windows-native toolchains
USER_LIBPATHS = ${shell for path in $(USERLIBS); do dir=`dirname $(TOPDIR)$(DELIM)$$path`;echo "-L\"`cygpath -w $$dir`\"";done}
USER_LDSCRIPT = -T "${shell cygpath -w $(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)scripts$(DELIM)memory.ld}"
USER_LDSCRIPT += -T "${shell cygpath -w $(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)scripts$(DELIM)user-space.ld}"
else
# Linux/Cygwin-native toolchain
USER_LIBPATHS = $(addprefix -L$(TOPDIR)$(DELIM),$(dir $(USERLIBS)))
USER_LDSCRIPT = -T$(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)scripts$(DELIM)memory.ld
USER_LDSCRIPT += -T$(TOPDIR)$(DELIM)configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)scripts$(DELIM)user-space.ld
endif
USER_LDFLAGS = --undefined=$(ENTRYPT) --entry=$(ENTRYPT) $(USER_LDSCRIPT)
USER_LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(USERLIBS))))
USER_LIBGCC = "${shell $(CC) -print-libgcc-file-name}"
# Source files
CSRCS = up_userspace.c
COBJS = $(CSRCS:.c=$(OBJEXT))
OBJS = $(COBJS)
# Targets:
all: $(TOPDIR)$(DELIM)nuttx_user.elf $(TOPDIR)$(DELIM)User.map
.PHONY: nuttx_user.elf depend clean distclean
$(COBJS): %$(OBJEXT): %.c
$(call COMPILE, $<, $@)
# Create the nuttx_user.elf file containing all of the user-mode code
nuttx_user.elf: $(OBJS)
$(Q) $(LD) -o $@ $(USER_LDFLAGS) $(USER_LIBPATHS) $(OBJS) --start-group $(USER_LDLIBS) --end-group $(USER_LIBGCC)
$(TOPDIR)$(DELIM)nuttx_user.elf: nuttx_user.elf
@echo "LD: nuttx_user.elf"
$(Q) cp -a nuttx_user.elf $(TOPDIR)$(DELIM)nuttx_user.elf
ifeq ($(CONFIG_INTELHEX_BINARY),y)
@echo "CP: nuttx_user.hex"
$(Q) $(OBJCOPY) $(OBJCOPYARGS) -O ihex nuttx_user.elf $(TOPDIR)$(DELIM)nuttx_user.hex
endif
ifeq ($(CONFIG_MOTOROLA_SREC),y)
@echo "CP: nuttx_user.srec"
$(Q) $(OBJCOPY) $(OBJCOPYARGS) -O srec nuttx_user.elf $(TOPDIR)$(DELIM)nuttx_user.srec
endif
ifeq ($(CONFIG_RAW_BINARY),y)
@echo "CP: nuttx_user.bin"
$(Q) $(OBJCOPY) $(OBJCOPYARGS) -O binary nuttx_user.elf $(TOPDIR)$(DELIM)nuttx_user.bin
endif
$(TOPDIR)$(DELIM)User.map: nuttx_user.elf
@echo "MK: User.map"
$(Q) $(NM) nuttx_user.elf >$(TOPDIR)$(DELIM)User.map
$(Q) $(CROSSDEV)size nuttx_user.elf
.depend:
depend: .depend
clean:
$(call DELFILE, nuttx_user.elf)
$(call DELFILE, "$(TOPDIR)$(DELIM)nuttx_user.*")
$(call DELFILE, "$(TOPDIR)$(DELIM)User.map")
$(call CLEAN)
distclean: clean

View File

@ -0,0 +1,142 @@
/****************************************************************************
* configs/stm32f4discovery/kernel/up_userspace.c
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdlib.h>
#include <nuttx/userspace.h>
#include <nuttx/wqueue.h>
#include <nuttx/mm.h>
#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
#ifndef CONFIG_NUTTX_USERSPACE
# error "CONFIG_NUTTX_USERSPACE not defined"
#endif
#if CONFIG_NUTTX_USERSPACE != 0x08018000
# error "CONFIG_NUTTX_USERSPACE must be 0x08018000 to match memory.ld"
#endif
/****************************************************************************
* Public Data
****************************************************************************/
/* These 'addresses' of these values are setup by the linker script. They are
* not actual uint32_t storage locations! They are only used meaningfully in the
* following way:
*
* - The linker script defines, for example, the symbol_sdata.
* - The declareion extern uint32_t _sdata; makes C happy. C will believe
* that the value _sdata is the address of a uint32_t variable _data (it is
* not!).
* - We can recoved the linker value then by simply taking the address of
* of _data. like: uint32_t *pdata = &_sdata;
*/
extern uint32_t _stext; /* Start of .text */
extern uint32_t _etext; /* End_1 of .text + .rodata */
extern const uint32_t _eronly; /* End+1 of read only section (.text + .rodata) */
extern uint32_t _sdata; /* Start of .data */
extern uint32_t _edata; /* End+1 of .data */
extern uint32_t _sbss; /* Start of .bss */
extern uint32_t _ebss; /* End+1 of .bss */
/* This is the user space entry point */
int CONFIG_USER_ENTRYPOINT(int argc, char *argv[]);
const struct userspace_s userspace __attribute__ ((section (".userspace"))) =
{
/* General memory map */
.us_entrypoint = (main_t)CONFIG_USER_ENTRYPOINT,
.us_textstart = (uintptr_t)&_stext,
.us_textend = (uintptr_t)&_etext,
.us_datasource = (uintptr_t)&_eronly,
.us_datastart = (uintptr_t)&_sdata,
.us_dataend = (uintptr_t)&_edata,
.us_bssstart = (uintptr_t)&_sbss,
.us_bssend = (uintptr_t)&_ebss,
/* Task/thread startup routines */
.task_startup = task_startup,
#ifndef CONFIG_DISABLE_PTHREAD
.pthread_startup = pthread_startup,
#endif
/* Signal handler trampoline */
#ifndef CONFIG_DISABLE_SIGNALS
.signal_handler = signal_handler,
#endif
/* Memory manager entry points (declared in include/nuttx/mm.h) */
.mm_initialize = umm_initialize,
.mm_addregion = umm_addregion,
.mm_trysemaphore = umm_trysemaphore,
.mm_givesemaphore = umm_givesemaphore,
/* Memory manager entry points (declared in include/stdlib.h) */
.mm_malloc = malloc,
.mm_realloc = realloc,
.mm_zalloc = zalloc,
.mm_free = free,
/* User-space work queue support (declared in include/nuttx/wqueue.h) */
#if defined(CONFIG_SCHED_WORKQUEUE) && defined(CONFIG_SCHED_USRWORK)
.work_usrstart = work_usrstart;
#endif
};
/****************************************************************************
* Public Functions
****************************************************************************/
#endif /* CONFIG_NUTTX_KERNEL && !__KERNEL__ */

View File

@ -0,0 +1,109 @@
/****************************************************************************
* configs/stm32f4discovery/scripts/kernel-space.ld
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* NOTE: This depends on the memory.ld script having been included prior to
* this script.
*/
OUTPUT_ARCH(arm)
ENTRY(_stext)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > kflash
.init_section : {
_sinit = ABSOLUTE(.);
*(.init_array .init_array.*)
_einit = ABSOLUTE(.);
} > kflash
.ARM.extab : {
*(.ARM.extab*)
} > kflash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > kflash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > ksram AT > kflash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > ksram
/* Stabs debugging sections */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -0,0 +1,78 @@
/****************************************************************************
* configs/stm32f4discovery/scripts/memory.ld
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The STM32F407VG has 1024Kb of FLASH beginning at address 0x0800:0000 and
* 192Kb of SRAM. SRAM is split up into three blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
* 2) 16Kb of SRAM beginning at address 0x2001:c000
* 3) 64Kb of CCM SRAM beginning at address 0x1000:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address
* range.
*
* For MPU support, the kernel-mode NuttX section is assumed to be 96Kb of
* FLASH and 4Kb of SRAM. That, of course, can be optimized as needed (See
* also configs/stm32f4discovery/scripts/kernel-space.ld). A detailed memory map
* for the CPU SRAM region is as follows:
*
* 0x20000 0000: Kernel .data region. Typical size: 0.1KB
* ------- ---- Kernel .bss region. Typical size: 1.8KB
* 0x20000 0800: Kernel IDLE thread stack (approximate). Size is
* determined by CONFIG_IDLETHREAD_STACKSIZE and
* adjustments for alignment. Typical is 1KB.
* ------- ---- Padded to 4KB
* 0x20000 1000: User .data region. Size is variable.
* ------- ---- User .bss region Size is variable.
* ------- ---- Beginning of kernel heap. Size determined by
* CONFIG_MM_KERNEL_HEAPSIZE.
* ------- ---- Beginning of user heap. Can vary with other settings.
* 0x20001 c000: End+1 of CPU RAM
*/
MEMORY
{
/* 1024Kb FLASH */
kflash (rx) : ORIGIN = 0x08000000, LENGTH = 96K
uflash (rx) : ORIGIN = 0x08018000, LENGTH = 928K
/* 112Kb of contiguous SRAM */
ksram (rwx) : ORIGIN = 0x20000000, LENGTH = 4K
usram (rwx) : ORIGIN = 0x20001000, LENGTH = 108K
}

View File

@ -0,0 +1,126 @@
/****************************************************************************
* configs/stm32f4discovery/scripts/user-space.ld
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* NOTE: This depends on the memory.ld script having been included prior to
* this script.
*/
/* Make sure that the critical memory management functions are in user-space.
* the user heap memory manager will reside in user-space but be usable both
* by kernel- and user-space code
*/
EXTERN(umm_initialize)
EXTERN(umm_addregion)
EXTERN(umm_trysemaphore)
EXTERN(umm_givesemaphore)
EXTERN(malloc)
EXTERN(realloc)
EXTERN(zalloc)
EXTERN(free)
OUTPUT_ARCH(arm)
SECTIONS
{
.userspace : {
*(.userspace)
} > uflash
.text : {
_stext = ABSOLUTE(.);
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > uflash
.init_section : {
_sinit = ABSOLUTE(.);
*(.init_array .init_array.*)
_einit = ABSOLUTE(.);
} > uflash
.ARM.extab : {
*(.ARM.extab*)
} > uflash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > uflash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > usram AT > uflash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > usram
/* Stabs debugging sections */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -0,0 +1,195 @@
/****************************************************************************
* configs/zkit-arm-1769/src/up_lcd.c
* arch/arm/src/board/up_lcd.c
*
* Copyright (C) 2013 Zilogic Systems. All rights reserved.
* Author: Manikandan <code@zilogic.com>
*
* Based on configs/lm3s6965-ek/src/up_oled.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
#include <stdbool.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/st7567.h>
#include "up_arch.h"
#include "up_internal.h"
#include "lpc17_gpio.h"
#include "zkitarm_internal.h"
#ifdef CONFIG_NX_LCDDRIVER
/****************************************************************************
* Definitions
****************************************************************************/
/* Enables debug output from this file (needs CONFIG_DEBUG with
* CONFIG_DEBUG_VERBOSE too)
*/
#undef LCD_DEBUG /* Define to enable debug */
#undef LCD_VERBOSE /* Define to enable verbose debug */
#ifdef LCD_DEBUG
# define leddbg lldbg
# ifdef LCD_VERBOSE
# define ledvdbg lldbg
# else
# define ledvdbg(x...)
# endif
#else
# undef LCD_VERBOSE
# define leddbg(x...)
# define ledvdbg(x...)
#endif
/****************************************************************************
* Private Data
****************************************************************************/
FAR struct spi_dev_s *spi;
FAR struct lcd_dev_s *dev;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_lcdinitialize
****************************************************************************/
int up_lcdinitialize(void)
{
lpc17_configgpio(ZKITARM_OLED_RST);
lpc17_configgpio(ZKITARM_OLED_CS);
lpc17_configgpio(ZKITARM_OLED_RS);
lpc17_gpiowrite(ZKITARM_OLED_RST, 1);
lpc17_gpiowrite(ZKITARM_OLED_CS, 1);
lpc17_gpiowrite(ZKITARM_OLED_RS, 1);
spi = up_spiinitialize(0);
if (!spi)
{
glldbg("Failed to initialize SSI port 0\n");
return 0;
}
lpc17_gpiowrite(ZKITARM_OLED_RST, 0);
up_mdelay(1);
lpc17_gpiowrite(ZKITARM_OLED_RST, 1);
return 1;
}
/****************************************************************************
* Name: up_lcdgetdev
****************************************************************************/
FAR struct lcd_dev_s *up_lcdgetdev(int lcddev)
{
dev = st7567_initialize(spi, lcddev);
if (!dev)
{
glldbg("Failed to bind SSI port 0 to OLCD %d: %d\n", lcddev);
}
else
{
gllvdbg("Bound SSI port 0 to OLCD %d\n", lcddev);
/* And turn the OLCD on (CONFIG_LCD_MAXPOWER should be 1) */
(void)dev->setpower(dev, CONFIG_LCD_MAXPOWER);
return dev;
}
return NULL;
}
/****************************************************************************
* Name: up_lcduninitialize
****************************************************************************/
void up_lcduninitialize(void)
{
/* TO-FIX */
}
/******************************************************************************
* Name: lpc17_spicmddata
*
* Description:
* Set or clear the SD1329 D/Cn bit to select data (true) or command
* (false). This function must be provided by platform-specific logic.
* This is an implementation of the cmddata method of the SPI
* interface defined by struct spi_ops_s (see include/nuttx/spi.h).
*
* Input Parameters:
*
* spi - SPI device that controls the bus the device that requires the CMD/
* DATA selection.
* devid - If there are multiple devices on the bus, this selects which one
* to select cmd or data. NOTE: This design restricts, for example,
* one one SPI display per SPI bus.
* cmd - true: select command; false: select data
*
* Returned Value:
* None
*
******************************************************************************/
int lpc17_ssp0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
{
if (devid == SPIDEV_DISPLAY)
{
/* Set GPIO to 1 for data, 0 for command */
lpc17_gpiowrite(ZKITARM_OLED_RS, !cmd);
return OK;
}
return -ENODEV;
}
#endif /* CONFIG_ARCH_LCDS */