From dfbc56054f377761c50a1a7453ed00a228fa9766 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 28 Dec 2012 23:40:54 +0000 Subject: Add board support at configs/zp214xpa for the The0.net ZP213X/4XPA board with the LPC2148; Add configurations sim/nxlines. convert mcu123-lpc214x/nsh to use the kconfig-frontends. git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5465 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/Kconfig | 14 +- nuttx/configs/README.txt | 5 + nuttx/configs/mcu123-lpc214x/README.txt | 18 +- nuttx/configs/mcu123-lpc214x/nsh/appconfig | 44 -- nuttx/configs/mcu123-lpc214x/nsh/defconfig | 760 ++++++++++++++++--------- nuttx/configs/mcu123-lpc214x/scripts/ld.script | 6 +- nuttx/configs/sim/nxlines/Make.defs | 107 ++++ nuttx/configs/sim/nxlines/defconfig | 591 +++++++++++++++++++ nuttx/configs/sim/nxlines/setenv.sh | 53 ++ nuttx/configs/zp214xpa/Kconfig | 7 + nuttx/configs/zp214xpa/README.txt | 136 +++++ nuttx/configs/zp214xpa/include/board.h | 68 +++ nuttx/configs/zp214xpa/nsh/Make.defs | 128 +++++ nuttx/configs/zp214xpa/nsh/defconfig | 574 +++++++++++++++++++ nuttx/configs/zp214xpa/nsh/setenv.sh | 65 +++ nuttx/configs/zp214xpa/scripts/ld.script | 120 ++++ nuttx/configs/zp214xpa/src/Makefile | 84 +++ 17 files changed, 2474 insertions(+), 306 deletions(-) delete mode 100644 nuttx/configs/mcu123-lpc214x/nsh/appconfig create mode 100644 nuttx/configs/sim/nxlines/Make.defs create mode 100644 nuttx/configs/sim/nxlines/defconfig create mode 100755 nuttx/configs/sim/nxlines/setenv.sh create mode 100644 nuttx/configs/zp214xpa/Kconfig create mode 100644 nuttx/configs/zp214xpa/README.txt create mode 100644 nuttx/configs/zp214xpa/include/board.h create mode 100644 nuttx/configs/zp214xpa/nsh/Make.defs create mode 100644 nuttx/configs/zp214xpa/nsh/defconfig create mode 100755 nuttx/configs/zp214xpa/nsh/setenv.sh create mode 100644 nuttx/configs/zp214xpa/scripts/ld.script create mode 100644 nuttx/configs/zp214xpa/src/Makefile (limited to 'nuttx/configs') diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig index bba1444c4..cda5aa7bc 100644 --- a/nuttx/configs/Kconfig +++ b/nuttx/configs/Kconfig @@ -619,6 +619,14 @@ config ARCH_BOARD_Z8F64200100KIT development kit, Z8F6423 part, and the Zilog ZDS-II Windows command line tools. The development environment is Cygwin under WinXP. +config ARCH_BOARD_ZP214XPA + bool "The0.net LPC2148 Development Board" + depends on ARCH_CHIP_LPC2148 + ---help--- + This port is for the NXP LPC2148 as provided on the The0.net + ZPA213X/4XPA development board. Includes support for the + UG-2864AMBAG01 OLED also from The0.net + config ARCH_BOARD_SIM bool "User mode simulation" depends on ARCH_SIM @@ -700,6 +708,7 @@ config ARCH_BOARD default "z80sim" if ARCH_BOARD_Z80SIM default "z8encore000zco" if ARCH_BOARD_Z8ENCORE000ZCO default "z8f64200100kit" if ARCH_BOARD_Z8F64200100KIT + default "zp214xpa" if ARCH_BOARD_ZP214XPA default "sim" if ARCH_BOARD_SIM default "" if ARCH_BOARD_CUSTOM @@ -709,7 +718,7 @@ config ARCH_HAVE_LEDS bool config ARCH_LEDS - bool "Board LEDs support" + bool "Board LED support" default y depends on ARCH_HAVE_LEDS ---help--- @@ -935,6 +944,9 @@ endif if ARCH_BOARD_Z8F64200100KIT source "configs/z8f64200100kit/Kconfig" endif +if ARCH_BOARD_ZP214XPA +source "configs/zp214xpa/Kconfig" +endif if ARCH_BOARD_SIM source "configs/sim/Kconfig" endif diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 21aace2af..4e9bcca14 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -1936,6 +1936,11 @@ configs/z8f64200100kit development kit, Z8F6423 part, and the Zilog ZDS-II Windows command line tools. The development environment is Cygwin under WinXP. +configs/zp214xpa + This port is for the NXP LPC2148 as provided on the The0.net + ZPA213X/4XPA development board. Includes support for the + UG-2864AMBAG01 OLED also from The0.net + Configuring NuttX ^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/mcu123-lpc214x/README.txt b/nuttx/configs/mcu123-lpc214x/README.txt index 435f8647d..4c7c608b7 100644 --- a/nuttx/configs/mcu123-lpc214x/README.txt +++ b/nuttx/configs/mcu123-lpc214x/README.txt @@ -349,8 +349,22 @@ nsh: Configures the NuttShell (nsh) located at examples/nsh. The Configuration enables only the serial NSH interfaces. - Default toolchain: Buildroot - Output format: ELF and binary + NOTES: + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Default platform/toolchain: + + CONFIG_HOST_LINUX=y : Windows + CONFIG_ARM_TOOLCHAIN_GNU_EABI=y : Buildroot (arm-nuttx-elf-gcc) + CONFIG_RAW_BINARY=y : Output formats: ELF and raw binary ostest: ------- diff --git a/nuttx/configs/mcu123-lpc214x/nsh/appconfig b/nuttx/configs/mcu123-lpc214x/nsh/appconfig deleted file mode 100644 index f8e2d5165..000000000 --- a/nuttx/configs/mcu123-lpc214x/nsh/appconfig +++ /dev/null @@ -1,44 +0,0 @@ -############################################################################ -# configs/mcu123-lpc214x/nsh/appconfig -# -# Copyright (C) 2011-2012 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. -# -############################################################################ - -# Path to example in apps/examples containing the user_start entry point - -CONFIGURED_APPS += examples/nsh - -# The NSH library - -CONFIGURED_APPS += system/readline -CONFIGURED_APPS += nshlib - diff --git a/nuttx/configs/mcu123-lpc214x/nsh/defconfig b/nuttx/configs/mcu123-lpc214x/nsh/defconfig index a8a53a340..6ae163386 100644 --- a/nuttx/configs/mcu123-lpc214x/nsh/defconfig +++ b/nuttx/configs/mcu123-lpc214x/nsh/defconfig @@ -1,169 +1,207 @@ -############################################################################ -# configs/mcu123-lpc214x/nsh/defconfig -# -# Copyright (C) 2008-2010, 2012 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. -# -############################################################################ -# -# Architecture selection # -CONFIG_ARCH="arm" +# 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 is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y + +# +# 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_LM3S is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +CONFIG_ARCH_CHIP_LPC214X=y +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX 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_ARM7TDMI=y +CONFIG_ARCH_FAMILY="arm" CONFIG_ARCH_CHIP="lpc214x" -CONFIG_ARCH_CHIP_LPC2148=y -CONFIG_ARCH_BOARD="mcu123-lpc214x" -CONFIG_ARCH_BOARD_MCU123=y +CONFIG_ARCH_HAVE_LOWVECTORS=y +# CONFIG_ARCH_LOWVECTORS is not set CONFIG_BOARD_LOOPSPERMSEC=3270 -CONFIG_ARCH_LEDS=y -CONFIG_DRAM_SIZE=32768 -CONFIG_DRAM_START=0x40000000 -CONFIG_ARCH_INTERRUPTSTACK=0 -CONFIG_ARCH_STACKDUMP=y +# CONFIG_ARCH_CALIBRATION is not set # -# LPC2148 specific chip initialization +# ARM Configuration Options +# +# CONFIG_ARM_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARM_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARM_TOOLCHAIN_GNU_EABI=y + +# +# LPC214x Configuration Options +# +CONFIG_ARCH_CHIP_LPC2148=y + # -CONFIG_EXTMEM_MODE=n -CONFIG_RAM_MODE=n +# LPC214x Initialization Options +# +# CONFIG_EXTMEM_MODE is not set +# CONFIG_RAM_MODE is not set +CONFIG_DEFAULT_MODE=y CONFIG_CODE_BASE=0x00000000 CONFIG_PLL_SETUP=y CONFIG_MAM_SETUP=y CONFIG_APBDIV_SETUP=y -CONFIG_EMC_SETUP=n -CONFIG_BCFG0_SETUP=n -CONFIG_BCFG1_SETUP=n -CONFIG_BCFG2_SETUP=n -CONFIG_BCFG3_SETUP=n +CONFIG_APBDIV_VALUE=1 +# CONFIG_EMC_SETUP is not set +# CONFIG_BCFG0_SETUP is not set +# CONFIG_BCFG1_SETUP is not set +# CONFIG_BCFG2_SETUP is not set +# CONFIG_BCFG3_SETUP is not set CONFIG_ADC_SETUP=y # -# LPC214X specific device driver settings +# LPC214x Peripheral Support # -CONFIG_UART0_SERIAL_CONSOLE=y -CONFIG_UART1_SERIAL_CONSOLE=n -CONFIG_UART0_TXBUFSIZE=256 -CONFIG_UART1_TXBUFSIZE=256 -CONFIG_UART0_RXBUFSIZE=256 -CONFIG_UART1_RXBUFSIZE=256 -CONFIG_UART0_BAUD=38400 -CONFIG_UART1_BAUD=38400 -CONFIG_UART0_BITS=8 -CONFIG_UART1_BITS=8 -CONFIG_UART0_PARITY=0 -CONFIG_UART1_PARITY=0 -CONFIG_UART0_2STOP=0 -CONFIG_UART1_2STOP=0 +CONFIG_LPC214X_UART0=y +CONFIG_LPC214X_UART1=y +# CONFIG_LPC214x_FIO is not set +# CONFIG_SDIO_DMA is not set +# CONFIG_SDIO_WIDTH_D1_ONLY is not set # -# General build options +# Architecture Options # -CONFIG_RRLOAD_BINARY=n -CONFIG_INTELHEX_BINARY=n -CONFIG_MOTOROLA_SREC=n -CONFIG_RAW_BINARY=y +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +# CONFIG_ARCH_IRQPRIO is not set +# CONFIG_CUSTOM_STACK is not set +# CONFIG_ADDRENV is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set # -# General OS setup +# Board Settings # -CONFIG_USER_ENTRYPOINT="nsh_main" -CONFIG_DEBUG=n -CONFIG_DEBUG_VERBOSE=n -CONFIG_DEBUG_SYMBOLS=n -CONFIG_MM_REGIONS=1 -CONFIG_ARCH_LOWPUTC=y +CONFIG_DRAM_START=0x40000000 +CONFIG_DRAM_SIZE=32768 +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_MCU123=y +# CONFIG_ARCH_BOARD_ZP214XPA is not set +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="mcu123-lpc214x" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_NSH_MMCSDMINOR=0 +CONFIG_NSH_MMCSDSLOTNO=0 +CONFIG_NSH_MMCSDSPIPORTNO=1 + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 CONFIG_RR_INTERVAL=0 -CONFIG_SCHED_INSTRUMENTATION=n +# CONFIG_SCHED_INSTRUMENTATION is not set CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set CONFIG_START_YEAR=2008 CONFIG_START_MONTH=10 CONFIG_START_DAY=1 -CONFIG_JULIAN_TIME=n CONFIG_DEV_CONSOLE=y -CONFIG_DEV_LOWCONSOLE=n -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=0 -CONFIG_FDCLONE_DISABLE=n -CONFIG_FDCLONE_STDIO=n +# 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_NXFLAT=n - -# -# The following can be used to disable categories of -# APIs supported by the OS. If the compiler supports -# weak functions, then it should not be necessary to -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=n -CONFIG_DISABLE_PTHREAD=n -CONFIG_DISABLE_SIGNALS=n -CONFIG_DISABLE_MQUEUE=n -CONFIG_DISABLE_MOUNTPOINT=n -CONFIG_DISABLE_ENVIRON=n +# CONFIG_SCHED_WORKQUEUE is not set +# CONFIG_SCHED_WAITPID 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_MOUNTPOINT is not set +# CONFIG_DISABLE_ENVIRON is not set CONFIG_DISABLE_POLL=y -# -# Misc libc settings -# -CONFIG_NOPRINTF_FIELDWIDTH=n - -# -# Allow for architecture optimized implementations -# -# The architecture can provide optimized versions of the -# following to improve system performance -# -CONFIG_ARCH_MEMCPY=n -CONFIG_ARCH_MEMCMP=n -CONFIG_ARCH_MEMMOVE=n -CONFIG_ARCH_MEMSET=n -CONFIG_ARCH_STRCMP=n -CONFIG_ARCH_STRCPY=n -CONFIG_ARCH_STRNCPY=n -CONFIG_ARCH_STRLEN=n -CONFIG_ARCH_STRNLEN=n -CONFIG_ARCH_BZERO=n - # # Sizes of configurable things (0 disables) # @@ -173,8 +211,6 @@ CONFIG_NPTHREAD_KEYS=4 CONFIG_NFILE_DESCRIPTORS=8 CONFIG_NFILE_STREAMS=8 CONFIG_NAME_MAX=32 -CONFIG_STDIO_BUFFER_SIZE=256 -CONFIG_NUNGET_CHARS=2 CONFIG_PREALLOC_MQ_MSGS=4 CONFIG_MQ_MAXMSGSIZE=32 CONFIG_MAX_WDOGPARMS=2 @@ -182,168 +218,380 @@ CONFIG_PREALLOC_WDOGS=4 CONFIG_PREALLOC_TIMERS=4 # -# Filesystem configuration +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=2048 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +CONFIG_SPI=y +# CONFIG_SPI_OWNBUS is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_SPI_CMDDATA is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# 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_SPI=y +CONFIG_MMCSD_SPICLOCK=20000000 +# CONFIG_MMCSD_SDIO is not set +# CONFIG_SDIO_MUXBUS is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# 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_ARCH_HAVE_UART1=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_UART0_SERIAL_CONSOLE=y +# CONFIG_UART1_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# UART0 Configuration +# +CONFIG_UART0_RXBUFSIZE=256 +CONFIG_UART0_TXBUFSIZE=256 +CONFIG_UART0_BAUD=38400 +CONFIG_UART0_BITS=8 +CONFIG_UART0_PARITY=0 +CONFIG_UART0_2STOP=0 + +# +# UART1 Configuration +# +CONFIG_UART1_RXBUFSIZE=256 +CONFIG_UART1_TXBUFSIZE=256 +CONFIG_UART1_BAUD=38400 +CONFIG_UART1_BITS=8 +CONFIG_UART1_PARITY=0 +CONFIG_UART1_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_FS_FAT=y CONFIG_FAT_LCNAMES=y CONFIG_FAT_LFN=y CONFIG_FAT_MAXFNAME=32 -CONFIG_FS_NXFFS=n -CONFIG_FS_ROMFS=n +# CONFIG_FS_FATTIME is not set +# CONFIG_FAT_DMAMEMORY is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set # -# Maintain legacy build behavior (revisit) +# System Logging # +# CONFIG_SYSLOG is not set -CONFIG_MMCSD=y -CONFIG_MMCSD_SPI=y -CONFIG_MMCSD_SDIO=y +# +# Graphics Support +# +# CONFIG_NX is not set # -# SPI-based MMC/SD driver +# Memory Management # -CONFIG_MMCSD_NSLOTS=1 -CONFIG_MMCSD_READONLY=n -#CONFIG_MMCSD_SPICLOCK=20000000 +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# CONFIG_GRAN is not set # -# SPI-based MMC/SD driver +# Binary Formats # -CONFIG_MMCSD_NSLOTS=1 -CONFIG_MMCSD_READONLY=n +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set # -# TCP/IP and UDP support via uIP +# Library Routines # -CONFIG_NET=n -CONFIG_NET_IPv6=n -CONFIG_NSOCKET_DESCRIPTORS=0 -CONFIG_NET_SOCKOPTS=y -CONFIG_NET_BUFSIZE=420 -CONFIG_NET_TCP=n -CONFIG_NET_TCP_CONNS=40 -CONFIG_NET_MAX_LISTENPORTS=40 -CONFIG_NET_UDP=n -CONFIG_NET_UDP_CHECKSUMS=y -#CONFIG_NET_UDP_CONNS=10 -CONFIG_NET_ICMP=n -CONFIG_NET_ICMP_PING=n -#CONFIG_NET_PINGADDRCONF=0 -CONFIG_NET_STATISTICS=y -#CONFIG_NET_RECEIVE_WINDOW= -#CONFIG_NET_ARPTAB_SIZE=8 -CONFIG_NET_BROADCAST=n # -# UIP Network Utilities +# Standard C Library Options # -CONFIG_NET_DHCP_LIGHT=n -CONFIG_NET_RESOLV_ENTRIES=4 +CONFIG_STDIO_BUFFER_SIZE=256 +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_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 # -# USB Device Configuration +# Non-standard Helper Functions # -CONFIG_USBDEV=n -CONFIG_USBDEV_ISOCHRONOUS=n -CONFIG_USBDEV_DUALSPEED=n -CONFIG_USBDEV_SELFPOWERED=y -CONFIG_USBDEV_REMOTEWAKEUP=n -CONFIG_USBDEV_MAXPOWER=100 -CONFIG_USBDEV_TRACE=n -CONFIG_USBDEV_TRACE_NRECORDS=128 +CONFIG_LIB_KBDCODEC=y # -# LPC214X USB Configuration +# Basic CXX Support # -CONFIG_LPC214X_USBDEV_FRAME_INTERRUPT=n -CONFIG_LPC214X_USBDEV_EPFAST_INTERRUPT=n -CONFIG_LPC214X_USBDEV_DMA=n -CONFIG_LPC214X_USBDEV_NDMADESCRIPTORS=0 -CONFIG_LPC214X_USBDEV_DMAINTMASK=0 +# CONFIG_C99_BOOL8 is not set +# CONFIG_HAVE_CXX is not set # -# USB Serial Device Configuration +# Application Configuration # -CONFIG_PL2303=n -CONFIG_PL2303_EPINTIN=1 -CONFIG_PL2303_EPBULKOUT=2 -CONFIG_PL2303_EPBULKIN=5 -CONFIG_PL2303_NWRREQS=4 -CONFIG_PL2303_NRDREQS=4 -CONFIG_PL2303_VENDORID=0x067b -CONFIG_PL2303_PRODUCTID=0x2303 -CONFIG_PL2303_VENDORSTR="Nuttx" -CONFIG_PL2303_PRODUCTSTR="USBdev Serial" -CONFIG_PL2303_RXBUFSIZE=512 -CONFIG_PL2303_TXBUFSIZE=512 # -# USB Storage Device Configuration +# Built-In Applications +# +# CONFIG_BUILTIN is not set + # -CONFIG_USBMSC=n -CONFIG_USBMSC_EP0MAXPACKET=64 -CONFIG_USBMSC_EPBULKOUT=2 -CONFIG_USBMSC_EPBULKIN=5 -CONFIG_USBMSC_NRDREQS=2 -CONFIG_USBMSC_NWRREQS=2 -CONFIG_USBMSC_BULKINREQLEN=256 -CONFIG_USBMSC_BULKOUTREQLEN=256 -CONFIG_USBMSC_VENDORID=0x584e -CONFIG_USBMSC_VENDORSTR="NuttX" -CONFIG_USBMSC_PRODUCTID=0x5342 -CONFIG_USBMSC_PRODUCTSTR="USBdev Storage" -CONFIG_USBMSC_VERSIONNO=0x0399 -CONFIG_USBMSC_REMOVABLE=y +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM 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_NETTEST 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_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 +# CONFIG_EXAMPLES_WLAN is not set # -# Settings for examples/ostest -CONFIG_EXAMPLES_OSTEST_LOOPS=1 -CONFIG_EXAMPLES_OSTEST_STACKSIZE=4096 -CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 +# Interpreters +# # -# Settings for apps/nshlib +# 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 + +# +# ModBus +# + +# +# 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 is not set +# 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 is not set +# 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 is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# 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 is not set +# 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_STRERROR=n CONFIG_NSH_LINELEN=64 CONFIG_NSH_NESTDEPTH=3 -CONFIG_NSH_DISABLESCRIPT=n -CONFIG_NSH_DISABLEBG=n -CONFIG_NSH_ROMFSETC=n +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set CONFIG_NSH_CONSOLE=y -CONFIG_NSH_TELNET=n +# CONFIG_NSH_CONDEV is not set CONFIG_NSH_ARCHINIT=y -CONFIG_NSH_IOBUFFER_SIZE=512 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=n -CONFIG_NSH_IPADDR=0x0a000002 -CONFIG_NSH_DRIPADDR=0x0a000001 -CONFIG_NSH_NETMASK=0xffffff00 -CONFIG_NSH_ROMFSMOUNTPT="/etc" -CONFIG_NSH_INITSCRIPT="init.d/rcS" -CONFIG_NSH_ROMFSDEVNO=0 -CONFIG_NSH_ROMFSSECTSIZE=64 -CONFIG_NSH_FATDEVNO=1 -CONFIG_NSH_FATSECTSIZE=512 -CONFIG_NSH_FATNSECTORS=1024 -CONFIG_NSH_FATMOUNTPT="/tmp" - -# -# Architecture-specific NSH options -CONFIG_NSH_MMCSDSPIPORTNO=1 -CONFIG_NSH_MMCSDSLOTNO=0 -CONFIG_NSH_MMCSDMINOR=0 # -# Stack and heap information +# NxWidgets/NxWM # -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n -CONFIG_IDLETHREAD_STACKSIZE=2048 -CONFIG_USERMAIN_STACKSIZE=2048 -CONFIG_PTHREAD_STACK_MIN=256 -CONFIG_PTHREAD_STACK_DEFAULT=2048 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= + +# +# 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 diff --git a/nuttx/configs/mcu123-lpc214x/scripts/ld.script b/nuttx/configs/mcu123-lpc214x/scripts/ld.script index 8ce83748f..bc025dfb7 100644 --- a/nuttx/configs/mcu123-lpc214x/scripts/ld.script +++ b/nuttx/configs/mcu123-lpc214x/scripts/ld.script @@ -35,12 +35,12 @@ /* FLASH: * The lpc2148 has 512Kb of non-volatile memory beginning at address - * 0x00000000. The OS entry point is via the reset vector at address - * 0x00000000 (default MEMMAP mode assumed) + * 0x0000:0000. The OS entry point is via the reset vector at address + * 0x0000:0000 (default MEMMAP mode assumed) * * SRAM: * The lpc2148 has 32Kb of on-chip static RAM beginning at address - * 0x40000000. The .data section will be relocated from _eronly + * 0x4000:0000. The .data section will be relocated from _eronly * to _sdata at boot time. */ diff --git a/nuttx/configs/sim/nxlines/Make.defs b/nuttx/configs/sim/nxlines/Make.defs new file mode 100644 index 000000000..18c8bf537 --- /dev/null +++ b/nuttx/configs/sim/nxlines/Make.defs @@ -0,0 +1,107 @@ +############################################################################ +# configs/sim/nxlines/Make.defs +# +# Copyright (C) 2012 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 + +HOSTOS = ${shell uname -o 2>/dev/null || echo "Other"} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = -O2 +endif + +ARCHCPUFLAGS = -fno-builtin +ARCHCPUFLAGSXX = -fno-builtin -fno-exceptions -fno-rtti +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +ARCHDEFINES = +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include +ARCHINCLUDESXX = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx +ARCHSCRIPT = + +ifeq ($(CONFIG_SIM_M32),y) + ARCHCPUFLAGS += -m32 + ARCHCPUFLAGSXX += -m32 +endif + +CROSSDEV = +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 + +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXFLAGS = $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGSXX) $(ARCHINCLUDESXX) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +OBJEXT = .o +LIBEXT = .a + +ifeq ($(HOSTOS),Cygwin) + EXEEXT = .exe +else + EXEEXT = +endif + +LDLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(LD) +CCLINKFLAGS = $(ARCHSCRIPT) # Link flags used with $(CC) +LDFLAGS = $(ARCHSCRIPT) # For backward compatibility, same as CCLINKFLAGS + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDLINKFLAGS += -g + CCLINKFLAGS += -g + LDFLAGS += -g +endif + +ifeq ($(CONFIG_SIM_M32),y) + LDLINKFLAGS += -melf_i386 + CCLINKFLAGS += -m32 + LDFLAGS += -m32 +endif + +MKDEP = $(TOPDIR)/tools/mkdeps.sh + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/sim/nxlines/defconfig b/nuttx/configs/sim/nxlines/defconfig new file mode 100644 index 000000000..c023af674 --- /dev/null +++ b/nuttx/configs/sim/nxlines/defconfig @@ -0,0 +1,591 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_HOST_LINUX is not set +# CONFIG_HOST_OSX is not set +CONFIG_HOST_WINDOWS=y +# CONFIG_HOST_OTHER is not set +# CONFIG_WINDOWS_NATIVE is not set +CONFIG_WINDOWS_CYGWIN=y +# CONFIG_WINDOWS_MSYS is not set +# CONFIG_WINDOWS_OTHER is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# 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=y + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +# CONFIG_ARCH_ARM is not set +# 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=y +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="sim" +CONFIG_BOARD_LOOPSPERMSEC= + +# +# Simulation Configuration Options +# +# CONFIG_SIM_M32 is not set +# CONFIG_SIM_WALLTIME is not set +CONFIG_SIM_FRAMEBUFFER=y +CONFIG_SIM_X11FB=y +# CONFIG_SIM_X11NOSHM is not set +CONFIG_SIM_FBHEIGHT=240 +CONFIG_SIM_FBWIDTH=480 +CONFIG_SIM_FBBPP=32 + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +# CONFIG_ARCH_IRQPRIO is not set +# CONFIG_CUSTOM_STACK is not set +# CONFIG_ADDRENV is not set +# CONFIG_ARCH_STACKDUMP is not set +# CONFIG_ENDIAN_BIG is not set + +# +# Board Settings +# +CONFIG_DRAM_START= +CONFIG_DRAM_SIZE= + +# +# 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_SIM=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="sim" + +# +# Common Board Options +# +CONFIG_NSH_MMCSDMINOR=0 + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 +CONFIG_RR_INTERVAL=0 +# CONFIG_SCHED_INSTRUMENTATION is not set +CONFIG_TASK_NAME_SIZE=32 +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2012 +CONFIG_START_MONTH=5 +CONFIG_START_DAY=1 +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_WORKQUEUE is not set +CONFIG_SCHED_WAITPID=y +# CONFIG_SCHED_ATEXIT is not set +CONFIG_SCHED_ONEXIT=y +CONFIG_SCHED_ONEXIT_MAX=1 +CONFIG_USER_ENTRYPOINT="nxlines_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +CONFIG_DISABLE_POSIX_TIMERS=y +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_DISABLE_ENVIRON is not set +CONFIG_DISABLE_POLL=y + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=16 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=16 +CONFIG_NFILE_STREAMS=16 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=32 +CONFIG_MQ_MAXMSGSIZE=48 +CONFIG_MAX_WDOGPARMS=4 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_PREALLOC_TIMERS=8 + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=8192 +CONFIG_USERMAIN_STACKSIZE=16384 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=8192 + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# 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 is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +# CONFIG_MMCSD is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# 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_STANDARD_SERIAL is not set +# 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_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_RAMMAP is not set +# CONFIG_FS_NXFFS is not set +CONFIG_FS_ROMFS=y + +# +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +CONFIG_NX=y +CONFIG_NX_NPLANES=1 +# CONFIG_NX_WRITEONLY is not set + +# +# Supported Pixel Depths +# +CONFIG_NX_DISABLE_1BPP=y +CONFIG_NX_DISABLE_2BPP=y +CONFIG_NX_DISABLE_4BPP=y +CONFIG_NX_DISABLE_8BPP=y +CONFIG_NX_DISABLE_16BPP=y +CONFIG_NX_DISABLE_24BPP=y +# CONFIG_NX_DISABLE_32BPP is not set +# CONFIG_NX_PACKEDMSFIRST is not set + +# +# Input Devices +# +CONFIG_NX_MOUSE=y +CONFIG_NX_KBD=y + +# +# Framed Window Borders +# +CONFIG_NXTK_BORDERWIDTH=4 +CONFIG_NXTK_BORDERCOLOR1=0x005a96bd +CONFIG_NXTK_BORDERCOLOR2=0x00233a49 +CONFIG_NXTK_BORDERCOLOR3=0x00f8f8f8 +# CONFIG_NXTK_AUTORAISE is not set + +# +# Font Selections +# +CONFIG_NXFONTS_CHARBITS=7 +# CONFIG_NXFONT_SANS17X22 is not set +# CONFIG_NXFONT_SANS20X26 is not set +CONFIG_NXFONT_SANS23X27=y +# CONFIG_NXFONT_SANS22X29 is not set +# CONFIG_NXFONT_SANS28X37 is not set +# CONFIG_NXFONT_SANS39X48 is not set +# CONFIG_NXFONT_SANS17X23B is not set +# CONFIG_NXFONT_SANS20X27B is not set +# CONFIG_NXFONT_SANS22X29B is not set +CONFIG_NXFONT_SANS28X37B=y +# CONFIG_NXFONT_SANS40X49B is not set +# CONFIG_NXFONT_SERIF22X29 is not set +# CONFIG_NXFONT_SERIF29X37 is not set +# CONFIG_NXFONT_SERIF38X48 is not set +# CONFIG_NXFONT_SERIF22X28B is not set +# CONFIG_NXFONT_SERIF27X38B is not set +# CONFIG_NXFONT_SERIF38X49B is not set +# CONFIG_NXCONSOLE is not set + +# +# NX Multi-user only options +# +# CONFIG_NX_MULTIUSER is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# 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_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# +CONFIG_STDIO_BUFFER_SIZE=256 +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_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 Helper Functions +# +CONFIG_LIB_KBDCODEC=y + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +# CONFIG_HAVE_CXXINITIALIZE is not set +# CONFIG_CXX_NEWLONG is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +# CONFIG_BUILTIN is not set + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_CXXTEST 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_NETTEST is not set +# CONFIG_EXAMPLES_NSH is not set +# 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=y +CONFIG_EXAMPLES_NXLINES_VPLANE=0 +CONFIG_EXAMPLES_NXLINES_DEVNO=0 +CONFIG_EXAMPLES_NXLINES_BGCOLOR=0x00006400 +CONFIG_EXAMPLES_NXLINES_LINEWIDTH=16 +CONFIG_EXAMPLES_NXLINES_LINECOLOR=0x00ffff00 +CONFIG_EXAMPLES_NXLINES_BORDERWIDTH=16 +CONFIG_EXAMPLES_NXLINES_BORDERCOLOR=0x00ffff00 +CONFIG_EXAMPLES_NXLINES_CIRCLECOLOR=0x00f5f5dc +CONFIG_EXAMPLES_NXLINES_BPP=32 +# CONFIG_EXAMPLES_NXLINES_EXTERNINIT 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_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 +# CONFIG_EXAMPLES_WLAN is not set + +# +# Interpreters +# + +# +# 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 + +# +# ModBus +# + +# +# 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 is not set +# 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 is not set +# 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 is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# 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 is not set +# 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=1024 +CONFIG_NSH_LINELEN=80 +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSMOUNTPT="/etc" +CONFIG_NSH_INITSCRIPT="init.d/rcS" +CONFIG_NSH_ROMFSDEVNO=1 +CONFIG_NSH_ROMFSSECTSIZE=64 +CONFIG_NSH_FATDEVNO=2 +CONFIG_NSH_FATSECTSIZE=512 +CONFIG_NSH_FATNSECTORS=1024 +CONFIG_NSH_FATMOUNTPT="/tmp" +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_CONDEV is not set +# CONFIG_NSH_ARCHINIT is not set + +# +# NxWidgets/NxWM +# +# CONFIG_NXWIDGETS is not set + +# +# 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 diff --git a/nuttx/configs/sim/nxlines/setenv.sh b/nuttx/configs/sim/nxlines/setenv.sh new file mode 100755 index 000000000..0722cbc2e --- /dev/null +++ b/nuttx/configs/sim/nxlines/setenv.sh @@ -0,0 +1,53 @@ +#!/bin/bash +# sim/nxlines/setenv.sh +# +# Copyright (C) 2012 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 + +#export NUTTX_BIN= +#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/zp214xpa/Kconfig b/nuttx/configs/zp214xpa/Kconfig new file mode 100644 index 000000000..d8d04ca5c --- /dev/null +++ b/nuttx/configs/zp214xpa/Kconfig @@ -0,0 +1,7 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +if ARCH_BOARD_ZP214XPA +endif diff --git a/nuttx/configs/zp214xpa/README.txt b/nuttx/configs/zp214xpa/README.txt new file mode 100644 index 000000000..6fd7bfba9 --- /dev/null +++ b/nuttx/configs/zp214xpa/README.txt @@ -0,0 +1,136 @@ +zp214xpa README FILE +==================== + +The ZP213X/4XPA board from the0.net with LPC2148 installed. +Includes support for the UG-2864AMBAG01 OLED from The0.net. + +Contents +======== + + o MCU Connections + o Serial Console + o Configurations + +MCU Connections: +================ + +Module Socket: +-------------- +PIN NAME PIN NAME + 1 VBAT 56 VCC + 2 3V3 55 Vusb + 3 VREF 54 3V3 + 4 P0.0 53 RESET + 5 P0.1 52 P1.31 + 6 P0.2 51 P1.30 + 7 P0.3 50 P1.29 + 8 P0.4 49 P1.28 + 9 P0.5 48 P1.27 +10 P0.6 47 P1.26 +11 P0.7 46 P1.25 +12 P0.8 45 P1.24 +13 P0.9 44 P1.23 +14 P0.10 43 P1.22 +15 P0.11 42 P1.21 +16 P0.12 41 P1.20 +17 P0.13 40 P1.19 +18 P0.14 39 P1.18 +19 P0.15 38 P1.17 +20 P0.16 37 P1.16 +21 P0.17 36 P0.31 +22 P0.18 35 P0.30 +23 P0.19 34 P0.29 +24 P0.20 33 P0.28 +25 P0.21 32 P0.27 +26 P0.22 31 P0.26 +27 P0.23 30 P0.25 +28 GND 29 GND + +JTAG Debug: +----------- +PIN NAME PIN NAME + 1 VCC1 2 3V3 + 3 P1.31 NTRST 4 GND + 5 P1.28 TDI 6 GND + 7 P1.30 TMS 8 GND + 9 P1.29 TCK 10 GND +11 P1.26 RTCK 12 GND +13 P1.27 TDO 14 GND +15 RESET NRTS 16 GND +17 N/C NC0 18 GND +19 N/C NC1 20 GND + +Z28160 Net Module: +------------------ +PIN NAME PIN NAME + 1 P0.7 /CS 10 3V3 VCC + 2 P0.4 SCK 9 P1.24 RST + 3 P0.6 SI 8 N/C CLKOUT + 4 P0.5 SO 7 INT P1.25 + 5 GND 6 N/C WOL + +SPI LCD: +-------- +PIN NAME + 1 3V3 3V3 + 2 VCC 5V + 3 P0.18 RESET(DO) + 4 P0.19 DI + 5 P0.20 CS + 6 P0.17 SCK + 7 P0.23 A0(RESET) + 8 N/C LED- + 9 N/C LED+(BL) +10 GND GND + +USB Interface: +-------------- +Vusb, P0.26, P0.27 + +Serial Console: +=============== + +Both UART0 and UART1 are always enabled. UART0 is configured to be the +serial console in these configurations. + +P0.0/TXD0/PWM1 Module Socket, Pin 4 +P0.1/RxD0/PWM3/EINT0 Module Socket, Pin 5 + +P0.8/TXD1/PWM4/AD1.1 Module Socket, Pin 12 +P0.9/RxD1/PWM6/EINT3 Module Socket, Pin 13 + +Configurations: +=============== + +Each NXP LPC214x configuration is maintained in a sudirectory and +can be selected as follow: + + cd tools + ./configure.sh zp214xpa/ + cd - + . ./setenv.sh + +Where is one of the following: + +nsh: +---- + + Configures the NuttShell (nsh) located at examples/nsh. The + Configuration enables only the serial NSH interfaces. + + NOTES: + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Default platform/toolchain: + + CONFIG_HOST_LINUX=y : Windows + CONFIG_ARM_TOOLCHAIN_GNU_EABI=y : Buildroot (arm-nuttx-elf-gcc) + CONFIG_RAW_BINARY=y : Output formats: ELF and raw binary diff --git a/nuttx/configs/zp214xpa/include/board.h b/nuttx/configs/zp214xpa/include/board.h new file mode 100644 index 000000000..111d8ad55 --- /dev/null +++ b/nuttx/configs/zp214xpa/include/board.h @@ -0,0 +1,68 @@ +/**************************************************************************** + * configs/zp214xpa/include/board.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef __CONFIGS_ZP214XPA_INCLUDE_BOARD_H +#define __CONFIGS_ZP214XPA_INCLUDE_BOARD_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Clocking *****************************************************************/ + +/* Oscillator frequency */ + +#define LPC214X_FOSC 12000000 + +/* PLL0 settings CCLK = PLL_M * FOSC PCLK = CCLK/APBDIV */ + +#define LPC214X_PLL_M 5 +#define LPC214X_PLL_P 2 +#define LPC214X_APB_DIV 1 + +/* USB Pll settings -- 48 MHz needed. FUSB = PLL_M FOSC */ + +#define LPC214X_USBPLL_M 4 +#define LPC214X_USBPLL_P 2 + +/**************************************************************************** + * Inline Functions + ****************************************************************************/ + +#endif /* __CONFIGS_ZP214XPA_INCLUDE_BOARD_H */ diff --git a/nuttx/configs/zp214xpa/nsh/Make.defs b/nuttx/configs/zp214xpa/nsh/Make.defs new file mode 100644 index 000000000..f55e766d3 --- /dev/null +++ b/nuttx/configs/zp214xpa/nsh/Make.defs @@ -0,0 +1,128 @@ +############################################################################## +# configs/zp214xpa/nsh/Make.defs +# +# Copyright (C) 2012 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 + +# The default value for CROSSDEV can be overridden from the make command line: +# make -- Will build for the NuttX buildroot toolchain +# make CROSSDEV=arm-eabi- -- Will build for the devkitARM toolchain +# make CROSSDEV=arm-none-eabi- -- Will build for the CodeSourcery toolchain +# make CROSSDEV=arm-nuttx-elf- -- Will build for the NuttX buildroot toolchain + +CROSSDEV = arm-nuttx-elf- +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 + +HOSTOS = ${shell uname -o 2>/dev/null || echo "Other"} + +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 ($(ARCHCCMAJOR),4) +ifneq ($(HOSTOS),Cygwin) +OBJCOPYARGS = -R .note -R .note.gnu.build-id -R .comment +endif +endif + +ifeq ($(CROSSDEV),arm-nuttx-elf-) + 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/ld.script + MAXOPTIMIZATION = -Os +else + WINTOOL = y + 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/ld.script}" + MAXOPTIMIZATION = -O2 +endif + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ifeq ($(ARCHCCMAJOR),4) + ARCHCPUFLAGS = -mcpu=arm7tdmi -mfloat-abi=soft +else + ARCHCPUFLAGS = -mapcs-32 -mcpu=arm7tdmi -msoft-float +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +ARCHDEFINES = + +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-gotoff.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/zp214xpa/nsh/defconfig b/nuttx/configs/zp214xpa/nsh/defconfig new file mode 100644 index 000000000..7c7d9d06c --- /dev/null +++ b/nuttx/configs/zp214xpa/nsh/defconfig @@ -0,0 +1,574 @@ +# +# 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 is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y + +# +# 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_LM3S is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +CONFIG_ARCH_CHIP_LPC214X=y +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX 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_ARM7TDMI=y +CONFIG_ARCH_FAMILY="arm" +CONFIG_ARCH_CHIP="lpc214x" +CONFIG_ARCH_HAVE_LOWVECTORS=y +# CONFIG_ARCH_LOWVECTORS is not set +CONFIG_BOARD_LOOPSPERMSEC=3270 +# CONFIG_ARCH_CALIBRATION is not set + +# +# ARM Configuration Options +# +# CONFIG_ARM_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARM_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARM_TOOLCHAIN_GNU_EABI=y + +# +# LPC214x Configuration Options +# +CONFIG_ARCH_CHIP_LPC2148=y + +# +# LPC214x Initialization Options +# +# CONFIG_EXTMEM_MODE is not set +# CONFIG_RAM_MODE is not set +CONFIG_DEFAULT_MODE=y +CONFIG_CODE_BASE=0x00000000 +CONFIG_PLL_SETUP=y +CONFIG_MAM_SETUP=y +CONFIG_APBDIV_SETUP=y +CONFIG_APBDIV_VALUE=1 +# CONFIG_EMC_SETUP is not set +# CONFIG_BCFG0_SETUP is not set +# CONFIG_BCFG1_SETUP is not set +# CONFIG_BCFG2_SETUP is not set +# CONFIG_BCFG3_SETUP is not set +CONFIG_ADC_SETUP=y + +# +# LPC214x Peripheral Support +# +CONFIG_LPC214X_UART0=y +CONFIG_LPC214X_UART1=y +# CONFIG_LPC214x_FIO is not set + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +# CONFIG_ARCH_IRQPRIO is not set +# CONFIG_CUSTOM_STACK is not set +# CONFIG_ADDRENV is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set + +# +# Board Settings +# +CONFIG_DRAM_START=0x40000000 +CONFIG_DRAM_SIZE=32768 +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_MCU123 is not set +CONFIG_ARCH_BOARD_ZP214XPA=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="zp214xpa" + +# +# Common Board Options +# +CONFIG_NSH_MMCSDMINOR=0 + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 +CONFIG_RR_INTERVAL=0 +# CONFIG_SCHED_INSTRUMENTATION is not set +CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2008 +CONFIG_START_MONTH=10 +CONFIG_START_DAY=1 +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_WORKQUEUE is not set +# CONFIG_SCHED_WAITPID 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_MOUNTPOINT is not set +# CONFIG_DISABLE_ENVIRON is not set +CONFIG_DISABLE_POLL=y + +# +# 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=2048 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# 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 is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +# CONFIG_MMCSD is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# 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_ARCH_HAVE_UART1=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_UART0_SERIAL_CONSOLE=y +# CONFIG_UART1_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# UART0 Configuration +# +CONFIG_UART0_RXBUFSIZE=256 +CONFIG_UART0_TXBUFSIZE=256 +CONFIG_UART0_BAUD=38400 +CONFIG_UART0_BITS=8 +CONFIG_UART0_PARITY=0 +CONFIG_UART0_2STOP=0 + +# +# UART1 Configuration +# +CONFIG_UART1_RXBUFSIZE=256 +CONFIG_UART1_TXBUFSIZE=256 +CONFIG_UART1_BAUD=38400 +CONFIG_UART1_BITS=8 +CONFIG_UART1_PARITY=0 +CONFIG_UART1_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_FS_FAT is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set + +# +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=1 +# 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_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# +CONFIG_STDIO_BUFFER_SIZE=256 +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_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 Helper Functions +# +CONFIG_LIB_KBDCODEC=y + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +# CONFIG_HAVE_CXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +# CONFIG_BUILTIN is not set + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM 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_NETTEST 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_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 +# CONFIG_EXAMPLES_WLAN is not set + +# +# Interpreters +# + +# +# 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 + +# +# ModBus +# + +# +# 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 is not set +# 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 is not set +# 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 is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# 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 is not set +# 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=64 +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_CONSOLE=y +# 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 diff --git a/nuttx/configs/zp214xpa/nsh/setenv.sh b/nuttx/configs/zp214xpa/nsh/setenv.sh new file mode 100755 index 000000000..724dab706 --- /dev/null +++ b/nuttx/configs/zp214xpa/nsh/setenv.sh @@ -0,0 +1,65 @@ +#!/bin/bash +# configs/zp214xpa/nsh/setenv.sh +# +# Copyright (C) 2012 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" + +# 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 zp214xpa/tools directory +export LPCTOOL_DIR="${WD}/configs/zp214xpa/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/zp214xpa/scripts/ld.script b/nuttx/configs/zp214xpa/scripts/ld.script new file mode 100644 index 000000000..ba6ff8f2c --- /dev/null +++ b/nuttx/configs/zp214xpa/scripts/ld.script @@ -0,0 +1,120 @@ +/**************************************************************************** + * configs/zp214xpa/scripts/ld.script + * + * Copyright (C) 2012 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. + * + ****************************************************************************/ + +/* FLASH: + * The lpc2148 has 512Kb of non-volatile memory beginning at address + * 0x0000:0000. The OS entry point is via the reset vector at address + * 0x0000:0000 (default MEMMAP mode assumed) + * + * SRAM: + * The lpc2148 has 32Kb of on-chip static RAM beginning at address + * 0x4000:0000. The .data section will be relocated from _eronly + * to _sdata at boot time. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x00000000, LENGTH = 500K + sram (rw) : ORIGIN = 0x40000000, LENGTH = 32K - 32 +} + +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(.); + } > flash + + .init_section : { + _sinit = ABSOLUTE(.); + *(.init_array .init_array.*) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* 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/zp214xpa/src/Makefile b/nuttx/configs/zp214xpa/src/Makefile new file mode 100644 index 000000000..8f1e1c05d --- /dev/null +++ b/nuttx/configs/zp214xpa/src/Makefile @@ -0,0 +1,84 @@ +############################################################################ +# configs/zp214xpa/src/Makefile +# +# Copyright (C) 2012 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 + +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)/arm}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/sched}" +else + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/arm -I$(TOPDIR)/sched +endif + +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) +CSRCS = + +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +CFLAGS += -I $(TOPDIR)/arch/$(CONFIG_ARCH)/src + +all: libboard$(LIBEXT) + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +libboard$(LIBEXT): $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) + +.depend: Makefile $(SRCS) + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ + +depend: .depend + +clean: + $(call DELFILE, libboard$(LIBEXT)) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep -- cgit v1.2.3