summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog4
-rw-r--r--nuttx/Documentation/NuttX.html21
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html31
-rw-r--r--nuttx/Makefile14
-rw-r--r--nuttx/TODO13
-rw-r--r--nuttx/arch/README.txt7
-rw-r--r--nuttx/arch/arm/src/Makefile4
-rw-r--r--nuttx/arch/arm/src/c5471/Make.defs14
-rw-r--r--nuttx/arch/arm/src/c5471/c5471_doirq.c104
-rw-r--r--nuttx/arch/arm/src/c5471/c5471_vectors.S2
-rw-r--r--nuttx/arch/arm/src/c5471/chip.h4
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h3
-rw-r--r--nuttx/arch/arm/src/common/up_vectors.S47
-rw-r--r--nuttx/arch/arm/src/common/up_vectortab.S103
-rw-r--r--nuttx/arch/arm/src/dm320/Make.defs9
-rw-r--r--nuttx/arch/arm/src/dm320/dm320_decodeirq.c (renamed from nuttx/arch/arm/src/dm320/dm320_doirq.c)4
-rw-r--r--nuttx/arch/arm/src/dm320/dm320_vectors.S449
-rw-r--r--nuttx/configs/README.txt8
-rw-r--r--nuttx/configs/ntosd-dm320/defconfig2
-rwxr-xr-xnuttx/tools/configure.sh5
-rwxr-xr-xnuttx/tools/zipme.sh2
21 files changed, 214 insertions, 636 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 32d3a665e..31f381dbf 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -123,4 +123,8 @@
0.2.5 2007-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Added support for the NXP 214x processor on the mcu123.com lpc214x
+ development board.
+ * Corrected some build/configuration issues introduced with the
+ last release.
* Started m68322
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index bcfcf34f1..64857be2f 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: March 28, 2007</p>
+ <p>Last Updated: April 29, 2007</p>
</td>
</tr>
</table>
@@ -235,6 +235,21 @@
</td>
</tr>
<tr>
+ <td><br></td>
+ <td>
+ <p>
+ <b>NXP LPC214x</b>.
+ Support is provided for the NXP LPC214x family of processors. In particular,
+ support is provided for the mcu123.com lpc214x evaluation board (LPC2148).
+ This port also used the GNU arm-eld toolchain*.
+ </p>
+ <p>
+ <b>STATUS:</b>
+ This port is in progress and should be available in the nuttx-0.2.5 release.
+ </p>
+ </td>
+</tr>
+<tr>
<td valign="top"><img src="favicon.ico"></td>
<td bgcolor="#5eaee1">
<b>ARM9EJS</b>.
@@ -484,6 +499,10 @@ Other memory:
0.2.5 2007-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Added support for the NXP 214x processor on the mcu123.com lpc214x
+ development board.
+ * Corrected some build/configuration issues introduced with the
+ last release.
* Started m68322
</pre></ul>
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index 636eaaa58..893888bee 100644
--- a/nuttx/Documentation/NuttxPortingGuide.html
+++ b/nuttx/Documentation/NuttxPortingGuide.html
@@ -361,6 +361,14 @@
NuttX operates on the ARM9EJS of this dual core processor.
This port complete, verified, and included in the NuttX release 0.2.1.
</li>
+
+ <li><code>arch/arm/include/lpc214x</code> and <code>arch/arm/src/lpc214x</code>:
+ These directories provide support for NXP LPC214x family of
+ processors.
+ STATUS: This port is in progress and should be available in the
+ nuttx-0.2.5 release.
+ </li>
+
</ul>
</li>
@@ -505,18 +513,24 @@
A user-mode port of NuttX to the x86 Linux platform is available.
The purpose of this port is primarily to support OS feature developement.
This port does not support interrupts or a real timer (and hence no
- round robin scheduler) Otherwise, it is complete.</li>
+ round robin scheduler) Otherwise, it is complete.
+ </li>
<li><code>configs/c5471evm</code>:
This is a port to the Spectrum Digital C5471 evaluation board. The
C5471 is a dual core processor from TI with an ARM7TDMI general purpose
processor and a c54 SDP. NuttX runs on the ARM core and is built with
with a GNU arm-elf toolchain*. This port is complete, verified, and
- included in the NuttX release.</li>
+ included in the NuttX release.
+ </li>
<li><code>configs/mcu123-lpc214x</code>:
- This is a port to the mcu123.com lpc214x development board.
- This OS is also built with the arm-elf toolchain*.</li>
+ This port is for the NXP LPC2148 as provided on the mcu123.com
+ lpc214x development board.
+ This OS is also built with the arm-elf toolchain*.
+ STATUS: This port is in progress and should be available in the
+ nuttx-0.2.5 release.
+ </li>
<li><code>configs/ntosd-dm320</code>:
This port uses the Neuros OSD with a GNU arm-elf toolchain*.
@@ -524,15 +538,18 @@
for futher information.
NuttX operates on the ARM9EJS of this dual core processor.
STATUS: This port is code complete, verified, and included in the
- NuttX 0.2.1 release.</li>
+ NuttX 0.2.1 release.
+ </li>
<li><code>configs/m68322evb</code>:
This is a work in progress for the venerable m68322evb board from
- Motorola.</li>
+ Motorola.
+ </li>
<li><code>configs/pjrc-8051</code>:
8051 Microcontroller. This port uses the PJRC 87C52 development system
- and the SDCC toolchain. This port is not quite ready for prime time.</li>
+ and the SDCC toolchain. This port is not quite ready for prime time.
+ </li>
</ul>
<p><small><blockquote>
diff --git a/nuttx/Makefile b/nuttx/Makefile
index d27c28f39..c7351b0e6 100644
--- a/nuttx/Makefile
+++ b/nuttx/Makefile
@@ -63,10 +63,10 @@ include/nuttx/config.h: $(TOPDIR)/.config tools/mkconfig
# link the arch/<arch-name>/include dir to include/arch
include/arch: Make.defs
- @if [ -e include/arch ]; then \
- if [ -h include/arch ]; then \
- rm -f include/arch ; \
- else \
+ @if [ -h include/arch ]; then \
+ rm -f include/arch ; \
+ else \
+ if [ -e include/arch ]; then \
echo "include/arch exists but is not a symbolic link" ; \
exit 1 ; \
fi ; \
@@ -75,10 +75,10 @@ include/arch: Make.defs
# Link the configs/<board-name>/include dir to include/arch/board
include/arch/board: Make.defs include/arch
- @if [ -e include/arch/board ]; then \
- if [ -h include/arch/board ]; then \
+ @if [ -h include/arch/board ]; then \
rm -f include/arch/board ; \
- else \
+ else \
+ if [ -e include/arch/board ]; then \
echo "include/arch/board exists but is not a symbolic link" ; \
exit 1 ; \
fi ; \
diff --git a/nuttx/TODO b/nuttx/TODO
index b5981f29c..b8ebddde9 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -42,12 +42,12 @@ o Documentation
- Document C-library APIs
o Build system
-- Names under arch are incorrect. These should hold processor architectures.
- c5471 and dm320 should be arm
- pjrc-8051 should be 805x
-- SoC-specific logic should be in subdirectories under arch/<processor-name>.
- Eg. arm/include/c5471 should hold c5471 specific header files
+- Some names under arch are still incorrect. These should be processor architecture
+ names: pjrc-8051 should be 805x
- configs/pjrc-8051 should be configs/pjrc-87c52
+- Last change to create the arch/arm directory breaks dependencies in arch/arm/src.
+ Probably need to add the path to the chip or common subdirectorys when
+ running tools/mkdeps.sh
o Applications & Tests
@@ -55,6 +55,9 @@ o C5471
o DM320
+o LPC214x
+- Finish
+
o pjrc-8052 / MCS51
- Current status:
- Basic OS task management seems OK
diff --git a/nuttx/arch/README.txt b/nuttx/arch/README.txt
index f347f3333..f29edc15e 100644
--- a/nuttx/arch/README.txt
+++ b/nuttx/arch/README.txt
@@ -146,8 +146,15 @@ arch/arm
NuttX operates on the ARM9EJS of this dual core processor. This port
complete, verified, and included in the NuttX release 0.2.1.
+ arch/arm/include/lpc214x and arch/arm/src/lpc214x
+ These directories provide support for NXP LPC214x family of
+ processors.
+ STATUS: This port is in progress and should be available in the
+ nuttx-0.2.5 release.
+
arch/m68322
A work in progress.
+ STATUS: Stalled for the moment.
arch/pjrc-8051
8051 Microcontroller. This port is not quite ready for prime time.
diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile
index 25c17b0bd..b02c4c9ec 100644
--- a/nuttx/arch/arm/src/Makefile
+++ b/nuttx/arch/arm/src/Makefile
@@ -99,10 +99,10 @@ ifeq ($(CONFIG_RRLOAD_BINARY),y)
fi
endif
-.depend: Makefile $(SRCS)
+.depend: Makefile chip/Make.defs $(SRCS)
@if [ -e board/Makefile ]; then \
$(MAKE) -C board TOPDIR=$(TOPDIR) depend ; \
- if
+ fi
$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
@touch $@
diff --git a/nuttx/arch/arm/src/c5471/Make.defs b/nuttx/arch/arm/src/c5471/Make.defs
index 54d337938..ea04d6b81 100644
--- a/nuttx/arch/arm/src/c5471/Make.defs
+++ b/nuttx/arch/arm/src/c5471/Make.defs
@@ -37,12 +37,12 @@ HEAD_ASRC = up_nommuhead.S
CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.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
+ up_createstack.c up_dataabort.c up_delay.c up_doirq.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 = c5471_lowputc.S c5471_vectors.S
-CHIP_CSRCS = c5471_doirq.c c5471_irq.c c5471_serial.c c5471_timerisr.c \
- c5471_watchdog.c
+CHIP_CSRCS = c5471_irq.c c5471_serial.c c5471_timerisr.c c5471_watchdog.c
diff --git a/nuttx/arch/arm/src/c5471/c5471_doirq.c b/nuttx/arch/arm/src/c5471/c5471_doirq.c
deleted file mode 100644
index 19d898b4c..000000000
--- a/nuttx/arch/arm/src/c5471/c5471_doirq.c
+++ /dev/null
@@ -1,104 +0,0 @@
-/************************************************************
- * c5471/c5471_doirq.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 "up_arch.h"
-#include "os_internal.h"
-#include "up_internal.h"
-
-/************************************************************
- * Definitions
- ************************************************************/
-
-/************************************************************
- * Public Data
- ************************************************************/
-
-/************************************************************
- * Private Data
- ************************************************************/
-
-/************************************************************
- * Private Functions
- ************************************************************/
-
-/************************************************************
- * Public Funtions
- ************************************************************/
-
-void c5471_doirq(int irq, uint32* regs)
-{
- up_ledon(LED_INIRQ);
-#ifdef CONFIG_SUPPRESS_INTERRUPTS
- PANIC(OSERR_ERREXCEPTION);
-#else
- if ((unsigned)irq < NR_IRQS)
- {
- /* 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;
-
- /* Mask and acknowledge the interrupt */
-
- up_maskack_irq(irq);
-
- /* 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);
- }
- up_ledoff(LED_INIRQ);
-#endif
-}
diff --git a/nuttx/arch/arm/src/c5471/c5471_vectors.S b/nuttx/arch/arm/src/c5471/c5471_vectors.S
index 328485e17..b10842b69 100644
--- a/nuttx/arch/arm/src/c5471/c5471_vectors.S
+++ b/nuttx/arch/arm/src/c5471/c5471_vectors.S
@@ -156,7 +156,7 @@ up_vectorirq:
mov fp, #0 /* Init frame pointer */
mov r1, sp /* Get r1=xcp */
- bl c5471_doirq /* Call the handler */
+ bl up_doirq /* Call the handler */
/* Restore the CPSR, SVC modr registers and return */
.Lnoirqset:
diff --git a/nuttx/arch/arm/src/c5471/chip.h b/nuttx/arch/arm/src/c5471/chip.h
index 74ff3c509..6720893c4 100644
--- a/nuttx/arch/arm/src/c5471/chip.h
+++ b/nuttx/arch/arm/src/c5471/chip.h
@@ -316,8 +316,4 @@
* Public Function Prototypes
************************************************************/
-#ifndef __ASSEMBLY__
-extern void c5471_doirq(int irq, uint32* regs);
-#endif
-
#endif /* __C5471_CHIP_H */
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 185b4e8ab..268dc6f2d 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -101,7 +101,8 @@ extern void up_boot(void);
extern void up_copystate(uint32 *dest, uint32 *src);
extern void up_dataabort(uint32 *regs);
extern void up_delay(int milliseconds);
-extern void up_doirq(uint32 *regs);
+extern void up_decodeirq(uint32 *regs);
+extern void up_doirq(int irq, uint32 *regs);
extern void up_fullcontextrestore(uint32 *regs) __attribute__ ((noreturn));
extern void up_irqinitialize(void);
extern void up_prefetchabort(uint32 *regs);
diff --git a/nuttx/arch/arm/src/common/up_vectors.S b/nuttx/arch/arm/src/common/up_vectors.S
index 648060218..44566b917 100644
--- a/nuttx/arch/arm/src/common/up_vectors.S
+++ b/nuttx/arch/arm/src/common/up_vectors.S
@@ -128,7 +128,7 @@ up_vectorirq:
mov fp, #0 /* Init frame pointer */
mov r0, sp /* Get r0=xcp */
- bl up_doirq /* Call the handler */
+ bl up_decodeirq /* Call the handler */
/* Restore the CPSR, SVC modr registers and return */
.Lnoirqset:
@@ -138,6 +138,7 @@ up_vectorirq:
.Lirqtmp:
.word g_irqtmp
+ .size up_vectorirq, . - up_vectorirq
.align 5
@@ -183,6 +184,7 @@ up_vectorswi:
ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */
msr spsr, r0
ldmia sp, {r0-r15}^ /* Return */
+ .size up_vectorswi, . - up_vectorswi
.align 5
@@ -251,6 +253,7 @@ up_vectordata:
.Ldaborttmp:
.word g_aborttmp
+ .size up_vectordata, . - up_vectordata
.align 5
@@ -317,6 +320,7 @@ up_vectorprefetch:
.Lpaborttmp:
.word g_aborttmp
+ .size up_vectorprefetch, . - up_vectorprefetch
.align 5
@@ -383,6 +387,7 @@ up_vectorundefinsn:
.Lundeftmp:
.word g_undeftmp
+ .size up_vectorundefinsn, . - up_vectorundefinsn
.align 5
@@ -397,6 +402,9 @@ up_vectorundefinsn:
.type up_vectorfiq, %function
up_vectorfiq:
subs pc, lr, #4
+ .size up_vectofiq, . - up_vectorfiq
+
+ .align 5
/********************************************************************
* Name: up_vectoraddrexcption
@@ -410,40 +418,5 @@ up_vectorfiq:
.type up_vectoraddrexcptn, %function
up_vectoraddrexcptn:
b up_vectoraddrexcptn
-
-/**************************************************************************
- * Vector initialization block.
- **************************************************************************/
-
-/* These will be relocated to VECTOR_BASE. */
-
- .globl _vector_start
-_vector_start:
- 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 */
-
-.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
- .globl _vector_end
-_vector_end:
+ .size up_vectoaddrexcptn, . - up_vectoraddrexcptn
.end
diff --git a/nuttx/arch/arm/src/common/up_vectortab.S b/nuttx/arch/arm/src/common/up_vectortab.S
new file mode 100644
index 000000000..dc7c38c61
--- /dev/null
+++ b/nuttx/arch/arm/src/common/up_vectortab.S
@@ -0,0 +1,103 @@
+/********************************************************************
+ * common/up_vectortab.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>
+
+/********************************************************************
+ * Definitions
+ ********************************************************************/
+
+/********************************************************************
+ * Global Data
+ ********************************************************************/
+
+/********************************************************************
+ * Assembly Macros
+ ********************************************************************/
+
+/********************************************************************
+ * Name: _vector_start
+ *
+ * Description:
+ * Vector initialization block
+ ********************************************************************/
+
+ .globl _vector_start
+
+/* These will be relocated to VECTOR_BASE. */
+
+_vector_start:
+ 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
+
+ .globl _vector_end
+_vector_end:
+ .end
diff --git a/nuttx/arch/arm/src/dm320/Make.defs b/nuttx/arch/arm/src/dm320/Make.defs
index 8868ee275..0c54c02a9 100644
--- a/nuttx/arch/arm/src/dm320/Make.defs
+++ b/nuttx/arch/arm/src/dm320/Make.defs
@@ -35,7 +35,8 @@
HEAD_ASRC = up_head.S
-CMN_ASRCS = up_cache.S up_fullcontextrestore.S up_saveusercontext.S
+CMN_ASRCS = up_cache.S up_fullcontextrestore.S up_saveusercontext.S \
+ up_vectors.S up_vectortab.S
CMN_CSRCS = 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 \
@@ -44,7 +45,7 @@ CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c \
up_sigdeliver.c up_syscall.c up_unblocktask.c \
up_undefinedinsn.c up_usestack.c
-CHIP_ASRCS = dm320_lowputc.S dm320_restart.S dm320_vectors.S
-CHIP_CSRCS = dm320_allocateheap.c dm320_boot.c dm320_doirq.c dm320_irq.c \
- dm320_serial.c dm320_timerisr.c
+CHIP_ASRCS = dm320_lowputc.S dm320_restart.S
+CHIP_CSRCS = dm320_allocateheap.c dm320_boot.c dm320_decodeirq.c \
+ dm320_irq.c dm320_serial.c dm320_timerisr.c
diff --git a/nuttx/arch/arm/src/dm320/dm320_doirq.c b/nuttx/arch/arm/src/dm320/dm320_decodeirq.c
index 66b55f75f..fad9f0faf 100644
--- a/nuttx/arch/arm/src/dm320/dm320_doirq.c
+++ b/nuttx/arch/arm/src/dm320/dm320_decodeirq.c
@@ -1,5 +1,5 @@
/********************************************************************************
- * dm320/dm320_doirq.c
+ * dm320/dm320_decodeirq.c
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -67,7 +67,7 @@
* Public Funtions
********************************************************************************/
-void up_doirq(uint32* regs)
+void up_decodeirq(uint32* regs)
{
#ifdef CONFIG_SUPPRESS_INTERRUPTS
lib_lowprintf("Unexpected IRQ\n");
diff --git a/nuttx/arch/arm/src/dm320/dm320_vectors.S b/nuttx/arch/arm/src/dm320/dm320_vectors.S
deleted file mode 100644
index 2f22f2b42..000000000
--- a/nuttx/arch/arm/src/dm320/dm320_vectors.S
+++ /dev/null
@@ -1,449 +0,0 @@
-/********************************************************************
- * dm320/dm320_vectors.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 <nuttx/irq.h>
-#include "up_arch.h"
-
-/********************************************************************
- * Definitions
- ********************************************************************/
-
-/********************************************************************
- * Global Data
- ********************************************************************/
-
- .data
-g_irqtmp:
- .word 0 /* Saved lr */
- .word 0 /* Saved spsr */
-g_undeftmp:
- .word 0 /* Saved lr */
- .word 0 /* Saved spsr */
-g_aborttmp:
- .word 0 /* Saved lr */
- .word 0 /* Saved spsr */
-
-/********************************************************************
- * Assembly Macros
- ********************************************************************/
-
-/********************************************************************
- * Private Functions
- ********************************************************************/
-
- .text
-
-/********************************************************************
- * Public Functions
- ********************************************************************/
-
- .text
-
-/********************************************************************
- * Name: up_vectorirq
- *
- * Description:
- * Interrupt excetpion. Entered in IRQ mode with spsr = SVC
- * CPSR, lr = SVC PC
- ********************************************************************/
-
- .globl up_vectorirq
- .type up_vectorirq, %function
-up_vectorirq:
- /* On entry, we are in IRQ mode. We are free to use
- * the IRQ mode r13 and r14.
- *
- */
-
- ldr r13, .Lirqtmp
- sub lr, lr, #4
- str lr, [r13] @ save lr_IRQ
- mrs lr, spsr
- str lr, [r13, #4] @ save spsr_IRQ
-
- /* Then switch back to SVC mode */
-
- bic lr, lr, #MODE_MASK /* Keep F and T bits */
- orr lr, lr, #(SVC_MODE | PSR_I_BIT)
- msr cpsr_c, lr /* Switch to SVC mode */
-
- /* Create a context structure. First set aside a stack frame
- * and store r0-r12 into the frame.
- */
-
- sub sp, sp, #XCPTCONTEXT_SIZE
- stmia sp, {r0-r12} /* Save the SVC mode regs */
-
- /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */
-
- add r1, sp, #XCPTCONTEXT_SIZE
- mov r2, r14
-
- /* Get the values for r15(pc) and CPSR in r3 and r4 */
-
- ldr r0, .Lirqtmp /* Points to temp storage */
- ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */
-
- add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */
- stmia r0, {r1-r4}
-
- /* Then call the IRQ handler with interrupts disabled. */
-
- mov fp, #0 /* Init frame pointer */
- mov r0, sp /* Get r0=xcp */
- bl up_doirq /* Call the handler */
-
- /* Restore the CPSR, SVC modr registers and return */
-.Lnoirqset:
- ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */
- msr spsr, r0
- ldmia sp, {r0-r15}^ /* Return */
-
-.Lirqtmp:
- .word g_irqtmp
-
- .align 5
-
-/********************************************************************
- * Function: up_vectorswi
- *
- * Description:
- * SWI interrupt. We enter the SWI in SVC mode
- ********************************************************************/
-
- .globl up_vectorswi
- .type up_vectorswi, %function
-up_vectorswi:
-
- /* Create a context structure. First set aside a stack frame
- * and store r0-r12 into the frame.
- */
-
- sub sp, sp, #XCPTCONTEXT_SIZE
- stmia sp, {r0-r12} /* Save the SVC mode regs */
-
- /* Get the correct values of r13(sp), r14(lr), r15(pc)
- * and CPSR in r1-r4 */
-
- add r1, sp, #XCPTCONTEXT_SIZE
- mov r2, r14 /* R14 is altered on return from SWI */
- mov r3, r14 /* Save r14 as the PC as well */
- mrs r4, spsr /* Get the saved CPSR */
-
- add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */
- stmia r0, {r1-r4}
-
- /* Then call the SWI handler with interrupt disabled.
- * void up_syscall(struct xcptcontext *xcp)
- */
-
- mov fp, #0 /* Init frame pointer */
- mov r0, sp /* Get r0=xcp */
- bl up_syscall /* Call the handler */
-
- /* Restore the CPSR, SVC modr registers and return */
-
- ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */
- msr spsr, r0
- ldmia sp, {r0-r15}^ /* Return */
-
- .align 5
-
-/********************************************************************
- * Name: up_vectordata
- *
- * Description:
- * Data abort Exception dispatcher. Give control to data
- * abort handler. This function is entered in ABORT mode
- * with spsr = SVC CPSR, lr = SVC PC
- *
- ********************************************************************/
-
- .globl up_vectordata
- .type up_vectordata, %function
-up_vectordata:
- /* On entry we are free to use the ABORT mode registers
- * r13 and r14
- */
-
- ldr r13, .Ldaborttmp /* Points to temp storage */
- sub lr, lr, #8 /* Fixup return */
- str lr, [r13] /* Save in temp storage */
- mrs lr, spsr /* Get SPSR */
- str lr, [r13, #4] /* Save in temp storage */
-
- /* Then switch back to SVC mode */
-
- bic lr, lr, #MODE_MASK /* Keep F and T bits */
- orr lr, lr, #(SVC_MODE | PSR_I_BIT)
- msr cpsr_c, lr /* Switch to SVC mode */
-
- /* Create a context structure. First set aside a stack frame
- * and store r0-r12 into the frame.
- */
-
- sub sp, sp, #XCPTCONTEXT_SIZE
- stmia sp, {r0-r12} /* Save the SVC mode regs */
-
- /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */
-
- add r1, sp, #XCPTCONTEXT_SIZE
- mov r2, r14
-
- /* Get the values for r15(pc) and CPSR in r3 and r4 */
-
- ldr r0, .Ldaborttmp /* Points to temp storage */
- ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */
-
- add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */
- stmia r0, {r1-r4}
-
- /* Then call the data abort handler with interrupt disabled.
- * void up_dataabort(struct xcptcontext *xcp)
- */
-
- mov fp, #0 /* Init frame pointer */
- mov r0, sp /* Get r0=xcp */
- bl up_dataabort /* Call the handler */
-
- /* Restore the CPSR, SVC modr registers and return */
-
- ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */
- msr spsr_cxsf, r0
- ldmia sp, {r0-r15}^ /* Return */
-
-.Ldaborttmp:
- .word g_aborttmp
-
- .align 5
-
-/********************************************************************
- * Name: up_vectorprefetch
- *
- * Description:
- * Prefetch abort exception. Entered in ABT mode with
- * spsr = SVC CPSR, lr = SVC PC
- ********************************************************************/
-
- .globl up_vectorprefetch
- .type up_vectorprefetch, %function
-up_vectorprefetch:
- /* On entry we are free to use the ABORT mode registers
- * r13 and r14
- */
-
- ldr r13, .Lpaborttmp /* Points to temp storage */
- sub lr, lr, #4 /* Fixup return */
- str lr, [r13] /* Save in temp storage */
- mrs lr, spsr /* Get SPSR */
- str lr, [r13, #4] /* Save in temp storage */
-
- /* Then switch back to SVC mode */
-
- bic lr, lr, #MODE_MASK /* Keep F and T bits */
- orr lr, lr, #(SVC_MODE | PSR_I_BIT)
- msr cpsr_c, lr /* Switch to SVC mode */
-
- /* Create a context structure. First set aside a stack frame
- * and store r0-r12 into the frame.
- */
-
- sub sp, sp, #XCPTCONTEXT_SIZE
- stmia sp, {r0-r12} /* Save the SVC mode regs */
-
- /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */
-
- add r1, sp, #XCPTCONTEXT_SIZE
- mov r2, r14
-
- /* Get the values for r15(pc) and CPSR in r3 and r4 */
-
- ldr r0, .Lpaborttmp /* Points to temp storage */
- ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */
-
- add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */
- stmia r0, {r1-r4}
-
- /* Then call the prefetch abort handler with interrupt disabled.
- * void up_prefetchabort(struct xcptcontext *xcp)
- */
-
- mov fp, #0 /* Init frame pointer */
- mov r0, sp /* Get r0=xcp */
- bl up_prefetchabort /* Call the handler */
-
- /* Restore the CPSR, SVC modr registers and return */
-
- ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */
- msr spsr_cxsf, r0
- ldmia sp, {r0-r15}^ /* Return */
-
-.Lpaborttmp:
- .word g_aborttmp
-
- .align 5
-
-/********************************************************************
- * Name: up_vectorundefinsn
- *
- * Description:
- * Undefined instruction entry exception. Entered in
- * UND mode, spsr = SVC CPSR, lr = SVC PC
- *
- ********************************************************************/
-
- .globl up_vectorundefinsn
- .type up_vectorundefinsn, %function
-up_vectorundefinsn:
- /* On entry we are free to use the UND mode registers
- * r13 and r14
- */
-
- ldr r13, .Lundeftmp /* Points to temp storage */
- str lr, [r13] /* Save in temp storage */
- mrs lr, spsr /* Get SPSR */
- str lr, [r13, #4] /* Save in temp storage */
-
- /* Then switch back to SVC mode */
-
- bic lr, lr, #MODE_MASK /* Keep F and T bits */
- orr lr, lr, #(SVC_MODE | PSR_I_BIT)
- msr cpsr_c, lr /* Switch to SVC mode */
-
- /* Create a context structure. First set aside a stack frame
- * and store r0-r12 into the frame.
- */
-
- sub sp, sp, #XCPTCONTEXT_SIZE
- stmia sp, {r0-r12} /* Save the SVC mode regs */
-
- /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */
-
- add r1, sp, #XCPTCONTEXT_SIZE
- mov r2, r14
-
- /* Get the values for r15(pc) and CPSR in r3 and r4 */
-
- ldr r0, .Lundeftmp /* Points to temp storage */
- ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */
-
- add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */
- stmia r0, {r1-r4}
-
- /* Then call the undef insn handler with interrupt disabled.
- * void up_undefinedinsn(struct xcptcontext *xcp)
- */
-
- mov fp, #0 /* Init frame pointer */
- mov r0, sp /* Get r0=xcp */
- bl up_undefinedinsn /* Call the handler */
-
- /* Restore the CPSR, SVC modr registers and return */
-
- ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */
- msr spsr_cxsf, r0
- ldmia sp, {r0-r15}^ /* Return */
-
-.Lundeftmp:
- .word g_undeftmp
-
- .align 5
-
-/********************************************************************
- * Name: up_vectorfiq
- *
- * Description:
- * Shouldn't happen
- ********************************************************************/
-
- .globl up_vectorfiq
- .type up_vectorfiq, %function
-up_vectorfiq:
- subs pc, lr, #4
-
-/********************************************************************
- * Name: up_vectoraddrexcption
- *
- * Description:
- * Shouldn't happen
- *
- ********************************************************************/
-
- .globl up_vectoraddrexcptn
- .type up_vectoraddrexcptn, %function
-up_vectoraddrexcptn:
- b up_vectoraddrexcptn
-
-/**************************************************************************
- * Vector initialization block.
- **************************************************************************/
-
-/* These will be relocated to VECTOR_BASE. */
-
- .globl _vector_start
-_vector_start:
- 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 */
-
-.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
- .globl _vector_end
-_vector_end:
- .end
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index 5c13d7693..547f3e1c2 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -242,9 +242,15 @@ configs/ntosd-dm320
STATUS: This port is code complete, verified, and included in the
NuttX 0.2.1 release.
+configs/mcu123-lpc214x
+ This port is for the NXP LPC2148 as provided on the mcu123.com
+ lpc214x development board.
+ STATUS: This port is in progress and should be available in the
+ nuttx-0.2.5 release.
+
configs/m68322evb
This is a work in progress for the venerable m68322evb board from
- Motorola.
+ Motorola. This OS is also built with the the arm-elf toolchain*.
configs/pjrc-8051
8051 Microcontroller. This port uses the PJRC 87C52 development system
diff --git a/nuttx/configs/ntosd-dm320/defconfig b/nuttx/configs/ntosd-dm320/defconfig
index 9f38f866d..a0df68383 100644
--- a/nuttx/configs/ntosd-dm320/defconfig
+++ b/nuttx/configs/ntosd-dm320/defconfig
@@ -46,7 +46,6 @@
# 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_ROM_VECTORS - unique to dm320
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
# CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual)
@@ -59,7 +58,6 @@ CONFIG_ARCH_CHIP_DM320=y
CONFIG_ARCH_BOARD=ntosd-dm320
CONFIG_ARCH_BOARD_NTOSD_DM320=y
CONFIG_BOARD_LOOPSPERMSEC=1250
-CONFIG_ROM_VECTORS=n
CONFIG_DRAM_SIZE=0x01000000
CONFIG_DRAM_START=0x01000000
CONFIG_DRAM_VSTART=0x00000000
diff --git a/nuttx/tools/configure.sh b/nuttx/tools/configure.sh
index f7c519a90..104c5e749 100755
--- a/nuttx/tools/configure.sh
+++ b/nuttx/tools/configure.sh
@@ -50,7 +50,10 @@ fi
BOARDDIR=${TOPDIR}/configs/${BOARD}
if [ ! -d ${BOARDDIR} ]; then
- echo "Directory ${BOARDDIR} does not exist"
+ echo "Directory ${BOARDDIR} does not exist. Options are:"
+ echo ""
+ echo `cd ${TOPDIR}/configs ; ls -1 | grep -v CVS | grep -v README.txt`
+ echo ""
show_usage
fi
diff --git a/nuttx/tools/zipme.sh b/nuttx/tools/zipme.sh
index dc2636d94..b182b3ca4 100755
--- a/nuttx/tools/zipme.sh
+++ b/nuttx/tools/zipme.sh
@@ -32,7 +32,7 @@
# POSSIBILITY OF SUCH DAMAGE.
#
-set -x
+#set -x
WD=`pwd`
DATECODE=$1