From 569561d0b8bbf208837ed267a59b5c8152b278d7 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 11 Mar 2013 20:26:55 +0000 Subject: Reorganize some AT91SAM3U files; Add an NSH kernel build configuration to the WaveSahhare Open1788 board git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5732 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/open1788/README.txt | 62 ++ nuttx/configs/open1788/kernel/Makefile | 114 ++++ nuttx/configs/open1788/kernel/up_userspace.c | 129 ++++ nuttx/configs/open1788/knsh/Make.defs | 109 ++++ nuttx/configs/open1788/knsh/defconfig | 722 +++++++++++++++++++++ nuttx/configs/open1788/knsh/setenv.sh | 73 +++ nuttx/configs/open1788/scripts/kernel-space.ld | 134 ++++ nuttx/configs/open1788/scripts/user-space.ld | 153 +++++ nuttx/configs/open1788/src/Makefile | 42 +- nuttx/configs/open1788/src/lpc17_boardinitialize.c | 26 + nuttx/configs/open1788/src/lpc17_buttons.c | 23 +- nuttx/configs/open1788/src/lpc17_nsh.c | 13 +- nuttx/configs/open1788/src/open1788.h | 19 + 13 files changed, 1594 insertions(+), 25 deletions(-) create mode 100644 nuttx/configs/open1788/kernel/Makefile create mode 100644 nuttx/configs/open1788/kernel/up_userspace.c create mode 100644 nuttx/configs/open1788/knsh/Make.defs create mode 100755 nuttx/configs/open1788/knsh/defconfig create mode 100755 nuttx/configs/open1788/knsh/setenv.sh create mode 100755 nuttx/configs/open1788/scripts/kernel-space.ld create mode 100644 nuttx/configs/open1788/scripts/user-space.ld (limited to 'nuttx/configs/open1788') diff --git a/nuttx/configs/open1788/README.txt b/nuttx/configs/open1788/README.txt index da3d91821..da41538cd 100644 --- a/nuttx/configs/open1788/README.txt +++ b/nuttx/configs/open1788/README.txt @@ -292,4 +292,66 @@ CONFIGURATION CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y : Buildroot toolchain CONFIG_ARMV7M_OABI_TOOLCHAIN=y : Older, OABI toolchain + knsh + ---- + This is identical to the nsh configuration below except that NuttX + is built as a kernel-mode, monolithic module and the user applications + are built separately. This build requires a special make command; not + just 'make' but make with the following two arguments: + make pass1 pass2 + + This is required because in the normal case (just 'make'), make will + create all dependencies then execute the pass1 and pass2 targets. But + this example, pass2 depends on auto-generatd files produced during pass1. + This special make command ('make pass1 pass2') will make the dependencies + separately for each pass. + + NOTES: + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + and misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Uses the older, OABI, buildroot toolchain. But that is easily + reconfigured: + + CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y : Buildroot toolchain + CONFIG_ARMV7M_OABI_TOOLCHAIN=y : Older, OABI toolchain + + 3. At the end of the build, there four files will top-level build + directory: + + nuttx_user.elf - The pass1 user-space ELF file + nuttx - The pass2 kernel-space ELF file + nuttx_user.hex - The pass1 Intel HEX format file + nuttx.hex - The pass2 Intel HEX file + System.map - Symbols in the kernel-space ELF file + User.map - Symbols in the user-space ELF file + + nsh + --- + Configures the NuttShell (nsh) located at examples/nsh. The + Configuration enables both the serial NSH interface. + + NOTES: + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + and misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Uses the older, OABI, buildroot toolchain. But that is easily + reconfigured: + + CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y : Buildroot toolchain + CONFIG_ARMV7M_OABI_TOOLCHAIN=y : Older, OABI toolchain diff --git a/nuttx/configs/open1788/kernel/Makefile b/nuttx/configs/open1788/kernel/Makefile new file mode 100644 index 000000000..9cf196375 --- /dev/null +++ b/nuttx/configs/open1788/kernel/Makefile @@ -0,0 +1,114 @@ +############################################################################ +# configs/open1788/kernel/Makefile +# +# 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. +# +############################################################################ + +-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)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)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: 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.elf") + $(call DELFILE, "$(TOPDIR)$(DELIM)User.map") + $(call CLEAN) + +distclean: clean diff --git a/nuttx/configs/open1788/kernel/up_userspace.c b/nuttx/configs/open1788/kernel/up_userspace.c new file mode 100644 index 000000000..62c83e735 --- /dev/null +++ b/nuttx/configs/open1788/kernel/up_userspace.c @@ -0,0 +1,129 @@ +/**************************************************************************** + * configs/open1788/kernel/up_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 + +#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 != 0x00010000 +# error "CONFIG_NUTTX_USERSPACE must be 0x00010000 to match user-space.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, + + /* 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/open1788/knsh/Make.defs b/nuttx/configs/open1788/knsh/Make.defs new file mode 100644 index 000000000..bf5073832 --- /dev/null +++ b/nuttx/configs/open1788/knsh/Make.defs @@ -0,0 +1,109 @@ +############################################################################ +# configs/open1788/knsh/Make.defs +# +# 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/kernel-space.ld}" + MAXOPTIMIZATION = -O2 +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/kernel-space.ld +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx/configs/open1788/knsh/defconfig b/nuttx/configs/open1788/knsh/defconfig new file mode 100755 index 000000000..ab64744e3 --- /dev/null +++ b/nuttx/configs/open1788/knsh/defconfig @@ -0,0 +1,722 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_2PASS=y +CONFIG_PASS1_TARGET="all" +CONFIG_PASS1_BUILDIR="configs/open1788/kernel" +CONFIG_PASS1_OBJECT="" +CONFIG_NUTTX_KERNEL=y +CONFIG_NUTTX_USERSPACE=0x00010000 + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +# CONFIG_RAW_BINARY is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_LM is not set +CONFIG_ARCH_CHIP_LPC17XX=y +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +# CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM3=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="lpc17xx" +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +CONFIG_ARCH_HAVE_MPU=y +CONFIG_ARMV7M_MPU=y +CONFIG_ARMV7M_MPU_NREGIONS=8 + +# +# ARMV7M Configuration Options +# +CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI is not set +CONFIG_ARMV7M_OABI_TOOLCHAIN=y + +# +# LPC17xx Configuration Options +# +# CONFIG_ARCH_CHIP_LPC1751 is not set +# CONFIG_ARCH_CHIP_LPC1752 is not set +# CONFIG_ARCH_CHIP_LPC1754 is not set +# CONFIG_ARCH_CHIP_LPC1756 is not set +# CONFIG_ARCH_CHIP_LPC1758 is not set +# CONFIG_ARCH_CHIP_LPC1759 is not set +# CONFIG_ARCH_CHIP_LPC1764 is not set +# CONFIG_ARCH_CHIP_LPC1765 is not set +# CONFIG_ARCH_CHIP_LPC1766 is not set +# CONFIG_ARCH_CHIP_LPC1767 is not set +# CONFIG_ARCH_CHIP_LPC1768 is not set +# CONFIG_ARCH_CHIP_LPC1769 is not set +# CONFIG_ARCH_CHIP_LPC1773 is not set +# CONFIG_ARCH_CHIP_LPC1774 is not set +# CONFIG_ARCH_CHIP_LPC1776 is not set +# CONFIG_ARCH_CHIP_LPC1777 is not set +# CONFIG_ARCH_CHIP_LPC1778 is not set +# CONFIG_ARCH_CHIP_LPC1785 is not set +# CONFIG_ARCH_CHIP_LPC1786 is not set +# CONFIG_ARCH_CHIP_LPC1787 is not set +CONFIG_ARCH_CHIP_LPC1788=y +CONFIG_ARCH_FAMILY_LPC178X=y +CONFIG_ARCH_HAVE_SDIO=y + +# +# LPC17xx Peripheral Support +# +CONFIG_LPC17_MAINOSC=y +CONFIG_LPC17_PLL0=y +CONFIG_LPC17_PLL1=y +# CONFIG_LPC17_EMC is not set +# CONFIG_LPC17_ETHERNET is not set +# CONFIG_LPC17_LCD is not set +# CONFIG_LPC17_USBHOST is not set +# CONFIG_LPC17_USBDEV is not set +# CONFIG_LPC17_SDCARD=y +CONFIG_LPC17_UART0=y +# CONFIG_LPC17_UART1 is not set +# CONFIG_LPC17_UART2 is not set +# CONFIG_LPC17_UART3 is not set +# CONFIG_LPC17_UART4 is not set +# CONFIG_LPC17_CAN1 is not set +# CONFIG_LPC17_CAN2 is not set +# CONFIG_LPC17_SSP0 is not set +# CONFIG_LPC17_SSP1 is not set +# CONFIG_LPC17_SSP2 is not set +# CONFIG_LPC17_I2C0 is not set +# CONFIG_LPC17_I2C1 is not set +# CONFIG_LPC17_I2C2 is not set +# CONFIG_LPC17_I2S is not set +# CONFIG_LPC17_TMR0 is not set +# CONFIG_LPC17_TMR1 is not set +# CONFIG_LPC17_TMR2 is not set +# CONFIG_LPC17_TMR3 is not set +# CONFIG_LPC17_RIT is not set +# CONFIG_LPC17_PWM0 is not set +# CONFIG_LPC17_PWM1 is not set +# CONFIG_LPC17_QEI is not set +# CONFIG_LPC17_RTC is not set +# CONFIG_LPC17_WDT is not set +# CONFIG_LPC17_ADC is not set +# CONFIG_LPC17_DAC is not set +CONFIG_LPC17_GPDMA=y +# CONFIG_LPC17_CRC is not set +# CONFIG_LPC17_FLASH is not set +# CONFIG_LPC17_EEPROM is not set + +# +# Serial driver options +# +# CONFIG_SERIAL_TERMIOS is not set +# CONFIG_UART0_FLOWCONTROL is not set + +# +# ADC driver options +# + +# +# CAN driver options +# +# CONFIG_GPIO_IRQ is not set + +# +# I2C driver options +# + +# +# SDIO Configuration +# +CONFIG_SDIO_DMA=y +CONFIG_SDIO_DMAPRIO=0x0 +# CONFIG_SDIO_WIDTH_D1_ONLY is not set + +# +# Ethernet driver options +# + +# +# USB device driver options +# + +# +# USB host driver options +# + +# +# External Memory Configuration +# +CONFIG_ARCH_HAVE_EXTNAND=y +CONFIG_ARCH_HAVE_EXTNOR=y +CONFIG_ARCH_HAVE_EXTDRAM=y +CONFIG_ARCH_HAVE_EXTSRAM0=y +CONFIG_ARCH_EXTNAND=y +CONFIG_ARCH_EXTNANDSIZE=134217728 +CONFIG_ARCH_EXTNOR=y +CONFIG_ARCH_EXTNORSIZE=4194304 +CONFIG_ARCH_EXTDRAM=y +CONFIG_ARCH_EXTDRAMSIZE=67108864 +CONFIG_ARCH_EXTDRAMHEAP=y +CONFIG_ARCH_EXTSRAM0=y +CONFIG_ARCH_EXTSRAM0SIZE=131072 +CONFIG_ARCH_EXTSRAM0HEAP=y + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_IRQPRIO=y +# CONFIG_CUSTOM_STACK is not set +# CONFIG_ADDRENV is not set +CONFIG_ARCH_HAVE_VFORK=y +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=11934 +# CONFIG_ARCH_CALIBRATION is not set +CONFIG_DRAM_START=0x10000000 +CONFIG_DRAM_SIZE=65536 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_OPEN1788=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="open1788" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +# CONFIG_ARCH_IRQBUTTONS is not set +CONFIG_NSH_MMCSDMINOR=0 +CONFIG_NSH_MMCSDSLOTNO=0 + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_BOARD_INITIALIZE=y +CONFIG_MSEC_PER_TICK=10 +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_INSTRUMENTATION is not set +CONFIG_TASK_NAME_SIZE=0 +# CONFIG_SCHED_HAVE_PARENT is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2013 +CONFIG_START_MONTH=3 +CONFIG_START_DAY=11 +CONFIG_DEV_CONSOLE=y +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +CONFIG_SCHED_WAITPID=y +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=17 + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=16 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +CONFIG_SYS_RESERVED=4 + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +CONFIG_LOOP=y +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +# CONFIG_SPI is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +CONFIG_BCH=y +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +CONFIG_MMCSD=y +CONFIG_MMCSD_NSLOTS=1 +# CONFIG_MMCSD_READONLY is not set +# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set +CONFIG_MMCSD_MMCSUPPORT=y +CONFIG_MMCSD_HAVECARDDETECT=y +CONFIG_MMCSD_SDIO=y +# CONFIG_SDIO_MUXBUS is not set +CONFIG_SDIO_BLOCKSETUP=y +# CONFIG_MTD is not set +CONFIG_PIPES=y +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_UART0=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_UART0_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# UART0 Configuration +# +CONFIG_UART0_RXBUFSIZE=256 +CONFIG_UART0_TXBUFSIZE=256 +CONFIG_UART0_BAUD=115200 +CONFIG_UART0_BITS=8 +CONFIG_UART0_PARITY=0 +CONFIG_UART0_2STOP=0 +# CONFIG_USBDEV is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_RAMMAP is not set +CONFIG_FS_FAT=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_MAXFNAME=32 +# CONFIG_FS_FATTIME is not set +# CONFIG_FAT_DMAMEMORY is not set +# CONFIG_FS_NXFFS is not set +CONFIG_FS_ROMFS=y + +# +# System Logging +# +# CONFIG_SYSLOG_ENABLE is not set +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +CONFIG_MM_MULTIHEAP=y +CONFIG_MM_KERNEL_HEAP=y +CONFIG_MM_KERNEL_HEAPSIZE=8192 +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_GRAN is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +# CONFIG_BUILTIN is not set +# CONFIG_PIC is not set +CONFIG_SYMTAB_ORDEREDBYNAME=y + +# +# Library Routines +# + +# +# Standard C Library Options +# +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set + +# +# Non-standard Library Support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_WORKPRIORITY=192 +CONFIG_SCHED_WORKPERIOD=50000 +CONFIG_SCHED_WORKSTACKSIZE=2048 +# CONFIG_SCHED_LPWORK is not set +# CONFIG_SCHED_USRWORK is not set +# CONFIG_LIB_KBDCODEC is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MODBUS is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POLL is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +CONFIG_NSH_DISABLE_DD=y +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_KILL is not set +CONFIG_NSH_DISABLE_LOSETUP=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +CONFIG_NSH_DISABLE_MKFATFS=y +# CONFIG_NSH_DISABLE_MKFIFO is not set +CONFIG_NSH_DISABLE_MKRD=y +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_NSFMOUNT is not set +CONFIG_NSH_DISABLE_PS=y +# CONFIG_NSH_DISABLE_PING is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=80 +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_ROMFSETC is not set +CONFIG_NSH_CONSOLE=y + +# +# USB Trace Support +# +# CONFIG_NSH_CONDEV is not set +# CONFIG_NSH_ARCHINIT is not set + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card +# +# CONFIG_SYSTEM_SDCARD is not set + +# +# Sysinfo +# +# CONFIG_SYSTEM_SYSINFO is not set + +# +# USB Monitor +# diff --git a/nuttx/configs/open1788/knsh/setenv.sh b/nuttx/configs/open1788/knsh/setenv.sh new file mode 100755 index 000000000..e8afd7c91 --- /dev/null +++ b/nuttx/configs/open1788/knsh/setenv.sh @@ -0,0 +1,73 @@ +#!/bin/bash +# configs/open1788/knsh/setenv.sh +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# The Olimex-lpc1766stk/tools directory +export LPCTOOL_DIR="${WD}/configs/open1788/tools" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/open1788/scripts/kernel-space.ld b/nuttx/configs/open1788/scripts/kernel-space.ld new file mode 100755 index 000000000..0d145ffea --- /dev/null +++ b/nuttx/configs/open1788/scripts/kernel-space.ld @@ -0,0 +1,134 @@ +/**************************************************************************** + * configs/open1788/scripts/kernel-space.ld + * + * Copyright (C) 2011, 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. + * + ****************************************************************************/ + +/* The AT91SAM3U-4 has 256Kb of FLASH beginning at address 0x0008:0000, + * 32Kb of SRAM beginning at address 0x2000:0000, and 16Kb of SRAM beginning + * at address 0x2008:000 (used only for heap). 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 64Kb of + * FLASH and 4Kb of SRAM. That, of course, can be optimized as needed (See + * also configs/open1788/scripts/kernel.ld). + */ + +MEMORY +{ + /* 256Kb FLASH */ + + kflash (rx) : ORIGIN = 0x00080000, LENGTH = 64K + uflash (rx) : ORIGIN = 0x00090000, LENGTH = 192K + + /* 32Kb SRAM */ + + ksram (rwx) : ORIGIN = 0x20000000, LENGTH = 4K + usram (rwx) : ORIGIN = 0x20001000, LENGTH = 28K + + /* 16Kb SRAM */ + + sram2 (rwx) : ORIGIN = 0x20080000, LENGTH = 16K +} + +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/open1788/scripts/user-space.ld b/nuttx/configs/open1788/scripts/user-space.ld new file mode 100644 index 000000000..49c0b8728 --- /dev/null +++ b/nuttx/configs/open1788/scripts/user-space.ld @@ -0,0 +1,153 @@ +/**************************************************************************** + * configs/open1788/scripts/user-space.ld + * + * Copyright (C) 2011, 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. + * + ****************************************************************************/ + +/* The LPC1788 has 512Kb of FLASH beginning at address 0x0000:0000 and + * 96Kb of total SRAM: 64Kb of SRAM in the CPU block beginning at address + * 0x10000000 and 32Kb of Peripheral SRAM in two banks, 8Kb at addresses + * 0x20000000 bank0 first and 8kb at 0x20002000 at bank0 second. And 16Kb + * at 0x20004000 on bank1. + * + * For MPU support, the kernel-mode NuttX section is assumed to be 64Kb of + * FLASH and 4Kb of SRAM. That, of course, can be optimized as needed (See + * also configs/open1788/scripts/kernel-space.ld). + */ + +MEMORY +{ + /* 256Kb FLASH */ + + kflash (rx) : ORIGIN = 0x00000000, LENGTH = 64K + uflash (rx) : ORIGIN = 0x00010000, LENGTH = 448K + + /* 64Kb of SRAM in the CPU block */ + + ksram (rwx) : ORIGIN = 0x20000000, LENGTH = 4K + usram (rwx) : ORIGIN = 0x20001000, LENGTH = 60K + + /* Other peripheral memory (free, nothing is linked here) */ + + ahbram8_b0a(rwx) : ORIGIN = 0x20000000, LENGTH = 8K + ahbram8_b0b(rwx) : ORIGIN = 0x20002000, LENGTH = 8K + ahbram16(rwx) : ORIGIN = 0x20004000, LENGTH = 16K +} + +/* Make sure that the critical memory management functions are in user-space. + * Currently, the plan is that the 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/open1788/src/Makefile b/nuttx/configs/open1788/src/Makefile index be18b28f9..e00bdf170 100644 --- a/nuttx/configs/open1788/src/Makefile +++ b/nuttx/configs/open1788/src/Makefile @@ -35,50 +35,52 @@ -include $(TOPDIR)/Make.defs -CFLAGS += -I$(TOPDIR)/sched +CFLAGS += -I$(TOPDIR)/sched -ASRCS = -CSRCS = lpc17_boardinitialize.c +ASRCS = +CSRCS = lpc17_boardinitialize.c ifeq ($(CONFIG_LPC17_EMC_NOR),y) -CSRCS += lpc17_norinitialize.c + CSRCS += lpc17_norinitialize.c endif ifeq ($(CONFIG_LPC17_EMC_NAND),y) -CSRCS += lpc17_nandinitialize.c + CSRCS += lpc17_nandinitialize.c endif ifeq ($(CONFIG_LPC17_EMC_SDRM),y) -CSRCS += lpc17_sdraminitialize.c + CSRCS += lpc17_sdraminitialize.c endif -ifeq ($(CONFIG_NSH_ARCHINIT),y) -CSRCS += lpc17_nsh.c +ifeq ($(CONFIG_NSH_LIBRARY),y) + CSRCS += lpc17_nsh.c endif ifeq ($(CONFIG_ARCH_LEDS),y) -CSRCS += lpc17_autoleds.c + CSRCS += lpc17_autoleds.c else -CSRCS += lpc17_userleds.c + CSRCS += lpc17_userleds.c endif ifeq ($(CONFIG_ARCH_BUTTONS),y) -CSRCS += up_buttons.c + CSRCS += lpc17_buttons.c endif -AOBJS = $(ASRCS:.S=$(OBJEXT)) -COBJS = $(CSRCS:.c=$(OBJEXT)) +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) -ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src ifeq ($(WINTOOL),y) - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" else - CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m + CFLAGS += -I$(ARCH_SRCDIR)/chip + CFLAGS += -I$(ARCH_SRCDIR)/common + CFLAGS += -I$(ARCH_SRCDIR)/armv7-m endif all: libboard$(LIBEXT) diff --git a/nuttx/configs/open1788/src/lpc17_boardinitialize.c b/nuttx/configs/open1788/src/lpc17_boardinitialize.c index 417c9ae85..2538b52b3 100644 --- a/nuttx/configs/open1788/src/lpc17_boardinitialize.c +++ b/nuttx/configs/open1788/src/lpc17_boardinitialize.c @@ -107,3 +107,29 @@ void lpc17_boardinitialize(void) up_ledinit(); #endif } +/**************************************************************************** + * Name: board_initialize + * + * Description: + * If CONFIG_BOARD_INITIALIZE is selected, then an additional + * initialization call will be performed in the boot-up sequence to a + * function called board_initialize(). board_initialize() will be + * called immediately after up_intiialize() is called and just before the + * initial application is started. This additional initialization phase + * may be used, for example, to initialize board-specific device drivers. + * + ****************************************************************************/ + +#ifdef CONFIG_BOARD_INITIALIZE +void board_initialize(void) +{ + /* Perform NSH initialization here instead of from the NSH. This + * alternative NSH initialization is necessary when NSH is ran in user-space + * but the initialization function must run in kernel space. + */ + +#if defined(CONFIG_NSH_LIBRARY) && !defined(CONFIG_NSH_ARCHINIT) + (void)nsh_archinitialize(); +#endif +} +#endif diff --git a/nuttx/configs/open1788/src/lpc17_buttons.c b/nuttx/configs/open1788/src/lpc17_buttons.c index 38e432ee0..a203b67fb 100644 --- a/nuttx/configs/open1788/src/lpc17_buttons.c +++ b/nuttx/configs/open1788/src/lpc17_buttons.c @@ -59,14 +59,33 @@ /**************************************************************************** * Private Data ****************************************************************************/ +/* The Open1788 supports several buttons. All will read "1" when open and "0" + * when closed + * + * USER1 -- Connected to P4[26] + * USER2 -- Connected to P2[22] + * USER3 -- Connected to P0[10] + * + * And a Joystick + * + * JOY_A -- Connected to P2[25] + * JOY_B -- Connected to P2[26] + * JOY_C -- Connected to P2[23] + * JOY_D -- Connected to P2[19] + * JOY_CTR -- Connected to P0[14] + * + * The switches are all connected to ground and should be pulled up and sensed + * with a value of '0' when closed. + */ + /* Pin configuration for each Open1788 button. This array is indexed by * the BUTTON_* and JOYSTICK_* definitions in board.h */ static const lpc17_pinset_t g_buttoncfg[BOARD_NUM_BUTTONS] = { - GPIO_USER1, GPIO_USER2, GPIO_WAKEUP, GPIO_USER3, - GPIO_JOY_A, GPIO_JOY_B, GPIO_JOY_C, GPIO_JOY_D, GPIO_JOY_CTR + GPIO_USER1, GPIO_USER2, GPIO_USER3, GPIO_JOY_A, + GPIO_JOY_B, GPIO_JOY_C, GPIO_JOY_D, GPIO_JOY_CTR }; /* This array defines all of the interupt handlers current attached to diff --git a/nuttx/configs/open1788/src/lpc17_nsh.c b/nuttx/configs/open1788/src/lpc17_nsh.c index a8b95a6d1..189dfc5f6 100644 --- a/nuttx/configs/open1788/src/lpc17_nsh.c +++ b/nuttx/configs/open1788/src/lpc17_nsh.c @@ -122,13 +122,13 @@ /* Debug ********************************************************************/ #ifdef CONFIG_CPP_HAVE_VARARGS -# ifdef CONFIG_DEBUG +# if defined(CONFIG_DEBUG) || !defined(CONFIG_NSH_ARCHINIT) # define message(...) lowsyslog(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif #else -# ifdef CONFIG_DEBUG +# if defined(CONFIG_DEBUG) || !defined(CONFIG_NSH_ARCHINIT) # define message lowsyslog # else # define message printf @@ -291,7 +291,14 @@ static int nsh_usbhostinitialize(void) * Name: nsh_archinitialize * * Description: - * Perform architecture specific initialization + * Perform architecture specific initialization for NSH. + * + * CONFIG_NSH_ARCHINIT=y : + * Called from the NSH library + * + * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, && + * CONFIG_NSH_ARCHINIT=n: + * Called from board_initialize(). * ****************************************************************************/ diff --git a/nuttx/configs/open1788/src/open1788.h b/nuttx/configs/open1788/src/open1788.h index 52da9a815..f5c4cdcd6 100644 --- a/nuttx/configs/open1788/src/open1788.h +++ b/nuttx/configs/open1788/src/open1788.h @@ -163,6 +163,25 @@ void lpc17_nand_initialize(void); #endif #endif /* CONFIG_LPC17_EMC */ +/**************************************************************************** + * Name: nsh_archinitialize + * + * Description: + * Perform architecture specific initialization for NSH. + * + * CONFIG_NSH_ARCHINIT=y : + * Called from the NSH library + * + * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, && + * CONFIG_NSH_ARCHINIT=n: + * Called from board_initialize(). + * + ****************************************************************************/ + +#ifdef CONFIG_NSH_LIBRARY +int nsh_archinitialize(void); +#endif + #endif /* __ASSEMBLY__ */ #endif /* _CONFIGS_OPEN1788_SRC_OPEN1788_H */ -- cgit v1.2.3