From 5fa9b67f97bb70b71fb84d6be9b1e8f46ff2b1ee Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 28 Feb 2014 19:19:11 -0600 Subject: Removed almost all ostest configurations --- nuttx/configs/twr-k60n512/README.txt | 23 -- nuttx/configs/twr-k60n512/ostest/Make.defs | 110 ------ nuttx/configs/twr-k60n512/ostest/defconfig | 583 ----------------------------- nuttx/configs/twr-k60n512/ostest/setenv.sh | 61 --- 4 files changed, 777 deletions(-) delete mode 100644 nuttx/configs/twr-k60n512/ostest/Make.defs delete mode 100644 nuttx/configs/twr-k60n512/ostest/defconfig delete mode 100644 nuttx/configs/twr-k60n512/ostest/setenv.sh (limited to 'nuttx/configs/twr-k60n512') diff --git a/nuttx/configs/twr-k60n512/README.txt b/nuttx/configs/twr-k60n512/README.txt index 1072dc4fc..ac10d1538 100644 --- a/nuttx/configs/twr-k60n512/README.txt +++ b/nuttx/configs/twr-k60n512/README.txt @@ -657,29 +657,6 @@ can be selected as follow: Where is one of the following: - ostest: - ------ - This configuration directory, performs a simple OS test using - examples/ostest. - - 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. Default platform/toolchain: - - CONFIG_HOST_LINUX=y : Linux (Cygwin under Windows okay too). - CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y : Buildroot (arm-nuttx-elf-gcc) - CONFIG_ARMV7M_OABI_TOOLCHAIN=y : The older OABI version - CONFIG_RAW_BINARY=y : Output formats: ELF and raw binary - nsh: --- Configures the NuttShell (nsh) located at apps/examples/nsh. The diff --git a/nuttx/configs/twr-k60n512/ostest/Make.defs b/nuttx/configs/twr-k60n512/ostest/Make.defs deleted file mode 100644 index e791e7137..000000000 --- a/nuttx/configs/twr-k60n512/ostest/Make.defs +++ /dev/null @@ -1,110 +0,0 @@ -############################################################################ -# configs/twr-k60n512/ostest/Make.defs -# -# Copyright (C) 2011 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/ld.script}" -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/ld.script -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 -endif - -ifneq ($(CONFIG_DEBUG_NOOPT),y) - 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/twr-k60n512/ostest/defconfig b/nuttx/configs/twr-k60n512/ostest/defconfig deleted file mode 100644 index 54154c5f6..000000000 --- a/nuttx/configs/twr-k60n512/ostest/defconfig +++ /dev/null @@ -1,583 +0,0 @@ -# -# 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=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=y -# CONFIG_ARCH_CHIP_LM is not set -# CONFIG_ARCH_CHIP_LPC17XX is not set -# 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_CORTEXM4=y -CONFIG_ARCH_FAMILY="armv7-m" -CONFIG_ARCH_CHIP="kinetis" -# CONFIG_ARMV7M_USEBASEPRI is not set -# CONFIG_ARCH_FPU is not set -CONFIG_ARCH_HAVE_MPU=y -# CONFIG_ARMV7M_MPU is not set - -# -# 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_EABIL is not set -CONFIG_ARMV7M_OABI_TOOLCHAIN=y - -# -# Kinetis Configuration Options -# -# CONFIG_ARCH_CHIP_MK40N512VLQ100 is not set -# CONFIG_ARCH_CHIP_MK40N512VMD100 is not set -# CONFIG_ARCH_CHIP_MK40X128VLQ100 is not set -# CONFIG_ARCH_CHIP_MK40X128VMD100 is not set -# CONFIG_ARCH_CHIP_MK40X256VLQ100 is not set -# CONFIG_ARCH_CHIP_MK40X256VMD100 is not set -# CONFIG_ARCH_CHIP_MK60N256VLQ100 is not set -# CONFIG_ARCH_CHIP_MK60N256VMD100 is not set -# CONFIG_ARCH_CHIP_MK60N512VLQ100 is not set -CONFIG_ARCH_CHIP_MK60N512VMD100=y -# CONFIG_ARCH_CHIP_MK60X256VLQ100 is not set -# CONFIG_ARCH_CHIP_MK60X256VMD100 is not set -# CONFIG_ARCH_FAMILY_K40 is not set -CONFIG_ARCH_FAMILY_K60=y - -# -# Kinetis Peripheral Support -# -# CONFIG_KINETIS_TRACE is not set -# CONFIG_KINETIS_FLEXBUS is not set -# CONFIG_KINETIS_UART0 is not set -# CONFIG_KINETIS_UART1 is not set -# CONFIG_KINETIS_UART2 is not set -CONFIG_KINETIS_UART3=y -# CONFIG_KINETIS_UART4 is not set -# CONFIG_KINETIS_UART5 is not set -# CONFIG_KINETIS_ENET is not set -# CONFIG_KINETIS_RNGB is not set -# CONFIG_KINETIS_FLEXCAN0 is not set -# CONFIG_KINETIS_FLEXCAN1 is not set -# CONFIG_KINETIS_SPI0 is not set -# CONFIG_KINETIS_SPI1 is not set -# CONFIG_KINETIS_SPI2 is not set -# CONFIG_KINETIS_I2C0 is not set -# CONFIG_KINETIS_I2C1 is not set -# CONFIG_KINETIS_I2S is not set -# CONFIG_KINETIS_DAC0 is not set -# CONFIG_KINETIS_DAC1 is not set -# CONFIG_KINETIS_ADC0 is not set -# CONFIG_KINETIS_ADC1 is not set -# CONFIG_KINETIS_CMP is not set -# CONFIG_KINETIS_VREF is not set -# CONFIG_KINETIS_SDHC is not set -# CONFIG_KINETIS_FTM0 is not set -# CONFIG_KINETIS_FTM1 is not set -# CONFIG_KINETIS_FTM2 is not set -# CONFIG_KINETIS_LPTIMER is not set -# CONFIG_KINETIS_RTC is not set -# CONFIG_KINETIS_EWM is not set -# CONFIG_KINETIS_CMT is not set -# CONFIG_KINETIS_USBOTG is not set -# CONFIG_KINETIS_USBDCD is not set -# CONFIG_KINETIS_LLWU is not set -# CONFIG_KINETIS_TSI is not set -# CONFIG_KINETIS_FTFL is not set -# CONFIG_KINETIS_DMA is not set -# CONFIG_KINETIS_CRC is not set -# CONFIG_KINETIS_PDB is not set -# CONFIG_KINETIS_PIT is not set - -# -# Kinetis GPIO Interrupt Configuration -# -# CONFIG_GPIO_IRQ is not set - -# -# Kinetis UART Configuration -# - -# -# External Memory Configuration -# - -# -# 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=y -CONFIG_ARCH_RAMFUNCS=y -CONFIG_ARCH_HAVE_RAMVECTORS=y -# CONFIG_ARCH_RAMVECTORS is not set - -# -# Board Settings -# -CONFIG_BOARD_LOOPSPERMSEC=9535 -# CONFIG_ARCH_CALIBRATION is not set -CONFIG_RAM_START=0x1fff0000 -CONFIG_RAM_SIZE=131072 -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_TWR_K60N512=y -# CONFIG_ARCH_BOARD_CUSTOM is not set -CONFIG_ARCH_BOARD="twr-k60n512" - -# -# Common Board Options -# -CONFIG_ARCH_HAVE_LEDS=y -CONFIG_ARCH_LEDS=y -CONFIG_ARCH_HAVE_BUTTONS=y -# CONFIG_ARCH_BUTTONS is not set -CONFIG_ARCH_HAVE_IRQBUTTONS=y - -# -# Board-Specific Options -# - -# -# RTOS Features -# -# CONFIG_BOARD_INITIALIZE is not set -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=25 -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 is not set -# CONFIG_SCHED_STARTHOOK is not set -# CONFIG_SCHED_ATEXIT is not set -# CONFIG_SCHED_ONEXIT is not set -CONFIG_USER_ENTRYPOINT="ostest_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=y - -# -# Signal Numbers -# -CONFIG_SIG_SIGUSR1=1 -CONFIG_SIG_SIGUSR2=2 -CONFIG_SIG_SIGALARM=3 -CONFIG_SIG_SIGCONDTIMEDOUT=16 - -# -# 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 - -# -# Device Drivers -# -CONFIG_DISABLE_POLL=y -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=y -# CONFIG_16550_UART is not set -CONFIG_ARCH_HAVE_UART3=y -CONFIG_MCU_SERIAL=y -CONFIG_UART3_SERIAL_CONSOLE=y -# CONFIG_NO_SERIAL_CONSOLE is not set - -# -# UART3 Configuration -# -CONFIG_UART3_RXBUFSIZE=256 -CONFIG_UART3_TXBUFSIZE=256 -CONFIG_UART3_BAUD=115200 -CONFIG_UART3_BITS=8 -CONFIG_UART3_PARITY=0 -CONFIG_UART3_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=y -# CONFIG_FS_RAMMAP is not set - -# -# 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 is not set -# CONFIG_MM_SMALL is not set -CONFIG_MM_REGIONS=1 -# CONFIG_GRAN is not set - -# -# Binary Formats -# -# CONFIG_BINFMT_DISABLE 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 is not set - -# -# Library Routines -# - -# -# Standard C Library Options -# -CONFIG_STDIO_BUFFER_SIZE=64 -CONFIG_STDIO_LINEBUFFER=y -CONFIG_NUNGET_CHARS=2 -# 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 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_SYSTEM_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 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 is not set -# CONFIG_EXAMPLES_NXTEXT is not set -CONFIG_EXAMPLES_OSTEST=y -CONFIG_EXAMPLES_OSTEST_LOOPS=1 -CONFIG_EXAMPLES_OSTEST_STACKSIZE=2048 -CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 -CONFIG_EXAMPLES_OSTEST_RR_RANGE=10000 -CONFIG_EXAMPLES_OSTEST_RR_RUNS=10 -# 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_SYSTEM_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 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 is not set - -# -# 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/twr-k60n512/ostest/setenv.sh b/nuttx/configs/twr-k60n512/ostest/setenv.sh deleted file mode 100644 index 8daf1ce39..000000000 --- a/nuttx/configs/twr-k60n512/ostest/setenv.sh +++ /dev/null @@ -1,61 +0,0 @@ -#!/bin/bash -# configs/twr-k60n512/ostest/setenv.sh -# -# Copyright (C) 2011 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" - -# Add the path to the toolchain to the PATH varialble -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" -echo "PATH : ${PATH}" -- cgit v1.2.3