summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-04-29 21:29:30 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-04-29 21:29:30 +0000
commit6463ba69dad3e46bde7b61c0d31262fd26a954b8 (patch)
tree5e00202991a2ea33cf79ac787e6c28c209bcae66 /nuttx
parentd712452b2adfbdd2b6aaee11e88b176f8911d718 (diff)
downloadpx4-nuttx-6463ba69dad3e46bde7b61c0d31262fd26a954b8.tar.gz
px4-nuttx-6463ba69dad3e46bde7b61c0d31262fd26a954b8.tar.bz2
px4-nuttx-6463ba69dad3e46bde7b61c0d31262fd26a954b8.zip
Initial lpc214x support
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@193 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/include/lpc214x/irq.h86
-rw-r--r--nuttx/arch/arm/src/lpc214x/Make.defs48
-rw-r--r--nuttx/arch/arm/src/lpc214x/README.txt61
-rw-r--r--nuttx/arch/arm/src/lpc214x/Startup.s80
-rw-r--r--nuttx/arch/arm/src/lpc214x/chip.h104
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c112
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_head.S465
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_irq.c115
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_lowputc.S91
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c94
-rw-r--r--nuttx/configs/mcu123-lpc214x/Make.defs71
-rw-r--r--nuttx/configs/mcu123-lpc214x/defconfig248
-rw-r--r--nuttx/configs/mcu123-lpc214x/include/README.txt1
-rw-r--r--nuttx/configs/mcu123-lpc214x/include/board.h59
-rw-r--r--nuttx/configs/mcu123-lpc214x/ld.script84
-rwxr-xr-xnuttx/configs/mcu123-lpc214x/setenv.sh46
-rw-r--r--nuttx/configs/mcu123-lpc214x/src/Makefile79
-rw-r--r--nuttx/configs/mcu123-lpc214x/src/README.txt2
-rw-r--r--nuttx/configs/mcu123-lpc214x/src/up_leds.c84
19 files changed, 1930 insertions, 0 deletions
diff --git a/nuttx/arch/arm/include/lpc214x/irq.h b/nuttx/arch/arm/include/lpc214x/irq.h
new file mode 100644
index 000000000..f517e30a7
--- /dev/null
+++ b/nuttx/arch/arm/include/lpc214x/irq.h
@@ -0,0 +1,86 @@
+/************************************************************
+ * arch/lpc214x/irq.h
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 Gregory Nutt 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.
+ *
+ ************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through nuttx/irq.h
+ */
+
+#ifndef __ARCH_LPC214X_IRQ_H
+#define __ARCH_LPC214X_IRQ_H
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/* LPC214X Interrupts */
+
+#define NR_IRQS 16
+
+/************************************************************
+ * Public Types
+ ************************************************************/
+
+/************************************************************
+ * Inline functions
+ ************************************************************/
+
+/************************************************************
+ * Public Variables
+ ************************************************************/
+
+/************************************************************
+ * Public Function Prototypes
+ ************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_LPC214X_IRQ_H */
+
diff --git a/nuttx/arch/arm/src/lpc214x/Make.defs b/nuttx/arch/arm/src/lpc214x/Make.defs
new file mode 100644
index 000000000..30843b6ba
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc214x/Make.defs
@@ -0,0 +1,48 @@
+############################################################################
+# lpc214x/Make.defs
+#
+# Copyright (C) 2007 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# 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 Gregory Nutt 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.
+#
+############################################################################
+
+HEAD_ASRC = lpc214x_head.S
+
+CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_vectors.S
+CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
+ up_createstack.c up_dataabort.c up_delay.c up_exit.c \
+ up_idle.c up_initialize.c up_initialstate.c \
+ up_interruptcontext.c up_prefetchabort.c up_releasepending.c \
+ up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \
+ up_sigdeliver.c up_syscall.c up_unblocktask.c \
+ up_undefinedinsn.c up_usestack.c
+
+CHIP_ASRCS = lpc214x_lowputc.S
+CHIP_CSRCS = lpc214x_decodeirq.c lpc214x_irq.c lpc214x_timerisr.c
diff --git a/nuttx/arch/arm/src/lpc214x/README.txt b/nuttx/arch/arm/src/lpc214x/README.txt
new file mode 100644
index 000000000..9cfc99593
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc214x/README.txt
@@ -0,0 +1,61 @@
+General Description
+^^^^^^^^^^^^^^^^^^^
+
+http://www.nxp.com/pip/LPC2141FBD64.html:
+
+The LPC2141/42/44/46/48 microcontrollers are based on a 16-bit/32-bit ARM7TDMI-S
+CPU with real-time emulation and embedded trace support, that combine
+microcontroller with embedded high-speed flash memory ranging from 32 kB to
+512 kB. A 128-bit wide memory interface and a unique accelerator architecture
+enable 32-bit code execution at the maximum clock rate. For critical code size
+applications, the alternative 16-bit Thumb mode reduces code by more than 30 pct
+with minimal performance penalty.
+
+Due to their tiny size and low power consumption, LPC2141/42/44/46/48 are ideal
+for applications where miniaturization is a key requirement, such as access
+control and point-of-sale. Serial communications interfaces ranging from a USB 2.0
+Full-speed device, multiple UARTs, SPI, SSP to I2C-bus and on-chip SRAM of 8 kB
+up to 40 kB, make these devices very well suited for communication gateways and
+protocol converters, soft modems, voice recognition and low end imaging, providing
+both large buffer size and high processing power. Various 32-bit timers, single
+or dual 10-bit ADC(s), 10-bit DAC, PWM channels and 45 fast GPIO lines with up
+to nine edge or level sensitive external interrupt pins make these microcontrollers
+suitable for industrial control and medical systems.
+
+
+Features
+^^^^^^^^
+
+o 16-bit/32-bit ARM7TDMI-S microcontroller in a tiny LQFP64 package.
+o 8 kB to 40 kB of on-chip static RAM and 32 kB to 512 kB of on-chip flash memory.
+ 128-bit wide interface/accelerator enables high-speed 60 MHz operation.
+o In-System Programming/In-Application Programming (ISP/IAP) via on-chip boot
+ loader software. Single flash sector or full chip erase in 400 ms and programming
+ of 256 B in 1 ms.
+o EmbeddedICE RT and Embedded Trace interfaces offer real-time debugging with the
+ on-chip RealMonitor software and high-speed tracing of instruction execution.
+o USB 2.0 Full-speed compliant device controller with 2 kB of endpoint RAM. In addition,
+ the LPC2146/48 provides 8 kB of on-chip RAM accessible to USB by DMA.
+o One or two (LPC2141/42 vs. LPC2144/46/48) 10-bit ADCs provide a total of 6/14 analog
+ inputs, with conversion times as low as 2.44 us per channel.
+o Single 10-bit DAC provides variable analog output (LPC2142/44/46/48 only).
+o Two 32-bit timers/external event counters (with four capture and four compare
+ channels each), PWM unit (six outputs) and watchdog.
+o Low power Real-Time Clock (RTC) with independent power and 32 kHz clock input.
+o Multiple serial interfaces including two UARTs (16C550), two Fast I2C-bus (400
+ kbit/s), SPI and SSP with buffering and variable data length capabilities.
+o Vectored Interrupt Controller (VIC) with configurable priorities and vector addresses.
+o Up to 45 of 5 V tolerant fast general purpose I/O pins in a tiny LQFP64 package.
+o Up to 21 external interrupt pins available.
+o 60 MHz maximum CPU clock available from programmable on-chip PLL with settling
+ time of 100 us.
+o On-chip integrated oscillator operates with an external crystal from 1 MHz to 25 MHz.
+o Power saving modes include Idle and Power-down.
+o Individual enable/disable of peripheral functions as well as peripheral clock scaling
+ for additional power optimization.
+o Processor wake-up from Power-down mode via external interrupt or BOD.
+o Single power supply chip with POR and BOD circuits:
+o CPU operating voltage range of 3.0 V to 3.6 V (3.3 V +- 10 pct) with 5 V tolerant
+ I/O pads.
+
+
diff --git a/nuttx/arch/arm/src/lpc214x/Startup.s b/nuttx/arch/arm/src/lpc214x/Startup.s
new file mode 100644
index 000000000..ecf692747
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc214x/Startup.s
@@ -0,0 +1,80 @@
+/*
+ * The STARTUP.S code is executed after CPU Reset. This file may be
+ * translated with the following SET symbols. In uVision these SET
+ * symbols are entered under Options - ASM - Set.
+ *
+ * REMAP: when set the startup code initializes the register MEMMAP
+ * which overwrites the settings of the CPU configuration pins. The
+ * startup and interrupt vectors are remapped from:
+ * 0x00000000 default setting (not remapped)
+ * 0x80000000 when EXTMEM_MODE is used
+ * 0x40000000 when RAM_MODE is used
+ *
+ * EXTMEM_MODE: when set the device is configured for code execution
+ * from external memory starting at address 0x80000000. The startup
+ * vectors are located to 0x80000000.
+ *
+ * RAM_MODE: when set the device is configured for code execution
+ * from on-chip RAM starting at address 0x40000000. The startup
+ * vectors are located to 0x40000000.
+ */
+
+Reset_Handler:
+
+
+
+/* Memory Mapping */
+
+
+/* Setup Stack for each mode */
+ ldr r0, =Top_Stack
+
+/* Enter Undefined Instruction Mode and set its Stack Pointer */
+ msr CPSR_c, #UND_MODE | PSR_I_BIT | PSR_F_BIT
+ mov SP, r0
+ sub r0, r0, #UND_Stack_Size
+
+/* Enter Abort Mode and set its Stack Pointer */
+ msr CPSR_c, #ABT_MODE | PSR_I_BIT | PSR_F_BIT
+ mov SP, r0
+ sub r0, r0, #ABT_Stack_Size
+
+/* Enter FIQ Mode and set its Stack Pointer */
+ msr CPSR_c, #FIQ_MODE | PSR_I_BIT | PSR_F_BIT
+ mov SP, r0
+ sub r0, r0, #FIQ_Stack_Size
+
+/* Enter IRQ Mode and set its Stack Pointer */
+ msr CPSR_c, #IRQ_MODE | PSR_I_BIT | PSR_F_BIT
+ mov SP, r0
+ sub r0, r0, #IRQ_Stack_Size
+
+/* Enter Supervisor Mode and set its Stack Pointer */
+ msr CPSR_c, #SVC_MODE | PSR_I_BIT | PSR_F_BIT
+ mov SP, r0
+ sub r0, r0, #SVC_Stack_Size
+
+/* Enter User Mode and set its Stack Pointer */
+ msr CPSR_c, #USR_MODE
+ mov SP, r0
+
+/* Enter the C code */
+ ldr r0,=?C?INIT
+ tst r0,#1 ; Bit-0 set: INIT is Thumb
+ ldreq LR,=exit?A ; ARM Mode
+ ldrne LR,=exit?T ; Thumb Mode
+ bx r0
+ ENDP
+
+PUBLIC exit?A
+exit?A PROC CODE32
+ B exit?A
+ ENDP
+
+PUBLIC exit?T
+exit?T PROC CODE16
+exit: B exit?T
+ ENDP
+
+
+ END
diff --git a/nuttx/arch/arm/src/lpc214x/chip.h b/nuttx/arch/arm/src/lpc214x/chip.h
new file mode 100644
index 000000000..09f0ba342
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc214x/chip.h
@@ -0,0 +1,104 @@
+/************************************************************************************
+ * lpc214x/chip.h
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 Gregory Nutt 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 __LPC214X_CHIP_H
+#define __LPC214X_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+/* Memory Map ***********************************************************************/
+
+#define LPC214X_FLASH_BASE 0x00000000
+#define LPC214X_ONCHIP_RAM_BASE 0x40000000
+#define LPC214X_EXTMEM_BASE 0x80000000
+
+/* Interrupts **********************************************************************/
+
+/* Peripheral Registers ************************************************************/
+
+/* Register block base addresses */
+
+#define LPC214X_MAM_BASE 0xe01fc000 /* Memory Accelerator Module (MAM) Base Address */
+#define LPC214X_MEMMAP 0xe01fc040 /* Memory Mapping Control */
+#define LPC214X_PLL_BASE 0xe01fc080 /* Phase Locked Loop (PLL) Base Address */
+#define LPC214X_VPBDIV 0xe01fc100 /* VPBDIV Address */
+#define LPC214X_PINSEL2 0xe002c014 /* PINSEL2 Address */
+#define LPC214X_EMC_BASE 0xffe00000 /* External Memory Controller (EMC) Base Address */
+
+/* Memory Accelerator Module (MAM) Regiser Offsets */
+
+#define LPC214X_MAMCR_OFFSET 0x00 /* MAM Control Offset*/
+#define LPC214x_MAMTIM_OFFSET 0x04 /* MAM Timing Offset */
+
+/* Phase Locked Loop (PLL) register offsets */
+
+#define LPC214X_PLLCON_OFFSET 0x00 /* PLL Control Offset*/
+#define LPC214X_PLLCFG_OFFSET 0x04 /* PLL Configuration Offset */
+#define LPC214X_PLLSTAT_OFFSET 0x08 /* PLL Status Offset */
+#define LPC214X_PLLFEED_OFFSET 0x0c /* PLL Feed Offset */
+
+/* PLL Control Register Bit Settings */
+
+#define LPC214X_PLLCON_PLLE (1<<0) /* PLL Enable */
+#define LPC214X_PLLCON_PLLC (1<<1) /* PLL Connect */
+
+/* PLL Configuration Register Bit Settings */
+
+#define LPC214X_PLLCFG_MSEL (0x1f<<0) /* PLL Multiplier */
+#define LPC214X_PLLCFG_PSEL (0x03<<5) /* PLL Divider */
+#define LPC214X_PLLSTAT_PLOCK (1<<10) /* PLL Lock Status */
+
+/* External Memory Controller (EMC) definitions */
+
+#define LPC214X_BCFG0_OFFSET 0x00 /* BCFG0 Offset */
+#define LPC214X_BCFG1_OFFSET 0x04 /* BCFG1 Offset */
+#define LPC214X_BCFG2_OFFSET 0x08 /* BCFG2 Offset */
+#define LPC214X_BCFG3_OFFSET 0x0c /* BCFG3 Offset */
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Global Function Prototypes
+ ************************************************************************************/
+
+#endif /* __LPC214X_CHIP_H */
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c b/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c
new file mode 100644
index 000000000..9ac9f9fc6
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c
@@ -0,0 +1,112 @@
+/********************************************************************************
+ * lpc214x/lpc214x_decodeirq.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 Gregory Nutt 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 <sys/types.h>
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <assert.h>
+#include <debug.h>
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+/********************************************************************************
+ * Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Data
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Data
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Funtions
+ ********************************************************************************/
+
+void up_decodeirq(uint32* regs)
+{
+#ifdef CONFIG_SUPPRESS_INTERRUPTS
+ lib_lowprintf("Unexpected IRQ\n");
+ current_regs = regs;
+ PANIC(OSERR_ERREXCEPTION);
+#else
+
+ /* Decode the interrupt. First, fetch the interrupt id register. */
+
+ int irq = 0;
+#warning "Need to decode the interrupt here"
+
+ /* Verify that the resulting IRQ number is valie */
+
+ if ((unsigned)irq < NR_IRQS)
+ {
+ /* Mask and acknowledge the interrupt */
+
+ up_maskack_irq(irq);
+
+ /* Current regs non-zero indicates that we are processing an interrupt;
+ * current_regs is also used to manage interrupt level context switches.
+ */
+
+ current_regs = regs;
+
+ /* Deliver the IRQ */
+
+ irq_dispatch(irq, regs);
+
+ /* Indicate that we are no long in an interrupt handler */
+
+ current_regs = NULL;
+
+ /* Unmask the last interrupt (global interrupts are still
+ * disabled.
+ */
+
+ up_enable_irq(irq);
+ }
+#endif
+}
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_head.S b/nuttx/arch/arm/src/lpc214x/lpc214x_head.S
new file mode 100644
index 000000000..f52d6730a
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_head.S
@@ -0,0 +1,465 @@
+/********************************************************************
+ * lpc214x/lpc214x_head.S
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 Gregory Nutt 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 "up_internal.h"
+#include "up_arch.h"
+
+/********************************************************************
+ * Definitions
+ ********************************************************************/
+
+/* This file holds the NuttX start logic that runs when the LPC2148
+ * is reset. This logic must be located at address 0x0000:0000 in
+ * flash but may be linked to run at different locations based on
+ * the selected mode:
+ *
+ * default: Executes from 0x0000:0000. In non-default modes, the
+ * MEMAP register is set override the settings of the CPU configuration
+ * pins.
+ *
+ * CONFIG_EXTMEM_MODE: Code executes from external memory starting at
+ * address 0x8000:0000.
+ *
+ * CONFIG_RAM_MODE: Code executes from on-chip RAM at address
+ * 0x4000:0000.
+ *
+ * Starupt Code must be linked to run at the correct address
+ * corresponding to the selected mode.
+ */
+
+#if defined(CONFIG_EXTMEM_MODE)
+# if CONFIG_CODE_BASE != LPC214X_EXTMEM_BASE
+# error "CONFIG_CODE_BASE must be 0x80000000 in EXTMEM mode"
+# endif
+#elif defined(CONFIG_RAM_MODE)
+# if CONFIG_CODE_BASE != LPC214X_ONCHIP_RAM_BASE
+# error "CONFIG_CODE_BASE must be 0x40000000 in EXTMEM mode"
+# endif
+#else
+# if CONFIG_CODE_BASE != LPC214X_FLASH_BASE
+# error "CONFIG_CODE_BASE must be 0x00000000 in default mode"
+# endif
+#endif
+
+/* Phase Locked Loop (PLL) initialization values
+ *
+ * <e> PLL Setup
+ * <i>
+ * <i> CCLK - Processor Clock
+ * <i> Fcco - PLL Oscillator
+ * <o1.0..4> MSEL: PLL Multiplier Selection
+ * <1-32><#-1>
+ * <i> PLL Multiplier "M" Value
+ * <i> CCLK = M * Fosc
+ * <o1.5..6> PSEL: PLL Divider Selection
+ * <0=> 1 <1=> 2 <2=> 4 <3=> 8
+ * <i> PLL Divider "P" Value
+ * <i> Fcco = CCLK * 2 * P
+ * <i> 156MHz <= Fcco <= 320MHz
+ * </e>
+*/
+#defin LPC214X_PLLCFG_VALUE 0x00000024
+
+/* Memory Accelerator Module (MAM) initialization values
+ *
+ * MAM Control Register
+ * BIT 0:1 Mode
+ * 0 = Disabled
+ * 1 = Partially Enabled
+ * 2 = Fully Enabled
+ * MAM Timing Register
+ * BIT 0:2 Fetch Cycles
+ * 0 = Reserved
+ * 1 = 1
+ * 2 = 2
+ * 3 = 3
+ * 4 = 4
+ * 5 = 5
+ * 6 = 6
+ * 7 = 7
+ */
+
+#define LPC214X_MAMCR_VALUE 0x00000002
+#define LPC214x_MAMTIM_VALUE 0x00000004
+
+/* VPBDIV initialization values
+ *
+ * BITS 0:1 VPB Peripheral Bus Clock Rate
+ * 0 = VPB Clock = CPU Clock / 4
+ * 1 = VPB Clock = CPU Clock
+ * 2 = VPB Clock = CPU Clock / 2
+ * BITS 4:5 XCLKDIV: XCLK Pin
+ * 0 = XCLK Pin = CPU Clock / 4
+ * 1 = XCLK Pin = CPU Clock
+ * 2 = XCLK Pin = CPU Clock / 2
+ */
+
+#define LPC214X_VPBDIV_VALUE 0x00000001
+
+/* External Memory Pins definitions
+ *
+ * CS0..3, OE, WE, BLS0..3, D0..31, A2..23, JTAG Pins
+ */
+
+#define LPC214X_PINSEL2_VALUE 0x0e6149e4
+
+/* External Memory Controller (EMC) initialization values
+ *
+ * Bank Configuration n (BCFG0..3)
+ * BIT 0:3 IDCY: Idle Cycles (0-15)
+ * BIT 5:9 WST1: Wait States 1 (0-31)
+ * BIT 11:15 WST2: Wait States 2 (0-31)
+ * BIT 10 RBLE: Read Byte Lane Enable
+ * BIT 26 WP: Write Protect
+ * BIT 27 BM: Burst ROM
+ * BIT 28:29 MW: Memory Width (0=8-bit 1=16-bit 2=32-bit 3=Reserved)
+ */
+
+#define LPC214X_BCFG0_VALUE 0x0000fbef
+#define LPC214X_BCFG1_VALUE 0x0000fbef
+#define LPC214X_BCFG2_VALUE 0x0000fbef
+#define LPC214X_BCFG3_VALUE 0x0000fbef
+
+/********************************************************************
+ * Macros
+ ********************************************************************/
+
+/* Print a character on the UART to show boot status. This macro will
+ * modify r0, r1, r2 and r14
+ */
+
+ .macro showprogress, code
+#ifdef CONFIG_DEBUG
+ mov r0, #\code
+ bl up_lowputc
+#endif
+ .endm
+
+/* Configured the PINSEL2 register if EXTMEM mode is selected */
+
+ .macro configpinsel2, base, val
+#ifdef CONFIG_EXTMEM_MODE
+ ldr \base, =LPC214X_PINSEL2
+ ldr \val, =LPC214X_PINSEL2_VALUE
+ str \val, [\base]
+#endif
+ .endm
+
+/* Configure the external memory controller */
+
+ .macro configemc, base, val
+#ifdef CONFIG_EMC_SETUP
+ ldr \base, =LPC214X_EMC_BASE
+
+#ifdef CONFIG_BCFG0_SETUP
+ ldr \val, =LPC214X_BCFG0_VALUE
+ str \val, [\base, #LPC214X_BCFG0_OFFSET]
+#endif
+
+#ifdef CONFIG_BCFG1_SETUP
+ ldr \val, =LPC214X_BCFG1_VALUE
+ str \val, [\base, #LPC214X_BCFG1_OFFSET]
+#endif
+
+#ifdef CONFIG_BCFG2_SETUP
+ ldr \val, =LPC214X_BCFG2_VALUE
+ str \val, [\base, #LPC214X_BCFG2_OFFSET]
+#endif
+
+#ifdef CONFIG_BCFG3_SETUP
+ ldr \val, =LPC214X_BCFG3_VALUE
+ str \val, [\base, #LPC214X_BCFG3_OFFSET]
+#endif
+#endif
+ .endm
+
+/* Configure VPBDIV */
+
+ .macro configvpbdiv, base, val
+#ifdef CONFIG_VPBDIV_SETUP
+ ldr \base, =LPC214X_VPBDIV
+ ldr \val, =LPC214X_VPBDIV_VALUE
+ str \val, [\base]
+#endif
+ .endm
+
+/* Configure the PLL */
+
+ .macro configpll, base, val1, val2, val3
+#ifdef LPC214X_PLL_SETUP
+ ldr \base, =LPC214X_PLL_BASE
+ mov \val1, #0xaa
+ mov \val2, #0x55
+
+ /* Configure and Enable PLL */
+
+ mov \val3, #LPC214X_PLLCFG_VALUE
+ str \val3, [\base, #LPC214X_PLLCFG_OFFSET]
+ mov \val3, #LPC214X_PLLCON_PLLE
+ str \val3, [\base, #LPC214X_PLLCON_OFFSET]
+ str \val1, [\base, #LPC214X_PLLFEED_OFFSET]
+ str \val2, [\base, #LPC214X_PLLFEED_OFFSET]
+
+ /* Wait until PLL Locked */
+1:
+ ldr \val3, [\base, #LPC214X_PLLSTAT_OFFSET]
+ ands \val3, \val3, #LPC214X_PLLSTAT_PLOCK
+ beq 1b
+
+ /* Switch to PLL Clock */
+
+ mov \val3, #(LPC214X_PLLCON_PLLE | LPC214X_PLLCON_PLLC)
+ str \val3, [\base, #LPC214X_PLLCON__OFFSET]
+ str \val1, [\base, #LPC214X_PLLFEED_OFFSET]
+ str \val2, [\base, #LPC214X_PLLFEED_OFFSET]
+#endif
+ .endm
+
+/* Configure the Memory Accelerator Module (MAM) */
+
+ .macro configmam, base, val
+#ifdef CONFIG_MAM_SETUP
+ ldr \base, =LPC214X_MAM_BASE
+ mov \val, #LPC214x_MAMTIM_VALUE
+ str \val, [\base, #LPC214x_MAMTIM_OFFSET]
+ mov \val, #LPC214X_MAMCR_VALUE
+ str \val, [\base, #LPC214X_MAMCR_OFFSET]
+#endif
+ .endm
+
+/* Setup MEMMAP for the selected mode of operation */
+
+ .macro configmemmap, base, val
+ ldr r0, =LPC214X_MEMMAP
+#if defined(CONFIG_EXTMEM_MODE)
+ mov r1, #3
+#elif defined(CONFIG_RAM_MODE)
+ mov r1, #2
+#else /* Setting the default should not be necessary */
+ mov r1, #1
+#endif
+ str r1, [r0]
+ .endm
+
+/********************************************************************
+ * Text
+ ********************************************************************/
+
+ .text
+
+/********************************************************************
+ * Name: _vector_table
+ *
+ * Description:
+ * Interrrupt vector table. This must be located at the beginning
+ * of the memory space (at CONFIG_CODE_BASE). The first entry in
+ * the vector table is the reset vector and this is the code that
+ * will execute whn the processor is reset.
+ *
+ ********************************************************************/
+
+ .globl _vector_table
+ .type _vector_table, %function
+_vector_table:
+ ldr pc, .Lresethandler /* 0x00: Reset */
+ ldr pc, .Lundefinedhandler /* 0x04: Undefined instruction */
+ ldr pc, .Lswihandler /* 0x08: Software interrupt */
+ ldr pc, .Lprefetchaborthandler /* 0x0c: Prefetch abort */
+ ldr pc, .Ldataaborthandler /* 0x10: Data abort */
+ ldr pc, .Laddrexcptnhandler /* 0x14: Address exception */
+ ldr pc, .Lirqhandler /* 0x18: IRQ */
+ ldr pc, .Lfiqhandler /* 0x1c: FIQ */
+
+ .globl __start
+ .globl up_vectorundefinsn
+ .globl up_vectorswi
+ .globl up_vectorprefetch
+ .globl up_vectordata
+ .globl up_vectoraddrexcptn
+ .globl up_vectorirq
+ .globl up_vectorfiq
+
+.Lresethandler:
+ .long __start
+.Lundefinedhandler:
+ .long up_vectorundefinsn
+.Lswihandler:
+ .long up_vectorswi
+.Lprefetchaborthandler:
+ .long up_vectorprefetch
+.Ldataaborthandler:
+ .long up_vectordata
+.Laddrexcptnhandler:
+ .long up_vectoraddrexcptn
+.Lirqhandler:
+ .long up_vectorirq
+.Lfiqhandler:
+ .long up_vectorfiq
+ .size _vector_table, . - _vector_table
+ .end
+
+/********************************************************************
+ * Name: __start
+ *
+ * Description:
+ * Reset entry point. This is the first function to execute when
+ * the processor is reset. It initializes hardware and then gives
+ * control to NuttX.
+ *
+ ********************************************************************/
+
+ .global __start
+ .type __start, #function
+
+__start:
+ /* Setup the initial processor mode */
+
+ mov r0, #(SVC_MODE | PSR_I_BIT | PSR_F_BIT )
+ msr cpsr, r0
+
+ /* Set up external memory mode (if so selected) */
+
+ configpinsel2 r0, r1
+
+ /* Setup the External Memory Controllor (EMC) as configured */
+
+ configemc r0, r1
+
+ /* Configure VPBDIV */
+
+ configvpbdiv r0, r1
+
+ /* Configure the PLL */
+
+ configpll r0, r1, r2, r3
+
+ /* Configure the Memory Accelerator Module (MAM) */
+
+ configmam r0, r1
+
+ /* Setup MEMMAP for the selected mode of operation */
+
+ configmemmap r0, r1
+
+ showprogress 'A'
+
+ /* Setup system stack (and get the BSS range) */
+
+ adr r0, LC0
+ ldmia r0, {r4, r5, sp}
+
+ /* Clear system BSS section */
+
+ mov r0, #0
+1: cmp r4, r5
+ strcc r0, [r4], #4
+ bcc 1b
+
+ showprogress 'B'
+
+ /* Copy system .data sections to new home in RAM. */
+
+#ifdef CONFIG_BOOT_FROM_FLASH
+
+ adr r3, LC2
+ ldmia r3, {r0, r1, r2}
+
+1: ldmia r0!, {r3 - r10}
+ stmia r1!, {r3 - r10}
+ cmp r1, r2
+ blt 1b
+
+#endif
+ /* Perform early serial initialization */
+
+ mov fp, #0
+ bl up_earlyserialinit
+
+#ifdef CONFIG_DEBUG
+ mov r0, #'C'
+ bl up_putc
+ mov r0, #'\n'
+ bl up_putc
+#endif
+ /* Initialize onboard LEDs */
+
+#ifdef CONFIG_ARCH_LEDS
+ bl up_ledinit
+#endif
+
+ /* Then jump to OS entry */
+
+ b os_start
+
+ /* Variables:
+ * _sbss is the start of the BSS region (see ld.script)
+ * _ebss is the end of the BSS regsion (see ld.script)
+ * The idle task stack starts at the end of BSS and is
+ * of size CONFIG_PROC_STACK_SIZE. The heap continues
+ * from there until the end of memory. See g_heapbase
+ * below.
+ */
+
+LC0: .long _sbss
+ .long _ebss
+ .long _ebss+CONFIG_PROC_STACK_SIZE-4
+
+#ifdef CONFIG_BOOT_FROM_FLASH
+LC2: .long _eronly /* Where .data defaults are stored in FLASH */
+ .long _sdata /* Where .data needs to reside in SDRAM */
+ .long _edata
+#endif
+ .size __start, .-__start
+
+ /* This global variable is unsigned long g_heapbase and is
+ * exported from here only because of its coupling to LCO
+ * above.
+ */
+
+ .data
+ .align 4
+ .globl g_heapbase
+ .type g_heapbase, object
+g_heapbase:
+ .long _ebss+CONFIG_PROC_STACK_SIZE
+ .size g_heapbase, .-g_heapbase
+
+ .end
+
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_irq.c b/nuttx/arch/arm/src/lpc214x/lpc214x_irq.c
new file mode 100644
index 000000000..a6d6654f7
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_irq.c
@@ -0,0 +1,115 @@
+/************************************************************
+ * lpc214x/lpc214x_irq.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 Gregory Nutt 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 <sys/types.h>
+#include <nuttx/irq.h>
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Public Data
+ ************************************************************/
+
+uint32 *current_regs;
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_irqinitialize
+ ************************************************************/
+
+void up_irqinitialize(void)
+{
+#warning "Not implemented"
+}
+
+/************************************************************
+ * Name: up_disable_irq
+ *
+ * Description:
+ * Disable the IRQ specified by 'irq'
+ *
+ ************************************************************/
+
+void up_disable_irq(int irq)
+{
+#warning "Not implemented"
+}
+
+/************************************************************
+ * Name: up_enable_irq
+ *
+ * Description:
+ * Enable the IRQ specified by 'irq'
+ *
+ ************************************************************/
+
+void up_enable_irq(int irq)
+{
+#warning "Not implemented"
+}
+
+/************************************************************
+ * Name: up_maskack_irq
+ *
+ * Description:
+ * Mask the IRQ and acknowledge it
+ *
+ ************************************************************/
+
+void up_maskack_irq(int irq)
+{
+#warning "Not implemented"
+}
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_lowputc.S b/nuttx/arch/arm/src/lpc214x/lpc214x_lowputc.S
new file mode 100644
index 000000000..8096ed3e9
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_lowputc.S
@@ -0,0 +1,91 @@
+/**************************************************************************
+ * lpc214x/lpc214X_lowputc.S
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 Gregory Nutt 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 "up_internal.h"
+#include "up_arch.h"
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Function Prototypes
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_lowputc
+ **************************************************************************/
+
+/* This assembly language version has the advantage that it can does not
+ * require a C stack and uses only r0-r1. Hence it can be used during
+ * early boot phases.
+ */
+
+ .text
+ .global up_lowputc
+ .type up_lowputc, function
+up_lowputc:
+ /* On entry, r0 holds the character to be printed */
+#warning "Not implemented"
+
+ /* And return */
+
+ mov pc, lr
+ .end
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c b/nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c
new file mode 100644
index 000000000..16de968b2
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c
@@ -0,0 +1,94 @@
+/************************************************************
+ * lpc214x/lpc214x_timerisr.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 Gregory Nutt 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 <sys/types.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include "clock_internal.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Types
+ ************************************************************/
+
+/************************************************************
+ * Private Function Prototypes
+ ************************************************************/
+
+/************************************************************
+ * Global Functions
+ ************************************************************/
+
+/************************************************************
+ * Function: up_timerisr
+ *
+ * Description:
+ * The timer ISR will perform a variety of services for
+ * various portions of the systems.
+ *
+ ************************************************************/
+
+int up_timerisr(int irq, uint32 *regs)
+{
+ /* Process timer interrupt */
+
+ sched_process_timer();
+ return 0;
+}
+
+/************************************************************
+ * Function: up_timerinit
+ *
+ * Description:
+ * This function is called during start-up to initialize
+ * the timer interrupt.
+ *
+ ************************************************************/
+
+void up_timerinit(void)
+{
+#warning "Not implemented"
+}
+
diff --git a/nuttx/configs/mcu123-lpc214x/Make.defs b/nuttx/configs/mcu123-lpc214x/Make.defs
new file mode 100644
index 000000000..8baeb3f36
--- /dev/null
+++ b/nuttx/configs/mcu123-lpc214x/Make.defs
@@ -0,0 +1,71 @@
+############################################################
+# Make.defs
+#
+# Copyright (C) 2007 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# 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 Gregory Nutt 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
+
+ifeq ("${CONFIG_DEBUG}","y")
+ ARCHOPTIMIZATION = -g
+else
+ ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce \
+ -fomit-frame-pointer
+endif
+
+ARCHCPUFLAGS = -mapcs-32 -mcpu=arm7tdmi -msoft-float -fno-builtin
+ARCHPICFLAGS = -fpic
+ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
+ARCHDEFINES =
+ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ld.script
+
+CROSSDEV = arm-elf-
+CC = $(CROSSDEV)gcc
+LD = $(CROSSDEV)ld
+AR = $(CROSSDEV)ar rcs
+NM = $(CROSSDEV)nm
+OBJCOPY = $(CROSSDEV)objcopy
+OBJDUMP = $(CROSSDEV)objdump
+
+CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \
+ $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) -pipe
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+ifeq ("${CONFIG_DEBUG}","y")
+ LDFLAGS += -g
+endif
+
+
diff --git a/nuttx/configs/mcu123-lpc214x/defconfig b/nuttx/configs/mcu123-lpc214x/defconfig
new file mode 100644
index 000000000..73888e922
--- /dev/null
+++ b/nuttx/configs/mcu123-lpc214x/defconfig
@@ -0,0 +1,248 @@
+############################################################
+# defconfig
+#
+# Copyright (C) 2007 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# 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 Gregory Nutt 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 - identifies the arch subdirectory and, hence, the
+# processor architecture.
+# CONFIG_ARCH_name - for use in C code. This identifies the
+# particular chip or SoC that the architecture is implemented
+# in.
+# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
+# CONFIG_ARCH_CHIP_name - For use in C code
+# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
+# the board that supports the particular chip or SoC.
+# CONFIG_ARCH_BOARD_name - for use in C code
+# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
+# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to lpc2148.
+# CONFIG_DRAM_SIZE - Describes the internal DRAM.
+# CONFIG_DRAM_START - The start address of internal DRAM
+# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
+#
+CONFIG_ARCH=arm
+CONFIG_ARCH_CHIP=lpc214x
+CONFIG_ARCH_LPC2148=y
+CONFIG_ARCH_BOARD=mcu123-lpc214x
+CONFIG_ARCH_BOARD_MCU123=y
+CONFIG_BOARD_LOOPSPERMSEC=1250
+CONFIG_ARCH_LEDS=n
+CONFIG_DRAM_SIZE=0x02000000
+CONFIG_DRAM_START=0x40000000
+CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
+CONFIG_ARCH_STACKDUMP=y
+
+#
+# LPC2148 specific chip initialization
+#
+CONFIG_EXTMEM_MODE=n
+CONFIG_RAM_MODE=n
+CONFIG_CODE_BASE=0x00000000
+CONFIG_PLL_SETUP=y
+CONFIG_MAM_SETUP=y
+CONFIG_VPBDIV_SETUP=y
+CONFIG_EMC_SETUP=n
+CONFIG_BCFG0_SETUP=n
+CONFIG_BCFG1_SETUP=n
+CONFIG_BCFG2_SETUP=n
+CONFIG_BCFG3_SETUP=n
+
+#
+# General OS setup
+#
+# CONFIG_EXAMPLE - identifies the subdirectory in examples
+# that will be used in the build
+# CONFIG_DEBUG - enables built-in debug options
+# CONFIG_DEBUG_VERBOSE - enables verbose debug output
+# CONFIG_MM_REGIONS - If the architecture includes multiple
+# regions of memory to allocate from, this specifies the
+# number of memory regions that the memory manager must
+# handle and enables the API mm_addregion(start, end);
+# CONFIG_HAVE_LOWPUTC - architecture supports low-level, boot
+# time console output
+# CONFIG_RR_INTERVAL - The round robin timeslice will be set
+# this number of milliseconds; Round robin scheduling can
+# be disabled by setting this value to zero.
+# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in
+# scheduler to monitor system performance
+# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a
+# task name to save in the TCB. Useful if scheduler
+# instrumentation is selected. Set to zero to disable.
+# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY -
+# Used to initialize the internal time logic.
+# CONFIG_JULIAN_TIME - Enables Julian time conversions
+# CONFIG_DEV_CONSOLE - Set if architecture-specific logic
+# provides /dev/console. Enables stdout, stderr, stdin.
+#
+CONFIG_EXAMPLE=ostest
+CONFIG_DEBUG=n
+CONFIG_DEBUG_VERBOSE=n
+CONFIG_MM_REGIONS=1
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_RR_INTERVAL=200
+CONFIG_SCHED_INSTRUMENTATION=n
+CONFIG_TASK_NAME_SIZE=0
+CONFIG_START_YEAR=2007
+CONFIG_START_MONTH=2
+CONFIG_START_DAY=13
+CONFIG_JULIAN_TIME=n
+CONFIG_DEV_CONSOLE=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=n
+CONFIG_DISABLE_POSIX_TIMERS=n
+CONFIG_DISABLE_PTHREAD=n
+CONFIG_DISABLE_SIGNALS=n
+CONFIG_DISABLE_MQUEUE=n
+
+#
+# Misc libc settings
+#
+# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
+# little smaller if we do not support fieldwidthes
+#
+CONFIG_NOPRINTF_FIELDWIDTH=n
+
+#
+# Allow for architecture optimized implementations
+#
+# The architecture can provide optimized versions of the
+# following to improve sysem performance
+#
+CONFIG_ARCH_MEMCPY=n
+CONFIG_ARCH_MEMCMP=n
+CONFIG_ARCH_MEMMOVE=n
+CONFIG_ARCH_MEMSET=n
+CONFIG_ARCH_STRCMP=n
+CONFIG_ARCH_STRCPY=n
+CONFIG_ARCH_STRNCPY=n
+CONFIG_ARCH_STRLEN=n
+CONFIG_ARCH_BZERO=n
+CONFIG_ARCH_KMALLOC=n
+CONFIG_ARCH_KZMALLOC=n
+CONFIG_ARCH_KFREE=n
+
+#
+# General build options
+#
+# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
+# BSPs from www.ridgerun.com
+#
+CONFIG_RRLOAD_BINARY=y
+
+#
+# Sizes of configurable things (0 disables)
+#
+# CONFIG_MAX_TASKS - The maximum number of simultaneously
+# active tasks. This value must be a power of two.
+# CONFIG_MAX_TASK_ARGS - This controls the maximum number of
+# of parameters that a task may receive (i.e., maxmum value
+# of 'argc')
+# CONFIG_NPTHREAD_KEYS - The number of items of thread-
+# specific data that can be retained
+# CONFIG_NFILE_DESCRIPTORS - The maximum number of file
+# descriptors (one for each open)
+# CONFIG_NFILE_STREAMS - The maximum number of streams that
+# can be fopen'ed
+# CONFIG_NAME_MAX - The maximum size of a file name.
+# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate
+# on fopen. (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_NUNGET_CHARS - Number of characters that can be
+# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message
+# structures. The system manages a pool of preallocated
+# message structures to minimize dynamic allocations
+# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with
+# a fixed payload size given by this settin (does not include
+# other message structure overhead.
+# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that
+# can be passed to a watchdog handler
+# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog
+# structures. The system manages a pool of preallocated
+# watchdog structures to minimize dynamic allocations
+# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX
+# timer structures. The system manages a pool of preallocated
+# timer structures to minimize dynamic allocations. Set to
+# zero for all dynamic allocations.
+#
+CONFIG_MAX_TASKS=64
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_NPTHREAD_KEYS=4
+CONFIG_NFILE_DESCRIPTORS=32
+CONFIG_NFILE_STREAMS=16
+CONFIG_NAME_MAX=32
+CONFIG_STDIO_BUFFER_SIZE=1024
+CONFIG_NUNGET_CHARS=2
+CONFIG_PREALLOC_MQ_MSGS=32
+CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=4
+CONFIG_PREALLOC_WDOGS=32
+CONFIG_PREALLOC_TIMERS=8
+
+#
+# Stack and heap information
+#
+# CONFIG_BOOT_FROM_FLASH - Some configurations support XIP
+# operation from FLASH.
+# CONFIG_CUSTOM_STACK - The up_ implementation will handle
+# all stack operations outside of the nuttx model.
+# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only)
+# CONFIG_PROC_STACK_SIZE - The size of the initial stack
+# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size
+# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size
+# CONFIG_HEAP_BASE - The beginning of the heap
+# CONFIG_HEAP_SIZE - The size of the heap
+#
+CONFIG_BOOT_FROM_FLASH=n
+CONFIG_CUSTOM_STACK=n
+CONFIG_STACK_POINTER=
+CONFIG_PROC_STACK_SIZE=4096
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=4096
+CONFIG_HEAP_BASE=
+CONFIG_HEAP_SIZE=
diff --git a/nuttx/configs/mcu123-lpc214x/include/README.txt b/nuttx/configs/mcu123-lpc214x/include/README.txt
new file mode 100644
index 000000000..4a18c4011
--- /dev/null
+++ b/nuttx/configs/mcu123-lpc214x/include/README.txt
@@ -0,0 +1 @@
+This directory contains header files unique to the MCU123 LPC2148 board.
diff --git a/nuttx/configs/mcu123-lpc214x/include/board.h b/nuttx/configs/mcu123-lpc214x/include/board.h
new file mode 100644
index 000000000..2ed4d0a8b
--- /dev/null
+++ b/nuttx/configs/mcu123-lpc214x/include/board.h
@@ -0,0 +1,59 @@
+/************************************************************
+ * board/board.h
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 Gregory Nutt 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 __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#ifndef __ASSEMBLY__
+# include <sys/types.h>
+#endif
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/* Clocking *************************************************/
+
+/* LED definitions ******************************************/
+
+/************************************************************
+ * Inline Functions
+ ************************************************************/
+
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/nuttx/configs/mcu123-lpc214x/ld.script b/nuttx/configs/mcu123-lpc214x/ld.script
new file mode 100644
index 000000000..774f17420
--- /dev/null
+++ b/nuttx/configs/mcu123-lpc214x/ld.script
@@ -0,0 +1,84 @@
+/************************************************************
+ * ld.script
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 Gregory Nutt 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(arm)
+ENTRY(_stext)
+SECTIONS
+{
+ /* The OS entry point is here (default MEMMAP mode assumed) */
+
+ . = 0x00000000;
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.text)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got) /* Global offset table */
+ _etext = ABSOLUTE(.);
+ }
+
+ _eronly = ABSOLUTE(.); /* See below */
+ . = ALIGN(4096);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.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/mcu123-lpc214x/setenv.sh b/nuttx/configs/mcu123-lpc214x/setenv.sh
new file mode 100755
index 000000000..bb3bd49c5
--- /dev/null
+++ b/nuttx/configs/mcu123-lpc214x/setenv.sh
@@ -0,0 +1,46 @@
+#!/bin/sh
+# setenv.sh
+#
+# Copyright (C) 2007 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# 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 Gregory Nutt 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" ] ; 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_arm_nofpu/staging_dir/bin
+export PATH=${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/mcu123-lpc214x/src/Makefile b/nuttx/configs/mcu123-lpc214x/src/Makefile
new file mode 100644
index 000000000..01fb4997a
--- /dev/null
+++ b/nuttx/configs/mcu123-lpc214x/src/Makefile
@@ -0,0 +1,79 @@
+############################################################
+# Makefile
+#
+# Copyright (C) 2007 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# 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 Gregory Nutt 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
+
+MKDEP = $(TOPDIR)/tools/mkdeps.sh
+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
+ $(CC) -c $(CFLAGS) -D__ASSEMBLY__ $< -o $@
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(CC) -c $(CFLAGS) $< -o $@
+
+libboard$(LIBEXT): $(OBJS)
+ ( for obj in $(OBJS) ; do \
+ $(AR) $@ $${obj} || \
+ { echo "$(AR) $@ $obj FAILED!" ; exit 1 ; } ; \
+ done ; )
+
+.depend: Makefile $(SRCS)
+ $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ touch $@
+
+depend: .depend
+
+clean:
+ rm -f libboard$(LIBEXT) *~
+ if [ ! -z "$(OBJEXT)" ]; then rm -f *$(OBJEXT); fi
+
+distclean: clean
+ rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/configs/mcu123-lpc214x/src/README.txt b/nuttx/configs/mcu123-lpc214x/src/README.txt
new file mode 100644
index 000000000..767045c18
--- /dev/null
+++ b/nuttx/configs/mcu123-lpc214x/src/README.txt
@@ -0,0 +1,2 @@
+This directory contains drivers unique to the MCU123 LPC2148 board.
+
diff --git a/nuttx/configs/mcu123-lpc214x/src/up_leds.c b/nuttx/configs/mcu123-lpc214x/src/up_leds.c
new file mode 100644
index 000000000..e6744c547
--- /dev/null
+++ b/nuttx/configs/mcu123-lpc214x/src/up_leds.c
@@ -0,0 +1,84 @@
+/************************************************************
+ * board/up_leds.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 Gregory Nutt 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 <sys/types.h>
+#include "up_internal.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_ledinit
+ ************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void up_ledinit(void)
+{
+}
+
+/************************************************************
+ * Name: up_ledon
+ ************************************************************/
+
+void up_ledon(int led)
+{
+}
+
+/************************************************************
+ * Name: up_ledoff
+ ************************************************************/
+
+void up_ledoff(int led)
+{
+}
+#endif /* CONFIG_ARCH_LEDS */