aboutsummaryrefslogtreecommitdiff
path: root/nuttx/configs/us7032evb1
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs/us7032evb1')
-rw-r--r--nuttx/configs/us7032evb1/Kconfig13
-rw-r--r--nuttx/configs/us7032evb1/README.txt138
-rw-r--r--nuttx/configs/us7032evb1/bin/README.txt2
-rw-r--r--nuttx/configs/us7032evb1/include/README.txt2
-rw-r--r--nuttx/configs/us7032evb1/include/board.h100
-rw-r--r--nuttx/configs/us7032evb1/nsh/Make.defs105
-rw-r--r--nuttx/configs/us7032evb1/nsh/appconfig44
-rw-r--r--nuttx/configs/us7032evb1/nsh/defconfig325
-rw-r--r--nuttx/configs/us7032evb1/nsh/ld.script91
-rwxr-xr-xnuttx/configs/us7032evb1/nsh/setenv.sh47
-rw-r--r--nuttx/configs/us7032evb1/ostest/Make.defs105
-rw-r--r--nuttx/configs/us7032evb1/ostest/appconfig39
-rw-r--r--nuttx/configs/us7032evb1/ostest/defconfig325
-rw-r--r--nuttx/configs/us7032evb1/ostest/ld.script91
-rwxr-xr-xnuttx/configs/us7032evb1/ostest/setenv.sh47
-rw-r--r--nuttx/configs/us7032evb1/shterm/Makefile51
-rw-r--r--nuttx/configs/us7032evb1/shterm/shterm.c737
-rw-r--r--nuttx/configs/us7032evb1/src/Makefile77
-rw-r--r--nuttx/configs/us7032evb1/src/README.txt3
-rw-r--r--nuttx/configs/us7032evb1/src/up_leds.c135
20 files changed, 2477 insertions, 0 deletions
diff --git a/nuttx/configs/us7032evb1/Kconfig b/nuttx/configs/us7032evb1/Kconfig
new file mode 100644
index 000000000..d054a1624
--- /dev/null
+++ b/nuttx/configs/us7032evb1/Kconfig
@@ -0,0 +1,13 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+if ARCH_BOARD_TWR_K60N512
+config ARCH_LEDS
+ bool "NuttX LED support"
+ default n
+ ---help---
+ "Support control of board LEDs by NuttX to indicate system state"
+
+endif
diff --git a/nuttx/configs/us7032evb1/README.txt b/nuttx/configs/us7032evb1/README.txt
new file mode 100644
index 000000000..0b9060460
--- /dev/null
+++ b/nuttx/configs/us7032evb1/README.txt
@@ -0,0 +1,138 @@
+Status
+^^^^^^
+
+*** UNSTABLE ***
+The port is basically complete and many examples run correctly. However, there
+are remaining instabilities that make the port un-usable. The nature of these
+is not understood; the behavior is that certain SH-1 instructions stop working
+as advertised. This could be a silicon problem, some pipeline issue that is not
+handled properly by the gcc 3.4.5 toolchain (which has very limit SH-1 support
+to begin with), or perhaps with the CMON debugger. At any rate, I have exhausted
+all of the energy that I am willing to put into this cool old processor for the
+time being.
+
+Toolchain
+^^^^^^^^^
+
+ A GNU GCC-based toolchain is assumed. The files */setenv.sh should
+ be modified to point to the correct path to the SH toolchain (if
+ different from the default).
+
+ If you have no SH toolchain, one can be downloaded from the NuttX
+ SourceForge download site (https://sourceforge.net/project/showfiles.php?group_id=189573).
+
+ 1. You must have already configured Nuttx in <some-dir>nuttx.
+
+ cd tools
+ ./configure.sh us7032evb1/<sub-dir>
+
+ 2. Download the latest buildroot package into <some-dir>
+
+ 3. unpack
+
+ 4. cd <some-dir>/buildroot
+
+ 5. cp configs/sh-defconfig .config
+
+ 6. make oldconfig
+
+ 7. make
+
+ 8. Edit setenv.h so that the PATH variable includes the path to the
+ newly built binaries.
+
+shterm
+^^^^^^
+
+ The USB7032EVB1 supports CMON in PROM. CMON requires special
+ serial interactions in order to upload and download program files.
+ Therefore, a standard terminal emulation program (such as minicom)
+ cannot be used.
+
+ The shterm subdirectory contains a small terminal emulation
+ program that supports these special interactions for file transfers.
+
+Configurations
+^^^^^^^^^^^^^^
+
+Each SH-1 configuration is maintained in a sudirectory and
+can be selected as follow:
+
+ cd tools
+ ./configure.sh us7032evb1/<subdir>
+ cd -
+ . ./setenv.sh
+
+Where <subdir> is one of the following:
+
+ostest
+^^^^^^as advertised. This could be a silicon problem, some pipeline issue that is not handled properly by the gcc 3.4.5 tool
+
+This configuration directory, performs a simple OS test using
+examples/ostest.
+
+nsh
+^^^
+
+Configures the NuttShell (nsh) located at examples/nsh. The
+Configuration enables only the serial NSH interfaces.
+
+NOTE: At present, the NSH example does not run. See the "Status"
+discussion above for a full explanation.
+
+Configuration Options
+^^^^^^^^^^^^^^^^^^^^^
+
+In additional to the common configuration options listed in the
+file configs/README.txt, there are other configuration options
+specific to the SH-1
+
+Architecture selection
+
+ CONFIG_ARCH - identifies the arch subdirectory and, hence, the
+ processor architecture. This should be sh (for arch/sh)
+ CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory.
+ This should be sh1 (for arch/sh/src/sh1 and arch/sh/include/sh1)
+ CONFIG_ARCH_SH1 and CONFIG_ARCH_CHIP_SH7032 - for use in C code. These
+ identify the particular chip or SoC that the architecture is
+ implemented in.
+ CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
+ the board that supports the particular chip or SoC. This
+ should be us7032evb1 for (configs/us7032evb1).
+ CONFIG_ARCH_BOARD_US7032EVB1 - for use in C code
+ CONFIG_ENDIAN_BIG - the SH-1 usually runs big-endian
+ CONFIG_ARCH_NOINTC - define if the architecture does not
+ support an interrupt controller or otherwise cannot support
+ APIs like up_enable_irq() and up_disable_irq(). Should be
+ defined.
+ CONFIG_ARCH_IRQPRIO
+ Define if the architecture suports prioritizaton of interrupts
+ and the up_prioritize_irq() API. Should be defined.
+ CONFIG_BOARD_LOOPSPERMSEC - for delay loops
+ CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to SH1_LCEVB1
+ CONFIG_DRAM_SIZE - Describes the internal DRAM.
+ CONFIG_DRAM_START - The start address of internal DRAM
+ CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
+ stack. If defined, this symbol is the size of the interrupt
+ stack in bytes. If not defined, the user task stacks will be
+ used during interrupt handling.
+ CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
+
+ CONFIG_SH1_DMAC0, CONFIG_SH1_DMAC1, CONFIG_SH1_DMAC2, CONFIG_SH1_DMAC3,
+ CONFIG_SH1_ITU1, CONFIG_SH1_ITU2, CONFIG_SH1_ITU3, CONFIG_SH1_ITU4,
+ CONFIG_SH1_SCI0, CONFIG_SH1_SCI1, CONFIG_SH1_PCU, CONFIG_SH1_AD,
+ CONFIG_SH1_WDT, CONFIG_SH1_CMI - Each unused chip block should b
+ disabled to save space
+
+SH1 specific device driver settings
+
+ CONFIG_SCIn_SERIAL_CONSOLE - selects the SCIn for the
+ console and ttys0 (default is the UART0).
+ CONFIG_SCIn_RXBUFSIZE - Characters are buffered as received.
+ This specific the size of the receive buffer
+ CONFIG_SCIn_TXBUFSIZE - Characters are buffered before
+ being sent. This specific the size of the transmit buffer
+ CONFIG_SCIn_BAUD - The configure BAUD of the UART. Must be
+ CONFIG_SCIn_BITS - The number of bits. Must be either 7 or 8.
+ CONFIG_SCIn_PARTIY - 0=no parity, 1=odd parity, 2=even parity, 3=mark 1, 4=space 0
+ CONFIG_SCIn_2STOP - Two stop bits
diff --git a/nuttx/configs/us7032evb1/bin/README.txt b/nuttx/configs/us7032evb1/bin/README.txt
new file mode 100644
index 000000000..45b047c91
--- /dev/null
+++ b/nuttx/configs/us7032evb1/bin/README.txt
@@ -0,0 +1,2 @@
+This directory contains scripts and host executables unique to the Hitachi
+SH-1 Low-Cost Evaluation Board, US7032EVB1
diff --git a/nuttx/configs/us7032evb1/include/README.txt b/nuttx/configs/us7032evb1/include/README.txt
new file mode 100644
index 000000000..857785f4b
--- /dev/null
+++ b/nuttx/configs/us7032evb1/include/README.txt
@@ -0,0 +1,2 @@
+This directory contains header files unique to the Hitachi SH-1 Low-Cost
+Evaluation Board, US7032EVB1
diff --git a/nuttx/configs/us7032evb1/include/board.h b/nuttx/configs/us7032evb1/include/board.h
new file mode 100644
index 000000000..3ca3476da
--- /dev/null
+++ b/nuttx/configs/us7032evb1/include/board.h
@@ -0,0 +1,100 @@
+/****************************************************************************
+ * configs/us7032evb1/include/board.h
+ *
+ * Copyright (C) 2008-2009 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.
+ *
+ ****************************************************************************/
+
+#ifndef _CONFIGS_US7032EVB1_BOARD_H
+#define _CONFIGS_US7032EVB1_BOARD_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+#include "chip.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Clocking *****************************************************************/
+
+#define SH1_CLOCK 20000000 /* 20 MHz */
+
+/* LED definitions **********************************************************/
+
+/* The SH1_LPEVB only a single LED controlled by either port A, pin 15, or
+ * port B, pin 15 (selectable via JP8).
+ */
+
+#define LED_STARTED 0
+#define LED_HEAPALLOCATE 1
+#define LED_IRQSENABLED 1
+#define LED_STACKCREATED 1
+#define LED_INIRQ 0
+#define LED_SIGNAL 0
+#define LED_ASSERTION 0
+#define LED_PANIC 1
+
+/* Button definitions *******************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_BUTTONS
+EXTERN void up_buttoninit(void);
+EXTERN uint8_t up_buttons(void);
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* _CONFIGS_US7032EVB1_BOARD_H */
diff --git a/nuttx/configs/us7032evb1/nsh/Make.defs b/nuttx/configs/us7032evb1/nsh/Make.defs
new file mode 100644
index 000000000..623eb82d5
--- /dev/null
+++ b/nuttx/configs/us7032evb1/nsh/Make.defs
@@ -0,0 +1,105 @@
+##############################################################################
+# configs/us7032evb1/nsh/Make.defs
+#
+# Copyright (C) 2008 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+##############################################################################
+
+include ${TOPDIR}/.config
+include ${TOPDIR}/tools/Config.mk
+
+ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
+ ARCHOPTIMIZATION = -g
+else
+ ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \
+ -fomit-frame-pointer
+endif
+
+ARCHCPUFLAGS = -m1 -fno-builtin
+ARCHPICFLAGS = -fpic
+ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
+ARCHDEFINES =
+ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/ld.script
+
+CROSSDEV = sh-elf-
+CC = $(CROSSDEV)gcc
+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
+CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
+ LDFLAGS += -g
+endif
+
+define PREPROCESS
+ @echo "CPP: $1->$2"
+ @$(CPP) $(CPPFLAGS) $1 -o $2
+endef
+
+define COMPILE
+ @echo "CC: $1"
+ @$(CC) -c $(CFLAGS) $1 -o $2
+endef
+
+define ASSEMBLE
+ @echo "AS: $1"
+ @$(CC) -c $(AFLAGS) $1 -o $2
+endef
+
+define ARCHIVE
+ echo "AR: $2"; \
+ $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
+endef
+
+define CLEAN
+ @rm -f *.o *.a
+endef
+
+MKDEP = $(TOPDIR)/tools/mkdeps.sh
+
+HOSTCC = gcc
+HOSTINCLUDES = -I.
+HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTLDFLAGS =
+
diff --git a/nuttx/configs/us7032evb1/nsh/appconfig b/nuttx/configs/us7032evb1/nsh/appconfig
new file mode 100644
index 000000000..fe0916f95
--- /dev/null
+++ b/nuttx/configs/us7032evb1/nsh/appconfig
@@ -0,0 +1,44 @@
+############################################################################
+# configs/us7032evb1/nsh/appconfig
+#
+# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# 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/us7032evb1/nsh/defconfig b/nuttx/configs/us7032evb1/nsh/defconfig
new file mode 100644
index 000000000..02d42aebe
--- /dev/null
+++ b/nuttx/configs/us7032evb1/nsh/defconfig
@@ -0,0 +1,325 @@
+############################################################################
+# configs/us7032evb1/nsh/defconfig
+#
+# Copyright (C) 2008-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="sh"
+CONFIG_ARCH_SH1=y
+CONFIG_ARCH_CHIP="sh1"
+CONFIG_ARCH_CHIP_SH7032=y
+CONFIG_ARCH_BOARD="us7032evb1"
+CONFIG_ARCH_BOARD_US7032EVB1=y
+CONFIG_ENDIAN_BIG=y
+CONFIG_ARCH_NOINTC=y
+CONFIG_ARCH_IRQPRIO=y
+CONFIG_BOARD_LOOPSPERMSEC=572
+CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_BUTTONS=y
+CONFIG_DRAM_SIZE=57344
+CONFIG_DRAM_START=0x0a002000
+CONFIG_ARCH_INTERRUPTSTACK=0
+CONFIG_ARCH_STACKDUMP=y
+
+#
+# SH-1 specific boot/build settings
+#
+CONFIG_SH1_DMAC0=n
+CONFIG_SH1_DMAC1=n
+CONFIG_SH1_DMAC2=n
+CONFIG_SH1_DMAC3=n
+CONFIG_SH1_ITU1=n
+CONFIG_SH1_ITU2=n
+CONFIG_SH1_ITU3=n
+CONFIG_SH1_ITU4=n
+CONFIG_SH1_SCI0=n
+CONFIG_SH1_SCI1=y
+CONFIG_SH1_PCU=n
+CONFIG_SH1_AD=n
+CONFIG_SH1_WDT=n
+CONFIG_SH1_CMI=n
+
+#
+# SH1 specific device driver settings
+#
+CONFIG_SCI0_SERIAL_CONSOLE=n
+CONFIG_SCI1_SERIAL_CONSOLE=y
+CONFIG_SCI0_TXBUFSIZE=64
+CONFIG_SCI1_TXBUFSIZE=256
+CONFIG_SCI0_RXBUFSIZE=32
+CONFIG_SCI1_RXBUFSIZE=256
+CONFIG_SCI0_BAUD=9600
+CONFIG_SCI1_BAUD=9600
+CONFIG_SCI0_BITS=8
+CONFIG_SCI1_BITS=8
+CONFIG_SCI0_PARITY=0
+CONFIG_SCI1_PARITY=0
+CONFIG_SCI0_2STOP=0
+CONFIG_SCI1_2STOP=0
+
+#
+# General build options
+#
+CONFIG_RRLOAD_BINARY=n
+CONFIG_INTELHEX_BINARY=n
+CONFIG_MOTOROLA_SREC=y
+CONFIG_RAW_BINARY=y
+CONFIG_HAVE_LIBM=n
+
+#
+# General OS setup
+#
+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_RR_INTERVAL=0
+CONFIG_SCHED_INSTRUMENTATION=n
+CONFIG_TASK_NAME_SIZE=0
+CONFIG_START_YEAR=2008
+CONFIG_START_MONTH=11
+CONFIG_START_DAY=10
+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_SDCLONE_DISABLE=y
+
+#
+# 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=y
+CONFIG_DISABLE_POSIX_TIMERS=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_DISABLE_SIGNALS=y
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_DISABLE_MOUNTPOINT=y
+CONFIG_DISABLE_ENVIRON=n
+CONFIG_DISABLE_POLL=y
+
+#
+# Misc libc settings
+#
+CONFIG_NOPRINTF_FIELDWIDTH=y
+
+#
+# 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=8
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_NPTHREAD_KEYS=0
+CONFIG_NFILE_DESCRIPTORS=8
+CONFIG_NFILE_STREAMS=8
+CONFIG_NAME_MAX=32
+CONFIG_STDIO_BUFFER_SIZE=0
+CONFIG_NUNGET_CHARS=0
+CONFIG_PREALLOC_MQ_MSGS=0
+CONFIG_MQ_MAXMSGSIZE=0
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_PREALLOC_TIMERS=0
+
+#
+# Filesystem configuration
+#
+CONFIG_FS_FAT=n
+CONFIG_FS_ROMFS=n
+
+#
+# SPI-based MMC/SD driver
+#
+CONFIG_MMCSD_NSLOTS=1
+CONFIG_MMCSD_READONLY=n
+
+#
+# TCP/IP and UDP support via uIP
+#
+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
+#
+CONFIG_NET_DHCP_LIGHT=n
+CONFIG_NET_RESOLV_ENTRIES=4
+
+#
+# USB Device Configuration
+#
+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
+
+#
+# USB Serial Device 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
+#
+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
+
+#
+# Settings for examples/ostest
+CONFIG_EXAMPLES_OSTEST_LOOPS=1
+CONFIG_EXAMPLES_OSTEST_STACKSIZE=4096
+CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3
+
+#
+# Settings for apps/nshlib
+#
+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_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
+#
+CONFIG_BOOT_RUNFROMFLASH=n
+CONFIG_BOOT_COPYTORAM=n
+CONFIG_CUSTOM_STACK=n
+CONFIG_IDLETHREAD_STACKSIZE=1024
+CONFIG_USERMAIN_STACKSIZE=1024
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=1024
+CONFIG_HEAP_BASE=
+CONFIG_HEAP_SIZE=
diff --git a/nuttx/configs/us7032evb1/nsh/ld.script b/nuttx/configs/us7032evb1/nsh/ld.script
new file mode 100644
index 000000000..e21bdfa00
--- /dev/null
+++ b/nuttx/configs/us7032evb1/nsh/ld.script
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * configs/us7032evb1/nsh/ld.script
+ *
+ * Copyright (C) 2008 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.
+ *
+ ****************************************************************************/
+
+OUTPUT_ARCH(sh)
+ENTRY(_stext)
+SECTIONS
+{
+ /* The us7032evb1 has CMON in PROM beginning at address 0x00000000 and
+ * either 64Kb or 256Kb of SRAM beginning at 0x0a000000. Neither the
+ * PROM nor the first 8Kb of SRAM are avaible to the devoleper as these
+ * are used by CMON. The next 1Kb of SRAM is dedicated to relocated
+ * interrupt vectors.
+ */
+
+ . = 0x0a002000;
+ .text : {
+ _svect = ABSOLUTE(.);
+ *(.vects); /* Relocated interrupt vectors */
+ _evect = ABSOLUTE(.);
+ _stext = ABSOLUTE(.);
+ *(.reset) /* Reset/IRQ code */
+ *(.text) /* Code */
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata) /* Read-only data */
+ *(.rodata.str1.4)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got) /* Global offset table */
+ _etext = ABSOLUTE(.);
+ }
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data) /* Modifiable data */
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ }
+
+ .bss : { /* BSS */
+ _sbss = ABSOLUTE(.);
+ *(.bss)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ }
+ /* 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/us7032evb1/nsh/setenv.sh b/nuttx/configs/us7032evb1/nsh/setenv.sh
new file mode 100755
index 000000000..d23133612
--- /dev/null
+++ b/nuttx/configs/us7032evb1/nsh/setenv.sh
@@ -0,0 +1,47 @@
+#!/bin/bash
+# configs/us7032evb1/nsh/setenv.sh
+#
+# Copyright (C) 2008 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.
+#
+
+if [ "$(basename $0)" = "setenv.sh" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
+
+WD=`pwd`
+export BUILDROOT_BIN=${WD}/../buildroot/build_sh/staging_dir/bin
+export SH1BINARIES=$WD/configs/us7032evb1/bin
+export PATH=${BUILDROOT_BIN}:${SH1BINARIES}:/sbin:/usr/sbin:${PATH_ORIG}
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/us7032evb1/ostest/Make.defs b/nuttx/configs/us7032evb1/ostest/Make.defs
new file mode 100644
index 000000000..dcbaefdf8
--- /dev/null
+++ b/nuttx/configs/us7032evb1/ostest/Make.defs
@@ -0,0 +1,105 @@
+##############################################################################
+# configs/us7032evb1/ostest/Make.defs
+#
+# Copyright (C) 2008 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+##############################################################################
+
+include ${TOPDIR}/.config
+include ${TOPDIR}/tools/Config.mk
+
+ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
+ ARCHOPTIMIZATION = -g
+else
+ ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \
+ -fomit-frame-pointer
+endif
+
+ARCHCPUFLAGS = -m1 -fno-builtin
+ARCHPICFLAGS = -fpic
+ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
+ARCHDEFINES =
+ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/ld.script
+
+CROSSDEV = sh-elf-
+CC = $(CROSSDEV)gcc
+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
+CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
+ LDFLAGS += -g
+endif
+
+define PREPROCESS
+ @echo "CPP: $1->$2"
+ @$(CPP) $(CPPFLAGS) $1 -o $2
+endef
+
+define COMPILE
+ @echo "CC: $1"
+ @$(CC) -c $(CFLAGS) $1 -o $2
+endef
+
+define ASSEMBLE
+ @echo "AS: $1"
+ @$(CC) -c $(AFLAGS) $1 -o $2
+endef
+
+define ARCHIVE
+ echo "AR: $2"; \
+ $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
+endef
+
+define CLEAN
+ @rm -f *.o *.a
+endef
+
+MKDEP = $(TOPDIR)/tools/mkdeps.sh
+
+HOSTCC = gcc
+HOSTINCLUDES = -I.
+HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTLDFLAGS =
+
diff --git a/nuttx/configs/us7032evb1/ostest/appconfig b/nuttx/configs/us7032evb1/ostest/appconfig
new file mode 100644
index 000000000..ba7253e3f
--- /dev/null
+++ b/nuttx/configs/us7032evb1/ostest/appconfig
@@ -0,0 +1,39 @@
+############################################################################
+# configs/us7032evb1/ostest/appconfig
+#
+# Copyright (C) 2011 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.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/ostest
+
diff --git a/nuttx/configs/us7032evb1/ostest/defconfig b/nuttx/configs/us7032evb1/ostest/defconfig
new file mode 100644
index 000000000..f92a55461
--- /dev/null
+++ b/nuttx/configs/us7032evb1/ostest/defconfig
@@ -0,0 +1,325 @@
+############################################################################
+# configs/us7032evb1/ostest/defconfig
+#
+# Copyright (C) 2008-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="sh"
+CONFIG_ARCH_SH1=y
+CONFIG_ARCH_CHIP="sh1"
+CONFIG_ARCH_CHIP_SH7032=y
+CONFIG_ARCH_BOARD="us7032evb1"
+CONFIG_ARCH_BOARD_US7032EVB1=y
+CONFIG_ENDIAN_BIG=y
+CONFIG_ARCH_NOINTC=y
+CONFIG_ARCH_IRQPRIO=y
+CONFIG_BOARD_LOOPSPERMSEC=572
+CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_BUTTONS=y
+CONFIG_DRAM_SIZE=57344
+CONFIG_DRAM_START=0x0a002000
+CONFIG_ARCH_INTERRUPTSTACK=0
+CONFIG_ARCH_STACKDUMP=y
+
+#
+# SH-1 specific boot/build settings
+#
+CONFIG_SH1_DMAC0=n
+CONFIG_SH1_DMAC1=n
+CONFIG_SH1_DMAC2=n
+CONFIG_SH1_DMAC3=n
+CONFIG_SH1_ITU1=n
+CONFIG_SH1_ITU2=n
+CONFIG_SH1_ITU3=n
+CONFIG_SH1_ITU4=n
+CONFIG_SH1_SCI0=n
+CONFIG_SH1_SCI1=y
+CONFIG_SH1_PCU=n
+CONFIG_SH1_AD=n
+CONFIG_SH1_WDT=n
+CONFIG_SH1_CMI=n
+
+#
+# SH1 specific device driver settings
+#
+CONFIG_SCI0_SERIAL_CONSOLE=n
+CONFIG_SCI1_SERIAL_CONSOLE=y
+CONFIG_SCI0_TXBUFSIZE=64
+CONFIG_SCI1_TXBUFSIZE=256
+CONFIG_SCI0_RXBUFSIZE=32
+CONFIG_SCI1_RXBUFSIZE=256
+CONFIG_SCI0_BAUD=9600
+CONFIG_SCI1_BAUD=9600
+CONFIG_SCI0_BITS=8
+CONFIG_SCI1_BITS=8
+CONFIG_SCI0_PARITY=0
+CONFIG_SCI1_PARITY=0
+CONFIG_SCI0_2STOP=0
+CONFIG_SCI1_2STOP=0
+
+#
+# General build options
+#
+CONFIG_RRLOAD_BINARY=n
+CONFIG_INTELHEX_BINARY=n
+CONFIG_MOTOROLA_SREC=y
+CONFIG_RAW_BINARY=y
+CONFIG_HAVE_LIBM=n
+
+#
+# General OS setup
+#
+CONFIG_USER_ENTRYPOINT="ostest_main"
+CONFIG_DEBUG=n
+CONFIG_DEBUG_VERBOSE=n
+CONFIG_DEBUG_SYMBOLS=n
+CONFIG_MM_REGIONS=1
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_RR_INTERVAL=0
+CONFIG_SCHED_INSTRUMENTATION=n
+CONFIG_TASK_NAME_SIZE=0
+CONFIG_START_YEAR=2008
+CONFIG_START_MONTH=11
+CONFIG_START_DAY=10
+CONFIG_JULIAN_TIME=n
+CONFIG_DEV_CONSOLE=y
+CONFIG_DEV_LOWCONSOLE=y
+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
+
+#
+# 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=y
+CONFIG_DISABLE_POSIX_TIMERS=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_DISABLE_SIGNALS=y
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_DISABLE_MOUNTPOINT=y
+CONFIG_DISABLE_ENVIRON=y
+CONFIG_DISABLE_POLL=y
+
+#
+# Misc libc settings
+#
+CONFIG_NOPRINTF_FIELDWIDTH=y
+
+#
+# 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=8
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_NPTHREAD_KEYS=0
+CONFIG_NFILE_DESCRIPTORS=8
+CONFIG_NFILE_STREAMS=8
+CONFIG_NAME_MAX=32
+CONFIG_STDIO_BUFFER_SIZE=0
+CONFIG_NUNGET_CHARS=0
+CONFIG_PREALLOC_MQ_MSGS=0
+CONFIG_MQ_MAXMSGSIZE=0
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_PREALLOC_TIMERS=0
+
+#
+# Filesystem configuration
+#
+CONFIG_FS_FAT=n
+CONFIG_FS_ROMFS=n
+
+#
+# SPI-based MMC/SD driver
+#
+CONFIG_MMCSD_NSLOTS=1
+CONFIG_MMCSD_READONLY=n
+
+#
+# TCP/IP and UDP support via uIP
+#
+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
+#
+CONFIG_NET_DHCP_LIGHT=n
+CONFIG_NET_RESOLV_ENTRIES=4
+
+#
+# USB Device Configuration
+#
+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
+
+#
+# USB Serial Device 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
+#
+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
+
+#
+# Settings for examples/ostest
+CONFIG_EXAMPLES_OSTEST_LOOPS=1
+CONFIG_EXAMPLES_OSTEST_STACKSIZE=4096
+CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3
+
+#
+# Settings for apps/nshlib
+#
+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_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
+#
+CONFIG_BOOT_RUNFROMFLASH=n
+CONFIG_BOOT_COPYTORAM=n
+CONFIG_CUSTOM_STACK=n
+CONFIG_IDLETHREAD_STACKSIZE=1024
+CONFIG_USERMAIN_STACKSIZE=1024
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=1024
+CONFIG_HEAP_BASE=
+CONFIG_HEAP_SIZE=
diff --git a/nuttx/configs/us7032evb1/ostest/ld.script b/nuttx/configs/us7032evb1/ostest/ld.script
new file mode 100644
index 000000000..36c9b0d9a
--- /dev/null
+++ b/nuttx/configs/us7032evb1/ostest/ld.script
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * configs/us7032evb1/ostest/ld.script
+ *
+ * Copyright (C) 2008 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.
+ *
+ ****************************************************************************/
+
+OUTPUT_ARCH(sh)
+ENTRY(_stext)
+SECTIONS
+{
+ /* The us7032evb1 has CMON in PROM beginning at address 0x00000000 and
+ * either 64Kb or 256Kb of SRAM beginning at 0x0a000000. Neither the
+ * PROM nor the first 8Kb of SRAM are avaible to the devoleper as these
+ * are used by CMON. The next 1Kb of SRAM is dedicated to relocated
+ * interrupt vectors.
+ */
+
+ . = 0x0a002000;
+ .text : {
+ _svect = ABSOLUTE(.);
+ *(.vects); /* Relocated interrupt vectors */
+ _evect = ABSOLUTE(.);
+ _stext = ABSOLUTE(.);
+ *(.reset) /* Reset/IRQ code */
+ *(.text) /* Code */
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata) /* Read-only data */
+ *(.rodata.str1.4)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got) /* Global offset table */
+ _etext = ABSOLUTE(.);
+ }
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data) /* Modifiable data */
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ }
+
+ .bss : { /* BSS */
+ _sbss = ABSOLUTE(.);
+ *(.bss)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ }
+ /* 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/us7032evb1/ostest/setenv.sh b/nuttx/configs/us7032evb1/ostest/setenv.sh
new file mode 100755
index 000000000..ac37e9150
--- /dev/null
+++ b/nuttx/configs/us7032evb1/ostest/setenv.sh
@@ -0,0 +1,47 @@
+#!/bin/bash
+# configs/us7032evb1/ostest/setenv.sh
+#
+# Copyright (C) 2008 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.
+#
+
+if [ "$(basename $0)" = "setenv.sh" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
+
+WD=`pwd`
+export BUILDROOT_BIN=${WD}/../buildroot/build_sh/staging_dir/bin
+export SH1BINARIES=$WD/configs/us7032evb1/bin
+export PATH=${BUILDROOT_BIN}:${SH1BINARIES}:/sbin:/usr/sbin:${PATH_ORIG}
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/us7032evb1/shterm/Makefile b/nuttx/configs/us7032evb1/shterm/Makefile
new file mode 100644
index 000000000..2ea23db33
--- /dev/null
+++ b/nuttx/configs/us7032evb1/shterm/Makefile
@@ -0,0 +1,51 @@
+############################################################################
+# config/us7032evb1/shterm/Makefile
+#
+# Copyright (C) 2008 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+include $(TOPDIR)/.config
+include $(TOPDIR)/Make.defs
+
+SRC = shterm.c
+BIN = shterm
+
+all: ../bin/$(BIN)$(EXEEXT)
+
+$(BIN)$(EXEEXT): $(SRC)
+ $(HOSTCC) $(HOSTCFLAGS) $^ -o $@
+
+../bin/$(BIN)$(EXEEXT): $(BIN)$(EXEEXT)
+ install --mode 0755 $^ $@
+clean:
+ @rm -f $(BIN)$(EXEEXT) ../bin/$(BIN)$(EXEEXT) *~ .*.swp *.o
+ $(call CLEAN)
diff --git a/nuttx/configs/us7032evb1/shterm/shterm.c b/nuttx/configs/us7032evb1/shterm/shterm.c
new file mode 100644
index 000000000..f9ff2994a
--- /dev/null
+++ b/nuttx/configs/us7032evb1/shterm/shterm.c
@@ -0,0 +1,737 @@
+/****************************************************************************
+ * config/us7032evb1/shterm/shterm.c
+ *
+ * Copyright(C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES(INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <sys/stat.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <string.h>
+#include <signal.h>
+#include <ctype.h>
+#include <termios.h>
+#include <fcntl.h>
+#include <stdarg.h>
+#include <errno.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Size of the circular buffer used for interrupt I/O */
+
+#define MAX_FILEPATH 255
+
+#define ENQ 5
+#define ACK 6
+
+#define DEFAULT_BAUD 9600
+
+#define dbg(format, arg...) if (debug > 0) printconsole(format, ##arg)
+#define vdbg(format, arg...) if (debug > 1) printconsole(format, ##arg)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static void sendfile(int fdtarg, char *filename, int verify);
+static void receivefile(int fdtarg, char *filename);
+static void getfilename(int fd, char *name);
+static int readbyte(int fd, char *ch);
+static void writebyte(int fd, char byte);
+static void close_tty(void);
+static void interrupt(int signo);
+static void show_usage(const char *progname, int exitcode);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static int debug = 0;
+static int g_fd = -1;
+static int g_fdnb = -1;
+static FILE *g_logstream = NULL;
+static const char g_dfttydev[] = "/dev/ttyS0";
+static const char *g_ttydev = g_dfttydev;
+static const char *g_logfile = 0;
+static int g_baud = DEFAULT_BAUD;
+static struct termios g_termios;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: putconsole
+ ****************************************************************************/
+
+static void putconsole(char ch)
+{
+ if (g_logstream)
+ {
+ (void)putc(ch, g_logstream);
+ }
+ (void)putchar(ch);
+}
+
+/****************************************************************************
+ * Name: flushconsole
+ ****************************************************************************/
+
+static void flushconsole(void)
+{
+ if (g_logstream)
+ {
+ (void)fflush(g_logstream);
+ }
+ (void)fflush(stdout);
+}
+
+/****************************************************************************
+ * Name: printconsole
+ ****************************************************************************/
+
+static void printconsole(const char *fmt, ...)
+{
+ va_list ap;
+
+ va_start(ap, fmt);
+ if (g_logstream)
+ {
+ (void)vfprintf(g_logstream, fmt, ap);
+ }
+ (void)vprintf(fmt, ap);
+ va_end(ap);
+}
+
+/****************************************************************************
+ * Name: sendfile
+ ****************************************************************************/
+
+static void sendfile(int fdtarg, char *filename, int verify)
+{
+ char chin;
+ char chout;
+ int fdin;
+ int nbytes;
+ int ndots;
+ int ret;
+
+ /* Source the source file */
+
+ fdin = open(filename, O_RDONLY);
+ if (fdin < 0)
+ {
+ fprintf(stderr, "ERROR: Failed to open '%s' for reading\n", filename);
+ (void)writebyte(fdin, '>');
+ return;
+ }
+
+ if (verify)
+ {
+ printconsole("Verifying file '%s':\n", filename);
+ }
+ else
+ {
+ printconsole("Loading file '%s':\n", filename);
+ }
+ flushconsole();
+
+ /* This loop processes each byte from the source file */
+
+ nbytes = 0;
+ ndots = 0;
+ while ((ret = readbyte(fdin, &chout)) == 1)
+ {
+ /* If verbose debug is OFF, then output dots at a low rate */
+
+ if (debug < 2)
+ {
+ if (++nbytes > 64)
+ {
+ nbytes = 0;
+ putconsole('.');
+ if (++ndots > 72)
+ {
+ putconsole('\n');
+ ndots = 0;
+ }
+ flushconsole();
+ }
+ }
+
+ /* If verbose debug is ON, dump everything */
+
+ else if (chout == 'S')
+ {
+ printconsole("\n[%c", chout);
+ }
+ else if (isprint(chout))
+ {
+ printconsole("[%c", chout);
+ }
+ else
+ {
+ printconsole("[.");
+ }
+
+ /* Send the byte to the target */
+
+ writebyte(fdtarg, chout);
+
+ /* Get the response from the target. Loop until the target responds
+ * by either echoing the byte sent or by sending '>'
+ */
+
+ do
+ {
+ ret = readbyte(fdtarg, &chin);
+
+ /* If verbose debug is ON, echo the response from the target */
+
+ if (ret == 1 && debug >= 2)
+ {
+ if (chin != chout)
+ {
+ if (isprint(chin))
+ {
+ putconsole(chin);
+ }
+ else
+ {
+ putconsole('.');
+ }
+ }
+ else
+ {
+ putconsole(']');
+ }
+ }
+
+ /* Check if the target is asking to terminate the transfer */
+
+ if (ret == 1 && chin == '>')
+ {
+ close(fdin);
+ writebyte(fdtarg, ACK);
+ return;
+ }
+ }
+ while (ret == 1 && chin != chout);
+ }
+
+ writebyte(fdtarg, '>');
+ do
+ {
+ ret = readbyte(fdtarg, &chin);
+ }
+ while (ret == 1 && chin != ENQ);
+ close(fdin);
+ writebyte(fdtarg, ACK);
+}
+
+/****************************************************************************
+ * Name: receivefile
+ ****************************************************************************/
+
+static void receivefile(int fdtarg, char *filename)
+{
+ char ch;
+ int fdout;
+ int nbytes;
+ int ndots;
+ int ret;
+
+ fdout = open(filename, O_WRONLY | O_CREAT | O_TRUNC, 0644);
+ if (fdout < 0)
+ {
+ fprintf(stderr, "ERROR: Failed to open '%s' for writing\n", filename);
+ (void)writebyte(fdtarg, '>');
+ return;
+ }
+
+ printconsole("Receiving file '%s':\n", filename);
+ flushconsole();
+ (void)writebyte(fdtarg, '+');
+
+ /* Synchronize */
+
+ do
+ {
+ ret = readbyte(fdtarg, &ch);
+ }
+ while (ret == 1 && ch != 'S' && ch != 'Q');
+
+ nbytes = 0;
+ ndots = 0;
+
+ /* Receive the file */
+
+ while (ret == 1)
+ {
+ /* Check for end-of-file */
+
+ if (ch == '>')
+ {
+ close(fdout);
+ return;
+ }
+
+ writebyte(fdout, ch);
+
+ if (++nbytes > 256)
+ {
+ nbytes = 0;
+ putconsole('.');
+ if (++ndots > 72)
+ {
+ putconsole('\n');
+ ndots = 0;
+ }
+ flushconsole();
+ }
+
+ ret = readbyte(fdtarg, &ch);
+ if (ch == '\r')
+ {
+ writebyte(fdtarg, '+');
+ }
+ }
+
+ close (fdout);
+}
+
+/****************************************************************************
+ * Name: getfilename
+ ****************************************************************************/
+
+static void getfilename(int fd, char *name)
+{
+ char ch;
+ int ret;
+
+ /* Skip over spaces */
+
+ do
+ {
+ ret = readbyte(fd, &ch);
+ }
+ while(ch == ' ' && ret == 1);
+
+ /* Concatenate the filename */
+
+ while(ret == 1 && ch > ' ')
+ {
+ *name++ = ch;
+ ret = readbyte(fd, &ch);
+ }
+ *name++ = 0;
+}
+
+/****************************************************************************
+ * Name: readbyte
+ ****************************************************************************/
+
+static int readbyte(int fd, char *ch)
+{
+ int ret;
+
+ /* Read characters from the console, and echo them to the target tty */
+
+ ret = read(fd, ch, 1);
+ if(ret < 0)
+ {
+ if(errno != EAGAIN)
+ {
+ printconsole("ERROR: Failed to read from fd=%d: %s\n", fd, strerror(errno));
+ close_tty();
+ exit(12);
+ }
+ return -EAGAIN;
+ }
+ else if(ret > 1)
+ {
+ printconsole("ERROR: Unexpected number of bytes read(%d) from fd=%d\n", ret, fd);
+ close_tty();
+ exit(13);
+ }
+ return ret;
+}
+
+/****************************************************************************
+ * Name: writebyte
+ ****************************************************************************/
+
+static void writebyte(int fd, char byte)
+{
+ int ret = write(fd, &byte, 1);
+ if(ret < 0)
+ {
+ printconsole("ERROR: Failed to write to fd=%d: %s\n", fd, strerror(errno));
+ close_tty();
+ exit(14);
+ }
+}
+
+/****************************************************************************
+ * Name: close_tty
+ ****************************************************************************/
+
+static void close_tty(void)
+{
+ int ret;
+
+ if (g_fdnb >= 0)
+ {
+ (void)close(g_fdnb);
+ }
+
+ if (g_fd >= 0)
+ {
+ ret = tcsetattr(g_fd, TCSANOW, &g_termios);
+ if (ret < 0)
+ {
+ printconsole("ERROR: Failed to restore termios for %s: %s\n", g_ttydev, strerror(errno));
+ }
+ (void)close(g_fd);
+ }
+
+ if (g_logstream >= 0)
+ {
+ (void)fclose(g_logstream);
+ }
+}
+
+/****************************************************************************
+ * Name: interrupt
+ ****************************************************************************/
+
+static void interrupt(int signo)
+{
+ printconsole("Exit-ing...\n");
+ close_tty();
+ exit(0);
+}
+
+/****************************************************************************
+ * Name: interrupt
+ ****************************************************************************/
+
+static void show_usage(const char *progname, int exitcode)
+{
+ fprintf(stderr, "\nUSAGE: %s [-h] [-d] [-t <ttyname>] [-b <baud>] [-l <log-file>]\n", progname);
+ fprintf(stderr, "\nWhere:\n");
+ fprintf(stderr, "\t-h: Prints this message then exit.\n");
+ fprintf(stderr, "\t-d: Enable debug output (twice for verbose output).\n");
+ fprintf(stderr, "\t-t <ttyname>: Use <ttyname> device instead of %s.\n", g_dfttydev);
+ fprintf(stderr, "\t-b <baud>: Use <baud> instead of %d.\n", DEFAULT_BAUD);
+ fprintf(stderr, "\t-l <log-file>: Echo console output in <log-file>.\n");
+ exit(exitcode);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int main(int argc, char **argv, char **envp)
+{
+ struct termios tty;
+ char filename[MAX_FILEPATH];
+ char ch;
+ int speed;
+ int opt;
+ int oflags;
+ int ret;
+
+ while((opt = getopt(argc, argv, ":dt:b:hl:")) != -1)
+ {
+ switch(opt)
+ {
+ case 'd':
+ debug++;
+ break;
+
+ case 't':
+ g_ttydev = optarg;
+ break;
+
+ case 'b':
+ g_baud = atoi(optarg);
+ break;
+
+ case 'h':
+ show_usage(argv[0], 0);
+ break;
+
+ case 'l':
+ g_logfile = optarg;
+ break;
+
+ case ':':
+ fprintf(stderr, "ERROR: Missing argument to option '%c'\n", optopt);
+ show_usage(argv[0], 1);
+ break;
+
+ case '?':
+ fprintf(stderr, "ERROR: Unrecognized option '%c'\n", optopt);
+ show_usage(argv[0], 2);
+ break;
+ }
+ }
+
+ if(optind < argc)
+ {
+ fprintf(stderr, "ERROR: Unexpected arguments at end of line\n");
+ show_usage(argv[0], 3);
+ }
+
+ switch(g_baud)
+ {
+ case 0: speed = B0; break;
+ case 50: speed = B50; break;
+ case 75: speed = B75; break;
+ case 110: speed = B110; break;
+ case 134: speed = B134; break;
+ case 150: speed = B150; break;
+ case 200: speed = B200; break;
+ case 300: speed = B300; break;
+ case 600: speed = B600; break;
+ case 1200: speed = B1200; break;
+ case 1800: speed = B1800; break;
+ case 2400: speed = B2400; break;
+ case 4800: speed = B4800; break;
+ case 9600: speed = B9600; break;
+ case 19200: speed = B19200; break;
+ case 38400: speed = B38400; break;
+ case 57600: speed = B57600; break;
+ case 115200: speed = B115200; break;
+ case 230400: speed = B230400; break;
+
+ default:
+ fprintf(stderr, "ERROR: Unsupported BAUD=%d\n", g_baud);
+ show_usage(argv[0], 4);
+ }
+
+ /* Was a log file specified? */
+
+ if (g_logfile)
+ {
+ g_logstream = fopen(g_logfile, "w");
+ if (!g_logstream)
+ {
+ fprintf(stderr, "ERROR: Failed to open '%s' for writing\n", g_logfile);
+ return 5;
+ }
+ }
+
+ /* Set the host stdin to O_NONBLOCK */
+
+ oflags = fcntl(0, F_GETFL, 0);
+ if(oflags == -1)
+ {
+ fprintf(stderr, "ERROR: fnctl(F_GETFL) failed: %s\n", strerror(errno));
+ return 6;
+ }
+
+ ret = fcntl(0, F_SETFL, oflags | O_NONBLOCK);
+ if(ret < 0)
+ {
+ fprintf(stderr, "ERROR: fnctl(F_SETFL) failed: %s\n", strerror(errno));
+ return 7;
+ }
+
+ /* Open the selected serial port (blocking)*/
+
+ g_fd = open(g_ttydev, O_RDWR);
+ if(g_fd < 0)
+ {
+ printconsole("ERROR: Failed to open %s: %s\n", g_ttydev, strerror(errno));
+ return 8;
+ }
+
+ /* Configure the serial port in at the selected baud in 8-bit, no-parity, raw mode
+ * and turn off echo, etc.
+ */
+
+ ret = tcgetattr(g_fd, &g_termios);
+ if(ret < 0)
+ {
+ printconsole("ERROR: Failed to get termios for %s: %s\n", g_ttydev, strerror(errno));
+ close(g_fd);
+ return 9;
+ }
+
+ memcpy(&tty, &g_termios, sizeof(struct termios));
+ tty.c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL|IXON);
+ tty.c_oflag &= ~OPOST;
+ tty.c_lflag &= ~(ECHO|ECHONL|ICANON|ISIG|IEXTEN);
+ tty.c_cflag &= ~(CSIZE|PARENB);
+ tty.c_cflag |= CS8;
+
+ (void)cfsetispeed(&tty, speed);
+ (void)cfsetospeed(&tty, speed);
+
+ ret = tcsetattr(g_fd, TCSANOW, &tty);
+ if(ret < 0)
+ {
+ printconsole("ERROR: Failed to set termios for %s: %s\n", g_ttydev, strerror(errno));
+ close(g_fd);
+ return 10;
+ }
+
+#if 1
+ /* Open the selected serial port (non-blocking)*/
+
+ g_fdnb = open(g_ttydev, O_RDONLY | O_NONBLOCK);
+ if(g_fdnb < 0)
+ {
+ printconsole("ERROR: Failed to open %s: %s\n", g_ttydev, strerror(errno));
+ return 11;
+ }
+#else
+ /* Create a non-blocking copy of the configure tty descriptor */
+
+ g_fdnb = dup(g_fd);
+ if (g_fdnb < 0)
+ {
+ printconsole("ERROR: Failed to dup %s fd=%d: %s\n", g_ttydev, g_fd, strerror(errno));
+ close_tty();
+ return 12;
+ }
+
+ oflags = fcntl(g_fdnb, F_GETFL, 0);
+ if(oflags == -1)
+ {
+ fprintf(stderr, "ERROR: fnctl(F_GETFL) failed: %s\n", strerror(errno));
+ close_tty();
+ return 13;
+ }
+
+ ret = fcntl(g_fdnb, F_SETFL, oflags | O_NONBLOCK);
+ if(ret < 0)
+ {
+ fprintf(stderr, "ERROR: fnctl(F_SETFL) failed: %s\n", strerror(errno));
+ close_tty();
+ return 14;
+ }
+#endif
+
+ /* Catch attempts to control-C out of the program so that we can restore
+ * the TTY settings.
+ */
+
+ signal(SIGINT, interrupt);
+
+ /* Loopo until control-C */
+
+ for(;;)
+ {
+ /* Read characters from the console, and echo them to the target tty */
+
+ ret = readbyte(0, &ch);
+ if (ret == 0)
+ {
+ printconsole("End-of-file: exitting\n");
+ close_tty();
+ return 0;
+ }
+ else if (ret == 1)
+ {
+ writebyte(g_fd, ch);
+ }
+
+ /* Read characters from target TTY and echo them on the console */
+
+ ret = readbyte(g_fdnb, &ch);
+ if (ret == 0)
+ {
+ printconsole("ERROR: Unexpected number of bytes read(%d) from %s\n", ret, g_ttydev);
+ close_tty();
+ return 15;
+ }
+ else if (ret == 1)
+ {
+ if (ch == ENQ)
+ {
+ char ch1;
+ char ch2;
+
+ writebyte(g_fd, '*');
+ ret = readbyte(g_fd, &ch1);
+ if (ret != 1)
+ {
+ printconsole("ERROR: Unexpected number of bytes read(%d) from %s\n", ret, g_ttydev);
+ close_tty();
+ return 15;
+ }
+ ret = readbyte(g_fd, &ch2);
+ if (ret != 1)
+ {
+ printconsole("ERROR: Unexpected number of bytes read(%d) from %s\n", ret, g_ttydev);
+ close_tty();
+ return 16;
+ }
+
+ getfilename(g_fd, filename);
+
+ if (ch1 == 'l' || ch1 == 'L')
+ {
+ sendfile(g_fd, filename, 0);
+ }
+ else if (ch1 == 'v' || ch1 == 'v')
+ {
+ sendfile(g_fd, filename, 1);
+ }
+ else if (ch1 == 's' || ch1 == 'S')
+ {
+ receivefile(g_fd, filename);
+ }
+ }
+ else
+ {
+ putconsole(ch);
+ flushconsole();
+ }
+ }
+ }
+ return 0;
+}
diff --git a/nuttx/configs/us7032evb1/src/Makefile b/nuttx/configs/us7032evb1/src/Makefile
new file mode 100644
index 000000000..4ced0ac9e
--- /dev/null
+++ b/nuttx/configs/us7032evb1/src/Makefile
@@ -0,0 +1,77 @@
+############################################################################
+# configs/us7032evb1/src/Makefile
+#
+# Copyright (C) 2008 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+CSRCS = up_leds.c
+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)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @rm -f libboard$(LIBEXT) *~ .*.swp
+ $(call CLEAN)
+
+distclean: clean
+ @rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/configs/us7032evb1/src/README.txt b/nuttx/configs/us7032evb1/src/README.txt
new file mode 100644
index 000000000..e55f25d13
--- /dev/null
+++ b/nuttx/configs/us7032evb1/src/README.txt
@@ -0,0 +1,3 @@
+This directory contains drivers unique to the Hitachi SH-1 Low-Cost
+Evaluation Board, US7032EVB1
+
diff --git a/nuttx/configs/us7032evb1/src/up_leds.c b/nuttx/configs/us7032evb1/src/up_leds.c
new file mode 100644
index 000000000..d532bc355
--- /dev/null
+++ b/nuttx/configs/us7032evb1/src/up_leds.c
@@ -0,0 +1,135 @@
+/****************************************************************************
+ * configs/us7032evb1/src/up_leds.c
+ *
+ * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <stdint.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* The SH1_LPEVB only a single LED controlled by either port A, pin 15, or
+ * port B, pin 15 (selectable via JP8). In this file, we assume the portB
+ * setup.
+ */
+
+#define SH1_PBDR_LED 0x8000
+#define SH1_PBIOR_LED 0x8000
+#define SH1_PBCR2_LED 0xc000
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_ledinit
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void up_ledinit(void)
+{
+ uint16_t reg16;
+
+ /* Setup port B, pin 15 as an output */
+
+ reg16 = getreg16(SH1_PFC_PBIOR);
+ reg16 |= SH1_PBIOR_LED;
+ putreg16(reg16, SH1_PFC_PBIOR);
+
+ /* Setup port B, pin 15 as a normal I/O register */
+
+ reg16 = getreg16(SH1_PFC_PBCR1);
+ reg16 &= ~SH1_PBCR2_LED;
+ putreg16(reg16, SH1_PFC_PBCR1);
+
+ /* Turn the LED off */
+
+ reg16 = getreg16(SH1_PORTB_DR);
+ reg16 &= ~SH1_PBDR_LED;
+ putreg16(reg16, SH1_PORTB_DR);
+}
+
+/****************************************************************************
+ * Name: up_ledon
+ ****************************************************************************/
+
+void up_ledon(int led)
+{
+ uint16_t reg16;
+
+ if (led)
+ {
+ /* Turn the LED on */
+
+ reg16 = getreg16(SH1_PORTB_DR);
+ reg16 |= SH1_PBDR_LED;
+ putreg16(reg16, SH1_PORTB_DR);
+ }
+}
+
+/****************************************************************************
+ * Name: up_ledoff
+ ****************************************************************************/
+
+void up_ledoff(int led)
+{
+ uint16_t reg16;
+
+ if (led)
+ {
+ /* Turn the LED off */
+
+ reg16 = getreg16(SH1_PORTB_DR);
+ reg16 &= ~SH1_PBDR_LED;
+ putreg16(reg16, SH1_PORTB_DR);
+ }
+}
+#endif /* CONFIG_ARCH_LEDS */