summaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-22 14:49:21 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-22 14:49:21 +0000
commitd27a58798955bad789da8f89acadf8c4341c2ecb (patch)
treecbe8f3e15879dec4125868437e34b7773d5ca1a7 /nuttx/configs
parent4bfc8f39c961f54043988792cce387f36b783df2 (diff)
downloadpx4-nuttx-d27a58798955bad789da8f89acadf8c4341c2ecb.tar.gz
px4-nuttx-d27a58798955bad789da8f89acadf8c4341c2ecb.tar.bz2
px4-nuttx-d27a58798955bad789da8f89acadf8c4341c2ecb.zip
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
Diffstat (limited to 'nuttx/configs')
-rw-r--r--nuttx/configs/open1788/kernel/up_userspace.c2
-rw-r--r--nuttx/configs/open1788/scripts/memory.ld2
-rw-r--r--nuttx/configs/stm32f4discovery/kernel/Makefile116
-rw-r--r--nuttx/configs/stm32f4discovery/kernel/up_userspace.c142
-rwxr-xr-xnuttx/configs/stm32f4discovery/scripts/kernel-space.ld109
-rw-r--r--nuttx/configs/stm32f4discovery/scripts/memory.ld78
-rw-r--r--nuttx/configs/stm32f4discovery/scripts/user-space.ld126
-rw-r--r--nuttx/configs/zkit-arm-1769/src/up_lcd.c195
8 files changed, 768 insertions, 2 deletions
diff --git a/nuttx/configs/open1788/kernel/up_userspace.c b/nuttx/configs/open1788/kernel/up_userspace.c
index 2263bc3f5..b6a9e3df6 100644
--- a/nuttx/configs/open1788/kernel/up_userspace.c
+++ b/nuttx/configs/open1788/kernel/up_userspace.c
@@ -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
/****************************************************************************
diff --git a/nuttx/configs/open1788/scripts/memory.ld b/nuttx/configs/open1788/scripts/memory.ld
index 4f301dcfb..5f23145d4 100644
--- a/nuttx/configs/open1788/scripts/memory.ld
+++ b/nuttx/configs/open1788/scripts/memory.ld
@@ -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>
diff --git a/nuttx/configs/stm32f4discovery/kernel/Makefile b/nuttx/configs/stm32f4discovery/kernel/Makefile
new file mode 100644
index 000000000..9d65efde2
--- /dev/null
+++ b/nuttx/configs/stm32f4discovery/kernel/Makefile
@@ -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
diff --git a/nuttx/configs/stm32f4discovery/kernel/up_userspace.c b/nuttx/configs/stm32f4discovery/kernel/up_userspace.c
new file mode 100644
index 000000000..eb73f8069
--- /dev/null
+++ b/nuttx/configs/stm32f4discovery/kernel/up_userspace.c
@@ -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__ */
diff --git a/nuttx/configs/stm32f4discovery/scripts/kernel-space.ld b/nuttx/configs/stm32f4discovery/scripts/kernel-space.ld
new file mode 100755
index 000000000..3feb651e6
--- /dev/null
+++ b/nuttx/configs/stm32f4discovery/scripts/kernel-space.ld
@@ -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) }
+}
diff --git a/nuttx/configs/stm32f4discovery/scripts/memory.ld b/nuttx/configs/stm32f4discovery/scripts/memory.ld
new file mode 100644
index 000000000..e1d89450e
--- /dev/null
+++ b/nuttx/configs/stm32f4discovery/scripts/memory.ld
@@ -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
+}
diff --git a/nuttx/configs/stm32f4discovery/scripts/user-space.ld b/nuttx/configs/stm32f4discovery/scripts/user-space.ld
new file mode 100644
index 000000000..56d30a05f
--- /dev/null
+++ b/nuttx/configs/stm32f4discovery/scripts/user-space.ld
@@ -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) }
+}
diff --git a/nuttx/configs/zkit-arm-1769/src/up_lcd.c b/nuttx/configs/zkit-arm-1769/src/up_lcd.c
new file mode 100644
index 000000000..d315131ee
--- /dev/null
+++ b/nuttx/configs/zkit-arm-1769/src/up_lcd.c
@@ -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 */