summaryrefslogtreecommitdiff
path: root/nuttx/configs/olimex-lpc2378/ostest/defconfig
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs/olimex-lpc2378/ostest/defconfig')
-rw-r--r--nuttx/configs/olimex-lpc2378/ostest/defconfig271
1 files changed, 0 insertions, 271 deletions
diff --git a/nuttx/configs/olimex-lpc2378/ostest/defconfig b/nuttx/configs/olimex-lpc2378/ostest/defconfig
deleted file mode 100644
index b3913c1f9..000000000
--- a/nuttx/configs/olimex-lpc2378/ostest/defconfig
+++ /dev/null
@@ -1,271 +0,0 @@
-############################################################################
-# configs/olimex-lpc2378/ostest/defconfig
-#
-# Copyright (C) 2010 Rommel Marcelo. All rights reserved.
-# Author: Rommel Marcelo
-#
-# This is part of the NuttX RTOS and based on the LPC2148 port:
-#
-# Copyright (C) 2010 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <gnutt@nuttx.org>
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name NuttX nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-#
-# Architecture selection
-#
-CONFIG_ARCH="arm"
-CONFIG_ARCH_ARM=y
-CONFIG_ARCH_ARM7TDMI=y
-CONFIG_ARCH_CHIP="lpc2378"
-CONFIG_ARCH_CHIP_LPC2378=y
-CONFIG_ARCH_BOARD="olimex-lpc2378"
-CONFIG_ARCH_BOARD_OLIMEXLPC2378=y
-CONFIG_ARCH_IRQPRIO=y
-CONFIG_BOARD_LOOPSPERMSEC=3270
-CONFIG_ARCH_LEDS=y
-CONFIG_RAM_SIZE=32768
-CONFIG_RAM_START=0x40000000
-CONFIG_ARCH_INTERRUPTSTACK=0
-CONFIG_ARCH_STACKDUMP=y
-
-# Identify toolchain and linker options
-#
-CONFIG_OLIMEX_LPC2378_CODESOURCERYW=n
-CONFIG_OLIMEX_LPC2378_CODESOURCERYL=y
-CONFIG_OLIMEX_LPC2378_DEVKITARM=n
-CONFIG_OLIMEX_LPC2378_BUILDROOT=n
-
-#
-# LPC2378 specific chip initialization
-#CONFIG_PLL_CLKSRC - identifies the clock source to use
-# IRC = 0, MAIN = 1, RTC = 2
-#
-CONFIG_EXTMEM_MODE=n
-CONFIG_RAM_MODE=n
-CONFIG_CODE_BASE=0x00000000
-CONFIG_PLL_SETUP=y
-CONFIG_PLL_CLKSRC= 1
-CONFIG_MAM_SETUP=y
-#TODO: CONFIG_EMC_SETUP=n
-CONFIG_ADC_SETUP=n
-CONFIG_USBDEV=n
-CONFIG_UART0=y
-CONFIG_UART2=y
-
-#
-# LPC23xx specific device driver settings
-#
-CONFIG_UART0_SERIAL_CONSOLE=y
-CONFIG_UART2_SERIAL_CONSOLE=n
-
-CONFIG_UART0_TXBUFSIZE=128
-CONFIG_UART2_TXBUFSIZE=256
-
-CONFIG_UART0_RXBUFSIZE=128
-CONFIG_UART2_RXBUFSIZE=256
-
-# Baud Rate
-CONFIG_UART0_BAUD=9600
-CONFIG_UART2_BAUD=576000
-# Data Bits
-CONFIG_UART0_BITS=8
-CONFIG_UART2_BITS=8
-# Parity Bits
-CONFIG_UART0_PARITY=0
-CONFIG_UART2_PARITY=0
-# 2 Stop Bits ?
-CONFIG_UART0_2STOP=0
-CONFIG_UART2_2STOP=0
-
-#
-# General build options
-#
-CONFIG_RRLOAD_BINARY=n
-CONFIG_INTELHEX_BINARY=y
-CONFIG_RAW_BINARY=y
-
-#
-# General OS setup
-#
-CONFIG_USER_ENTRYPOINT="ostest_main"
-CONFIG_DEBUG=n
-CONFIG_DEBUG_VERBOSE=n
-#CONFIG_DEBUG_MM=y
-#CONFIG_DEBUG_SCHED=y
-#CONFIG_DEBUG_FS=y
-CONFIG_MM_REGIONS=1
-CONFIG_ARCH_LOWPUTC=y
-CONFIG_RR_INTERVAL=0
-CONFIG_SCHED_INSTRUMENTATION=n
-CONFIG_TASK_NAME_SIZE=0
-CONFIG_START_YEAR=2009
-CONFIG_START_MONTH=7
-CONFIG_START_DAY=13
-CONFIG_JULIAN_TIME=n
-CONFIG_DEV_CONSOLE=y
-CONFIG_DEV_LOWCONSOLE=
-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_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_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 sysem 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)
-#
-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_STDIO_BUFFER_SIZE=64
-CONFIG_NUNGET_CHARS=2
-CONFIG_PREALLOC_MQ_MSGS=4
-CONFIG_MQ_MAXMSGSIZE=32
-CONFIG_MAX_WDOGPARMS=2
-CONFIG_PREALLOC_WDOGS=4
-CONFIG_PREALLOC_TIMERS=4
-
-#
-# Filesystem configuration
-#
-CONFIG_FS_FAT=n
-CONFIG_FS_ROMFS=n
-
-#
-# Maintain legacy build behavior (revisit)
-#
-
-CONFIG_MMCSD=y
-CONFIG_MMCSD_SPI=y
-CONFIG_MTD=y
-
-#
-# SPI-based MMC/SD driver
-#
-CONFIG_MMCSD_NSLOTS=0
-CONFIG_MMCSD_READONLY=n
-CONFIG_MMCSD_SPICLOCK=20000000
-
-#
-# Settings for examples/hello
-CONFIG_EXAMPLES_OSTEST_LOOPS=1
-CONFIG_EXAMPLES_OSTEST_STACKSIZE=4096
-CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3
-
-# Settings for examples/serloop
-CONFIG_EXAMPLES_SERLOOP_BUFIO=
-
-#
-# Settings for examples/nsh
-#
-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_CONSOLE=y
-CONFIG_NSH_TELNET=n
-CONFIG_NSH_ARCHINIT=n
-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"
-
-
-# Stack and heap information
-#
-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