summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-05-19 17:16:17 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-05-19 17:16:17 +0000
commitf0233026fc2379ba8630a35f3a2525eac1e0bf66 (patch)
tree3014c6f68fc1a4761ec7890137be1451a1fdc4a2
parent97a479b2f239f6719dc87e5e2b6a978a1f8f61b1 (diff)
downloadpx4-nuttx-f0233026fc2379ba8630a35f3a2525eac1e0bf66.tar.gz
px4-nuttx-f0233026fc2379ba8630a35f3a2525eac1e0bf66.tar.bz2
px4-nuttx-f0233026fc2379ba8630a35f3a2525eac1e0bf66.zip
Move ARM and Cortex files to separate directories
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1795 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/Makefile16
-rw-r--r--nuttx/arch/arm/src/arm/arm.h (renamed from nuttx/arch/arm/src/common/arm.h)2
-rw-r--r--nuttx/arch/arm/src/arm/up_assert.c310
-rw-r--r--nuttx/arch/arm/src/arm/up_cache.S (renamed from nuttx/arch/arm/src/common/up_cache.S)2
-rw-r--r--nuttx/arch/arm/src/arm/up_copystate.c (renamed from nuttx/arch/arm/src/common/up_copystate.c)16
-rw-r--r--nuttx/arch/arm/src/arm/up_dataabort.c (renamed from nuttx/arch/arm/src/common/up_dataabort.c)4
-rw-r--r--nuttx/arch/arm/src/arm/up_doirq.c104
-rw-r--r--nuttx/arch/arm/src/arm/up_fullcontextrestore.S (renamed from nuttx/arch/arm/src/common/up_fullcontextrestore.S)2
-rw-r--r--nuttx/arch/arm/src/arm/up_head.S (renamed from nuttx/arch/arm/src/common/up_head.S)2
-rw-r--r--nuttx/arch/arm/src/arm/up_initialstate.c (renamed from nuttx/arch/arm/src/common/up_initialstate.c)25
-rw-r--r--nuttx/arch/arm/src/arm/up_nommuhead.S (renamed from nuttx/arch/arm/src/common/up_nommuhead.S)2
-rw-r--r--nuttx/arch/arm/src/arm/up_prefetchabort.c (renamed from nuttx/arch/arm/src/common/up_prefetchabort.c)4
-rw-r--r--nuttx/arch/arm/src/arm/up_saveusercontext.S (renamed from nuttx/arch/arm/src/common/up_saveusercontext.S)2
-rw-r--r--nuttx/arch/arm/src/arm/up_schedulesigaction.c203
-rw-r--r--nuttx/arch/arm/src/arm/up_sigdeliver.c (renamed from nuttx/arch/arm/src/common/up_sigdeliver.c)15
-rw-r--r--nuttx/arch/arm/src/arm/up_syscall.c (renamed from nuttx/arch/arm/src/common/up_syscall.c)4
-rw-r--r--nuttx/arch/arm/src/arm/up_undefinedinsn.c (renamed from nuttx/arch/arm/src/common/up_undefinedinsn.c)4
-rw-r--r--nuttx/arch/arm/src/arm/up_vectoraddrexcptn.S (renamed from nuttx/arch/arm/src/common/up_vectoraddrexcptn.S)4
-rw-r--r--nuttx/arch/arm/src/arm/up_vectors.S (renamed from nuttx/arch/arm/src/common/up_vectors.S)2
-rw-r--r--nuttx/arch/arm/src/arm/up_vectortab.S (renamed from nuttx/arch/arm/src/common/up_vectortab.S)2
-rw-r--r--nuttx/arch/arm/src/common/up_arch.h1
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h4
-rw-r--r--nuttx/arch/arm/src/cortexm3/nvic.h (renamed from nuttx/arch/arm/src/common/cortexm3_nvic.h)2
-rw-r--r--nuttx/arch/arm/src/cortexm3/psr.h (renamed from nuttx/arch/arm/src/common/cortexm3_psr.h)2
-rw-r--r--nuttx/arch/arm/src/cortexm3/up_assert.c (renamed from nuttx/arch/arm/src/common/up_assert.c)20
-rw-r--r--nuttx/arch/arm/src/cortexm3/up_copystate.c86
-rw-r--r--nuttx/arch/arm/src/cortexm3/up_doirq.c (renamed from nuttx/arch/arm/src/common/up_doirq.c)18
-rw-r--r--nuttx/arch/arm/src/cortexm3/up_initialstate.c106
-rw-r--r--nuttx/arch/arm/src/cortexm3/up_schedulesigaction.c (renamed from nuttx/arch/arm/src/common/up_schedulesigaction.c)25
-rw-r--r--nuttx/arch/arm/src/cortexm3/up_sigdeliver.c144
-rw-r--r--nuttx/arch/arm/src/lm3s/Make.defs9
-rw-r--r--nuttx/arch/arm/src/lm3s/chip.h1
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_context.S2
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_hardfault.c2
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_irq.c1
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_timerisr.c1
-rw-r--r--nuttx/configs/c5471evm/src/Makefile2
-rw-r--r--nuttx/configs/eagle100/src/Makefile2
-rw-r--r--nuttx/configs/mcu123-lpc214x/src/Makefile2
-rw-r--r--nuttx/configs/mx1ads/src/Makefile2
-rw-r--r--nuttx/configs/ntosd-dm320/src/Makefile2
-rw-r--r--nuttx/configs/olimex-strp711/src/Makefile2
42 files changed, 1023 insertions, 138 deletions
diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile
index 29e64f299..cf85c741b 100644
--- a/nuttx/arch/arm/src/Makefile
+++ b/nuttx/arch/arm/src/Makefile
@@ -1,7 +1,7 @@
############################################################################
# arch/arm/src/Makefile
#
-# Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+# Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@@ -37,7 +37,14 @@
-include chip/Make.defs
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
-CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched
+ifeq ($(CONFIG_ARCH_CORTEXM3),y)
+ARCH_SUBDIR = cortexm3
+else
+ARCH_SUBDIR = arm
+endif
+
+CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \
+ -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched
HEAD_AOBJ = $(HEAD_ASRC:.S=$(OBJEXT))
@@ -61,7 +68,7 @@ BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
LIBGCC = ${shell $(CC) -print-libgcc-file-name}
-VPATH = chip:common
+VPATH = chip:common:$(ARCH_SUBDIR)
all: $(HEAD_OBJ) libarch$(LIBEXT)
@@ -101,7 +108,8 @@ endif
@if [ -e board/Makefile ]; then \
$(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
fi
- @$(MKDEP) --dep-path chip --dep-path common $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @$(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
+ $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
@touch $@
depend: .depend
diff --git a/nuttx/arch/arm/src/common/arm.h b/nuttx/arch/arm/src/arm/arm.h
index 07b21de64..aa737ff96 100644
--- a/nuttx/arch/arm/src/common/arm.h
+++ b/nuttx/arch/arm/src/arm/arm.h
@@ -1,5 +1,5 @@
/************************************************************************************
- * arch/arm/src/common/arm.h
+ * arch/arm/src/arm/arm.h
*
* Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/arch/arm/src/arm/up_assert.c b/nuttx/arch/arm/src/arm/up_assert.c
new file mode 100644
index 000000000..0c38781d4
--- /dev/null
+++ b/nuttx/arch/arm/src/arm/up_assert.c
@@ -0,0 +1,310 @@
+/****************************************************************************
+ * arch/arm/src/arm/up_assert.c
+ *
+ * Copyright (C) 2007-2009 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 NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdlib.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Output debug info if stack dump is selected -- even if
+ * debug is not selected.
+ */
+
+#ifdef CONFIG_ARCH_STACKDUMP
+# undef lldbg
+# define lldbg lib_lowprintf
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_getsp
+ ****************************************************************************/
+
+/* I don't know if the builtin to get SP is enabled */
+
+static inline uint32 up_getsp(void)
+{
+ uint32 sp;
+ __asm__
+ (
+ "\tmov %0, sp\n\t"
+ : "=r"(sp)
+ );
+ return sp;
+}
+
+/****************************************************************************
+ * Name: up_stackdump
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_STACKDUMP
+static void up_stackdump(uint32 sp, uint32 stack_base)
+{
+ uint32 stack ;
+
+ for (stack = sp & ~0x1f; stack < stack_base; stack += 32)
+ {
+ uint32 *ptr = (uint32*)stack;
+ lldbg("%08x: %08x %08x %08x %08x %08x %08x %08x %08x\n",
+ stack, ptr[0], ptr[1], ptr[2], ptr[3],
+ ptr[4], ptr[5], ptr[6], ptr[7]);
+ }
+}
+#else
+# define up_stackdump()
+#endif
+
+/****************************************************************************
+ * Name: up_registerdump
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_STACKDUMP
+static inline void up_registerdump(void)
+{
+ /* Are user registers available from interrupt processing? */
+
+ if (current_regs)
+ {
+ int regs;
+
+ /* Yes.. dump the interrupt registers */
+
+ for (regs = REG_R0; regs <= REG_R15; regs += 8)
+ {
+ uint32 *ptr = (uint32*)&current_regs[regs];
+ lldbg("R%d: %08x %08x %08x %08x %08x %08x %08x %08x\n",
+ regs, ptr[0], ptr[1], ptr[2], ptr[3],
+ ptr[4], ptr[5], ptr[6], ptr[7]);
+ }
+
+ lldbg("CPSR: %08x\n", current_regs[REG_CPSR]);
+ }
+}
+#else
+# define up_registerdump()
+#endif
+
+/****************************************************************************
+ * Name: up_dumpstate
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_STACKDUMP
+static void up_dumpstate(void)
+{
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+ uint32 sp = up_getsp();
+ uint32 ustackbase;
+ uint32 ustacksize;
+#if CONFIG_ARCH_INTERRUPTSTACK > 3
+ uint32 istackbase;
+ uint32 istacksize;
+#endif
+
+ /* Get the limits on the user stack memory */
+
+ if (rtcb->pid == 0)
+ {
+ ustackbase = g_heapbase - 4;
+ ustacksize = CONFIG_IDLETHREAD_STACKSIZE;
+ }
+ else
+ {
+ ustackbase = (uint32)rtcb->adj_stack_ptr;
+ ustacksize = (uint32)rtcb->adj_stack_size;
+ }
+
+ /* Get the limits on the interrupt stack memory */
+
+#if CONFIG_ARCH_INTERRUPTSTACK > 3
+ istackbase = (uint32)&g_userstack;
+ istacksize = (CONFIG_ARCH_INTERRUPTSTACK & ~3) - 4;
+
+ /* Show interrupt stack info */
+
+ lldbg("sp: %08x\n", sp);
+ lldbg("IRQ stack:\n");
+ lldbg(" base: %08x\n", istackbase);
+ lldbg(" size: %08x\n", istacksize);
+
+ /* Does the current stack pointer lie within the interrupt
+ * stack?
+ */
+
+ if (sp <= istackbase && sp > istackbase - istacksize)
+ {
+ /* Yes.. dump the interrupt stack */
+
+ up_stackdump(sp, istackbase);
+
+ /* Extract the user stack pointer which should lie
+ * at the base of the interrupt stack.
+ */
+
+ sp = g_userstack;
+ lldbg("sp: %08x\n", sp);
+ }
+
+ /* Show user stack info */
+
+ lldbg("User stack:\n");
+ lldbg(" base: %08x\n", ustackbase);
+ lldbg(" size: %08x\n", ustacksize);
+#else
+ lldbg("sp: %08x\n", sp);
+ lldbg("stack base: %08x\n", ustackbase);
+ lldbg("stack size: %08x\n", ustacksize);
+#endif
+
+ /* Dump the user stack if the stack pointer lies within the allocated user
+ * stack memory.
+ */
+
+ if (sp > ustackbase || sp <= ustackbase - ustacksize)
+ {
+#if !defined(CONFIG_ARCH_INTERRUPTSTACK) || CONFIG_ARCH_INTERRUPTSTACK < 4
+ lldbg("ERROR: Stack pointer is not within allocated stack\n");
+#endif
+ }
+ else
+ {
+ up_stackdump(sp, ustackbase);
+ }
+
+ /* Then dump the registers (if available) */
+
+ up_registerdump();
+}
+#else
+# define up_dumpstate()
+#endif
+
+/****************************************************************************
+ * Name: _up_assert
+ ****************************************************************************/
+
+static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+{
+ /* Are we in an interrupt handler or the idle task? */
+
+ if (current_regs || ((_TCB*)g_readytorun.head)->pid == 0)
+ {
+ (void)irqsave();
+ for(;;)
+ {
+#ifdef CONFIG_ARCH_LEDS
+ up_ledon(LED_PANIC);
+ up_mdelay(250);
+ up_ledoff(LED_PANIC);
+ up_mdelay(250);
+#endif
+ }
+ }
+ else
+ {
+ exit(errorcode);
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_assert
+ ****************************************************************************/
+
+void up_assert(const ubyte *filename, int lineno)
+{
+#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG)
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+#endif
+
+ up_ledon(LED_ASSERTION);
+#if CONFIG_TASK_NAME_SIZE > 0
+ lldbg("Assertion failed at file:%s line: %d task: %s\n",
+ filename, lineno, rtcb->name);
+#else
+ lldbg("Assertion failed at file:%s line: %d\n",
+ filename, lineno);
+#endif
+ up_dumpstate();
+ _up_assert(EXIT_FAILURE);
+}
+
+/****************************************************************************
+ * Name: up_assert_code
+ ****************************************************************************/
+
+void up_assert_code(const ubyte *filename, int lineno, int errorcode)
+{
+#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG)
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+#endif
+
+ up_ledon(LED_ASSERTION);
+#if CONFIG_TASK_NAME_SIZE > 0
+ lldbg("Assertion failed at file:%s line: %d task: %s error code: %d\n",
+ filename, lineno, rtcb->name, errorcode);
+#else
+ lldbg("Assertion failed at file:%s line: %d error code: %d\n",
+ filename, lineno, errorcode);
+#endif
+ up_dumpstate();
+ _up_assert(errorcode);
+}
diff --git a/nuttx/arch/arm/src/common/up_cache.S b/nuttx/arch/arm/src/arm/up_cache.S
index 571217f0e..05926fbb4 100644
--- a/nuttx/arch/arm/src/common/up_cache.S
+++ b/nuttx/arch/arm/src/arm/up_cache.S
@@ -1,5 +1,5 @@
/****************************************************************************
- * common/up_cache.S
+ * arch/arm/src/arm/up_cache.S
*
* Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/arch/arm/src/common/up_copystate.c b/nuttx/arch/arm/src/arm/up_copystate.c
index b73c6c95c..80b34aed7 100644
--- a/nuttx/arch/arm/src/common/up_copystate.c
+++ b/nuttx/arch/arm/src/arm/up_copystate.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/src/common/up_copystate.c
+ * arch/arm/src/arm/up_copystate.c
*
* Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -71,20 +71,12 @@ void up_copystate(uint32 *dest, uint32 *src)
int i;
/* In the current ARM model, the state is always copied to and from the
- * stack and TCB. In the Cortex-M3 model, the state is copied from the
- * stack to the TCB, but only a referenced is passed to get the the state
- * from the TCB. So the following check makes sense only for the Cortex-M3
- * model:
+ * stack and TCB.
*/
-#ifdef __thumb2__
- if (src != dest)
-#endif
+ for (i = 0; i < XCPTCONTEXT_REGS; i++)
{
- for (i = 0; i < XCPTCONTEXT_REGS; i++)
- {
- *dest++ = *src++;
- }
+ *dest++ = *src++;
}
}
diff --git a/nuttx/arch/arm/src/common/up_dataabort.c b/nuttx/arch/arm/src/arm/up_dataabort.c
index 334cdc4c1..df51f2343 100644
--- a/nuttx/arch/arm/src/common/up_dataabort.c
+++ b/nuttx/arch/arm/src/arm/up_dataabort.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * arch/arm/src/common/up_dataabort.c
+ * arch/arm/src/arm/up_dataabort.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/arm/src/arm/up_doirq.c b/nuttx/arch/arm/src/arm/up_doirq.c
new file mode 100644
index 000000000..948550904
--- /dev/null
+++ b/nuttx/arch/arm/src/arm/up_doirq.c
@@ -0,0 +1,104 @@
+/****************************************************************************
+ * arch/arm/src/arm/up_doirq.c
+ *
+ * Copyright (C) 2007-2009 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 NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <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 Functions
+ ****************************************************************************/
+
+void up_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/common/up_fullcontextrestore.S b/nuttx/arch/arm/src/arm/up_fullcontextrestore.S
index 43dcf6573..c99337636 100644
--- a/nuttx/arch/arm/src/common/up_fullcontextrestore.S
+++ b/nuttx/arch/arm/src/arm/up_fullcontextrestore.S
@@ -1,5 +1,5 @@
/**************************************************************************
- * common/up_fullcontextrestore.S
+ * arch/arm/src/arm/up_fullcontextrestore.S
*
* Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/arch/arm/src/common/up_head.S b/nuttx/arch/arm/src/arm/up_head.S
index 0b4666221..dda8566d3 100644
--- a/nuttx/arch/arm/src/common/up_head.S
+++ b/nuttx/arch/arm/src/arm/up_head.S
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/src/common/up_head.S
+ * arch/arm/src/arm/up_head.S
*
* Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/arch/arm/src/common/up_initialstate.c b/nuttx/arch/arm/src/arm/up_initialstate.c
index 9c683a950..deed07209 100644
--- a/nuttx/arch/arm/src/common/up_initialstate.c
+++ b/nuttx/arch/arm/src/arm/up_initialstate.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/src/common/up_initialstate.c
+ * arch/arm/src/arm/up_initialstate.c
*
* Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -46,10 +46,6 @@
#include "up_internal.h"
#include "up_arch.h"
-#ifdef __thumb2__
-# include "cortexm3_psr.h"
-#endif
-
/****************************************************************************
* Private Definitions
****************************************************************************/
@@ -88,25 +84,10 @@ void up_initial_state(_TCB *tcb)
memset(xcp, 0, sizeof(struct xcptcontext));
- /* Save the initial stack point */
+ /* Save the initial stack pointer */
xcp->regs[REG_SP] = (uint32)tcb->adj_stack_ptr;
-#ifdef __thumb2__
- /* Save the task entry point (stripping off the thumb bit) */
-
- xcp->regs[REG_PC] = (uint32)tcb->start & ~1;
-
- /* Specify thumb mode */
-
- xcp->regs[REG_XPSR] = CORTEXM3_XPSR_T;
-
- /* Enable or disable interrupts, based on user configuration */
-
-# ifdef CONFIG_SUPPRESS_INTERRUPTS
- xcp->regs[REG_PRIMASK] = 1;
-# endif
-#else /* __thumb2__ */
/* Save the task entry point */
xcp->regs[REG_PC] = (uint32)tcb->start;
@@ -118,5 +99,5 @@ void up_initial_state(_TCB *tcb)
# else
xcp->regs[REG_CPSR] = SVC_MODE | PSR_F_BIT;
# endif
-#endif /* __thumb2__ */
}
+
diff --git a/nuttx/arch/arm/src/common/up_nommuhead.S b/nuttx/arch/arm/src/arm/up_nommuhead.S
index e6ff048bb..05c5cf9e6 100644
--- a/nuttx/arch/arm/src/common/up_nommuhead.S
+++ b/nuttx/arch/arm/src/arm/up_nommuhead.S
@@ -1,5 +1,5 @@
/****************************************************************************
- * common/up_nommuhead.S
+ * arch/arm/src/arm/up_nommuhead.S
*
* Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/arch/arm/src/common/up_prefetchabort.c b/nuttx/arch/arm/src/arm/up_prefetchabort.c
index 809c90d95..3f6a1c914 100644
--- a/nuttx/arch/arm/src/common/up_prefetchabort.c
+++ b/nuttx/arch/arm/src/arm/up_prefetchabort.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * arch/arm/src/common/up_prefetchabort.c
+ * arch/arm/src/src/up_prefetchabort.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/arm/src/common/up_saveusercontext.S b/nuttx/arch/arm/src/arm/up_saveusercontext.S
index dfae477c4..8d154d187 100644
--- a/nuttx/arch/arm/src/common/up_saveusercontext.S
+++ b/nuttx/arch/arm/src/arm/up_saveusercontext.S
@@ -1,5 +1,5 @@
/**************************************************************************
- * common/up_saveusercontext.S
+ * arch/arm/src/arm/up_saveusercontext.S
*
* Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/arch/arm/src/arm/up_schedulesigaction.c b/nuttx/arch/arm/src/arm/up_schedulesigaction.c
new file mode 100644
index 000000000..af536bd07
--- /dev/null
+++ b/nuttx/arch/arm/src/arm/up_schedulesigaction.c
@@ -0,0 +1,203 @@
+/****************************************************************************
+ * arch/arm/src/arm/up_schedulesigaction.c
+ *
+ * Copyright (C) 2007-2009 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 NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#ifndef CONFIG_DISABLE_SIGNALS
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_schedule_sigaction
+ *
+ * Description:
+ * This function is called by the OS when one or more
+ * signal handling actions have been queued for execution.
+ * The architecture specific code must configure things so
+ * that the 'igdeliver' callback is executed on the thread
+ * specified by 'tcb' as soon as possible.
+ *
+ * This function may be called from interrupt handling logic.
+ *
+ * This operation should not cause the task to be unblocked
+ * nor should it cause any immediate execution of sigdeliver.
+ * Typically, a few cases need to be considered:
+ *
+ * (1) This function may be called from an interrupt handler
+ * During interrupt processing, all xcptcontext structures
+ * should be valid for all tasks. That structure should
+ * be modified to invoke sigdeliver() either on return
+ * from (this) interrupt or on some subsequent context
+ * switch to the recipient task.
+ * (2) If not in an interrupt handler and the tcb is NOT
+ * the currently executing task, then again just modify
+ * the saved xcptcontext structure for the recipient
+ * task so it will invoke sigdeliver when that task is
+ * later resumed.
+ * (3) If not in an interrupt handler and the tcb IS the
+ * currently executing task -- just call the signal
+ * handler now.
+ *
+ ****************************************************************************/
+
+void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
+{
+ /* Refuse to handle nested signal actions */
+
+ sdbg("tcb=0x%p sigdeliver=0x%p\n", tcb, sigdeliver);
+
+ if (!tcb->xcp.sigdeliver)
+ {
+ irqstate_t flags;
+
+ /* Make sure that interrupts are disabled */
+
+ flags = irqsave();
+
+ /* First, handle some special cases when the signal is
+ * being delivered to the currently executing task.
+ */
+
+ sdbg("rtcb=0x%p current_regs=0x%p\n", g_readytorun.head, current_regs);
+
+ if (tcb == (_TCB*)g_readytorun.head)
+ {
+ /* CASE 1: We are not in an interrupt handler and
+ * a task is signalling itself for some reason.
+ */
+
+ if (!current_regs)
+ {
+ /* In this case just deliver the signal now. */
+
+ sigdeliver(tcb);
+ }
+
+ /* CASE 2: We are in an interrupt handler AND the
+ * interrupted task is the same as the one that
+ * must receive the signal, then we will have to modify
+ * the return state as well as the state in the TCB.
+ *
+ * Hmmm... there looks like a latent bug here: The following
+ * logic would fail in the strange case where we are in an
+ * interrupt handler, the thread is signalling itself, but
+ * a context switch to another task has occurred so that
+ * current_regs does not refer to the thread at g_readytorun.head!
+ */
+
+ else
+ {
+ /* Save the return lr and cpsr and one scratch register
+ * These will be restored by the signal trampoline after
+ * the signals have been delivered.
+ */
+
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_pc = current_regs[REG_PC];
+ tcb->xcp.saved_cpsr = current_regs[REG_CPSR];
+
+ /* Then set up to vector to the trampoline with interrupts
+ * disabled
+ */
+
+ current_regs[REG_PC] = (uint32)up_sigdeliver;
+ current_regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT;
+
+ /* And make sure that the saved context in the TCB
+ * is the same as the interrupt return context.
+ */
+
+ up_savestate(tcb->xcp.regs);
+ }
+ }
+
+ /* Otherwise, we are (1) signaling a task is not running
+ * from an interrupt handler or (2) we are not in an
+ * interrupt handler and the running task is signalling
+ * some non-running task.
+ */
+
+ else
+ {
+ /* Save the return lr and cpsr and one scratch register
+ * These will be restored by the signal trampoline after
+ * the signals have been delivered.
+ */
+
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC];
+ tcb->xcp.saved_cpsr = tcb->xcp.regs[REG_CPSR];
+
+ /* Then set up to vector to the trampoline with interrupts
+ * disabled
+ */
+
+ tcb->xcp.regs[REG_PC] = (uint32)up_sigdeliver;
+ tcb->xcp.regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT;
+ }
+
+ irqrestore(flags);
+ }
+}
+
+#endif /* !CONFIG_DISABLE_SIGNALS */
diff --git a/nuttx/arch/arm/src/common/up_sigdeliver.c b/nuttx/arch/arm/src/arm/up_sigdeliver.c
index aff743884..8b12a88cc 100644
--- a/nuttx/arch/arm/src/common/up_sigdeliver.c
+++ b/nuttx/arch/arm/src/arm/up_sigdeliver.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * common/up_sigdeliver.c
+ * arch/arm/src/arm/up_sigdeliver.c
*
* Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -81,7 +81,6 @@
void up_sigdeliver(void)
{
-#ifndef CONFIG_DISABLE_SIGNALS
_TCB *rtcb = (_TCB*)g_readytorun.head;
uint32 regs[XCPTCONTEXT_REGS];
sig_deliver_t sigdeliver;
@@ -103,12 +102,7 @@ void up_sigdeliver(void)
up_copystate(regs, rtcb->xcp.regs);
regs[REG_PC] = rtcb->xcp.saved_pc;
-#ifdef __thumb2__
- regs[REG_PRIMASK] = rtcb->xcp.saved_primask;
- regs[REG_XPSR] = rtcb->xcp.saved_xpsr;
-#else
regs[REG_CPSR] = rtcb->xcp.saved_cpsr;
-#endif
/* Get a local copy of the sigdeliver function pointer.
* we do this so that we can nullify the sigdeliver
@@ -122,11 +116,7 @@ void up_sigdeliver(void)
/* Then restore the task interrupt statat. */
-#ifdef __thumb2__
- irqrestore((uint16)regs[REG_PRIMASK]);
-#else
irqrestore(regs[REG_CPSR]);
-#endif
/* Deliver the signals */
@@ -147,8 +137,7 @@ void up_sigdeliver(void)
up_ledoff(LED_SIGNAL);
up_fullcontextrestore(regs);
-#endif
-}
+\}
#endif /* !CONFIG_DISABLE_SIGNALS */
diff --git a/nuttx/arch/arm/src/common/up_syscall.c b/nuttx/arch/arm/src/arm/up_syscall.c
index 2fef9594a..ec38b3500 100644
--- a/nuttx/arch/arm/src/common/up_syscall.c
+++ b/nuttx/arch/arm/src/arm/up_syscall.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * arch/arm/src/common/up_syscall.c
+ * arch/arm/src/arm/up_syscall.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/arm/src/common/up_undefinedinsn.c b/nuttx/arch/arm/src/arm/up_undefinedinsn.c
index 3a6bd39f6..e15457960 100644
--- a/nuttx/arch/arm/src/common/up_undefinedinsn.c
+++ b/nuttx/arch/arm/src/arm/up_undefinedinsn.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * arch/arm/src/common/up_undefinedinsn.c
+ * arch/arm/src/arm/up_undefinedinsn.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/arm/src/common/up_vectoraddrexcptn.S b/nuttx/arch/arm/src/arm/up_vectoraddrexcptn.S
index 09d7afc93..28df31481 100644
--- a/nuttx/arch/arm/src/common/up_vectoraddrexcptn.S
+++ b/nuttx/arch/arm/src/arm/up_vectoraddrexcptn.S
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/common/up_vectoraddrexceptn.S
+ * arch/arm/src/src/up_vectoraddrexceptn.S
*
- * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/arm/src/common/up_vectors.S b/nuttx/arch/arm/src/arm/up_vectors.S
index 97e2b0343..a084b8594 100644
--- a/nuttx/arch/arm/src/common/up_vectors.S
+++ b/nuttx/arch/arm/src/arm/up_vectors.S
@@ -1,5 +1,5 @@
/************************************************************************************
- * arch/arm/src/common/up_vectors.S
+ * arch/arm/src/arm/up_vectors.S
*
* Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/arch/arm/src/common/up_vectortab.S b/nuttx/arch/arm/src/arm/up_vectortab.S
index 0fad04ad6..b1efcce3f 100644
--- a/nuttx/arch/arm/src/common/up_vectortab.S
+++ b/nuttx/arch/arm/src/arm/up_vectortab.S
@@ -1,5 +1,5 @@
/****************************************************************************
- * common/up_vectortab.S
+ * arch/arm/src/arm/up_vectortab.S
*
* Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/arch/arm/src/common/up_arch.h b/nuttx/arch/arm/src/common/up_arch.h
index 71a33bb3e..6c8a2a6e3 100644
--- a/nuttx/arch/arm/src/common/up_arch.h
+++ b/nuttx/arch/arm/src/common/up_arch.h
@@ -45,7 +45,6 @@
# include <sys/types.h>
#endif
-#include "arm.h"
#include <arch/board/board.h>
#include "chip.h"
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 34a7918e1..d5c350e1e 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -77,7 +77,7 @@
* a referenced is passed to get the the state from the TCB.
*/
-#ifdef __thumb2__
+#ifdef CONFIG_ARCH_CORTEXM3
# define up_savestate(regs) up_copystate(regs, current_regs)
# define up_restorestate(regs) (current_regs = regs)
#else
@@ -136,7 +136,7 @@ extern void up_boot(void);
extern void up_copystate(uint32 *dest, uint32 *src);
extern void up_dataabort(uint32 *regs);
extern void up_decodeirq(uint32 *regs);
-#ifdef __thumb2__
+#ifdef CONFIG_ARCH_CORTEXM3
extern uint32 *up_doirq(int irq, uint32 *regs);
#else
extern void up_doirq(int irq, uint32 *regs);
diff --git a/nuttx/arch/arm/src/common/cortexm3_nvic.h b/nuttx/arch/arm/src/cortexm3/nvic.h
index d627a4dab..3cd094133 100644
--- a/nuttx/arch/arm/src/common/cortexm3_nvic.h
+++ b/nuttx/arch/arm/src/cortexm3/nvic.h
@@ -1,5 +1,5 @@
/************************************************************************************
- * arch/arm/src/common/cortexm3_nvic.h
+ * arch/arm/src/cortexm3/nvic.h
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/arch/arm/src/common/cortexm3_psr.h b/nuttx/arch/arm/src/cortexm3/psr.h
index 9f7d2cc72..dea45555a 100644
--- a/nuttx/arch/arm/src/common/cortexm3_psr.h
+++ b/nuttx/arch/arm/src/cortexm3/psr.h
@@ -1,5 +1,5 @@
/************************************************************************************
- * arch/arm/src/common/cortexm3_psr.h
+ * arch/arm/src/cortexm3/psr.h
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/arch/arm/src/common/up_assert.c b/nuttx/arch/arm/src/cortexm3/up_assert.c
index dcb254e60..ec2339887 100644
--- a/nuttx/arch/arm/src/common/up_assert.c
+++ b/nuttx/arch/arm/src/cortexm3/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * common/up_assert.c
+ * arch/arm/src/cortexm3/up_assert.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -121,7 +121,6 @@ static inline void up_registerdump(void)
if (current_regs)
{
-#ifdef __thumb2__
/* Yes.. dump the interrupt registers */
lldbg("R0: %08x %08x %08x %08x %08x %08x %08x %08x\n",
@@ -136,21 +135,6 @@ static inline void up_registerdump(void)
current_regs[REG_R14], current_regs[REG_R15]);
lldbg("xPSR: %08x PRIMASK: %08x\n",
current_regs[REG_XPSR], current_regs[REG_PRIMASK]);
-#else
- int regs;
-
- /* Yes.. dump the interrupt registers */
-
- for (regs = REG_R0; regs <= REG_R15; regs += 8)
- {
- uint32 *ptr = (uint32*)&current_regs[regs];
- lldbg("R%d: %08x %08x %08x %08x %08x %08x %08x %08x\n",
- regs, ptr[0], ptr[1], ptr[2], ptr[3],
- ptr[4], ptr[5], ptr[6], ptr[7]);
- }
-
- lldbg("CPSR: %08x\n", current_regs[REG_CPSR]);
-#endif
}
}
#else
diff --git a/nuttx/arch/arm/src/cortexm3/up_copystate.c b/nuttx/arch/arm/src/cortexm3/up_copystate.c
new file mode 100644
index 000000000..a7e7b1166
--- /dev/null
+++ b/nuttx/arch/arm/src/cortexm3/up_copystate.c
@@ -0,0 +1,86 @@
+/****************************************************************************
+ * arch/arm/src/cortexm3/up_copystate.c
+ *
+ * Copyright (C) 2009 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 NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_undefinedinsn
+ ****************************************************************************/
+
+/* A little faster than most memcpy's */
+
+void up_copystate(uint32 *dest, uint32 *src)
+{
+ int i;
+
+ /* In the Cortex-M3 model, the state is copied from the stack to the TCB,
+ * but only a reference is passed to get the state from the TCB. So the
+ * following check avoids copying the TCB save area onto itself:
+ */
+
+ if (src != dest)
+ {
+ for (i = 0; i < XCPTCONTEXT_REGS; i++)
+ {
+ *dest++ = *src++;
+ }
+ }
+}
+
diff --git a/nuttx/arch/arm/src/common/up_doirq.c b/nuttx/arch/arm/src/cortexm3/up_doirq.c
index 861f5f3d8..8c749ce5f 100644
--- a/nuttx/arch/arm/src/common/up_doirq.c
+++ b/nuttx/arch/arm/src/cortexm3/up_doirq.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * arch/arm/src/common/up_doirq.c
+ * arch/arm/src/cortexm3/up_doirq.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -66,11 +66,7 @@
* Public Functions
****************************************************************************/
-#ifdef __thumb2__
uint32 *up_doirq(int irq, uint32 *regs)
-#else
-void up_doirq(int irq, uint32 *regs)
-#endif
{
up_ledon(LED_INIRQ);
#ifdef CONFIG_SUPPRESS_INTERRUPTS
@@ -94,13 +90,13 @@ void up_doirq(int irq, uint32 *regs)
irq_dispatch(irq, regs);
/* If a context switch occurred while processing the interrupt
- * then current_regs may have value (depending upon the implementaton
- * of context switching for te particular chip.
+ * then current_regs may have change value. If we return any value
+ * different from the input regs, then the lower level will know
+ * that a context switch occurred during interrupt processing.
*/
-#ifdef __thumb2__
regs = current_regs;
-#endif
+
/* Indicate that we are no long in an interrupt handler */
current_regs = NULL;
@@ -113,7 +109,5 @@ void up_doirq(int irq, uint32 *regs)
}
up_ledoff(LED_INIRQ);
#endif
-#ifdef __thumb2__
return regs;
-#endif
}
diff --git a/nuttx/arch/arm/src/cortexm3/up_initialstate.c b/nuttx/arch/arm/src/cortexm3/up_initialstate.c
new file mode 100644
index 000000000..c529064d4
--- /dev/null
+++ b/nuttx/arch/arm/src/cortexm3/up_initialstate.c
@@ -0,0 +1,106 @@
+/****************************************************************************
+ * arch/arm/src/cortexm3/up_initialstate.c
+ *
+ * Copyright (C) 2009 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 NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <string.h>
+
+#include <nuttx/arch.h>
+
+#include "up_internal.h"
+#include "up_arch.h"
+#include "psr.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_initial_state
+ *
+ * Description:
+ * A new thread is being started and a new TCB
+ * has been created. This function is called to initialize
+ * the processor specific portions of the new TCB.
+ *
+ * This function must setup the intial architecture registers
+ * and/or stack so that execution will begin at tcb->start
+ * on the next context switch.
+ *
+ ****************************************************************************/
+
+void up_initial_state(_TCB *tcb)
+{
+ struct xcptcontext *xcp = &tcb->xcp;
+
+ /* Initialize the initial exception register context structure */
+
+ memset(xcp, 0, sizeof(struct xcptcontext));
+
+ /* Save the initial stack pointer */
+
+ xcp->regs[REG_SP] = (uint32)tcb->adj_stack_ptr;
+
+ /* Save the task entry point (stripping off the thumb bit) */
+
+ xcp->regs[REG_PC] = (uint32)tcb->start & ~1;
+
+ /* Specify thumb mode */
+
+ xcp->regs[REG_XPSR] = CORTEXM3_XPSR_T;
+
+ /* Enable or disable interrupts, based on user configuration */
+
+# ifdef CONFIG_SUPPRESS_INTERRUPTS
+ xcp->regs[REG_PRIMASK] = 1;
+# endif
+}
+
diff --git a/nuttx/arch/arm/src/common/up_schedulesigaction.c b/nuttx/arch/arm/src/cortexm3/up_schedulesigaction.c
index a4ae20953..31219874b 100644
--- a/nuttx/arch/arm/src/common/up_schedulesigaction.c
+++ b/nuttx/arch/arm/src/cortexm3/up_schedulesigaction.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * common/up_schedulesigaction.c
+ * arch/arm/src/cortexm3/up_schedulesigaction.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -45,6 +45,7 @@
#include <nuttx/arch.h>
+#include "psr.h"
#include "os_internal.h"
#include "up_internal.h"
#include "up_arch.h"
@@ -154,24 +155,16 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
tcb->xcp.sigdeliver = sigdeliver;
tcb->xcp.saved_pc = current_regs[REG_PC];
-#ifdef __thumb2__
tcb->xcp.saved_primask = current_regs[REG_PRIMASK];
tcb->xcp.saved_xpsr = current_regs[REG_XPSR];
-#else
- tcb->xcp.saved_cpsr = current_regs[REG_CPSR];
-#endif
/* Then set up to vector to the trampoline with interrupts
* disabled
*/
current_regs[REG_PC] = (uint32)up_sigdeliver;
-#ifdef __thumb2__
current_regs[REG_PRIMASK] = 1;
- current_regs[REG_XPSR] = 0;
-#else
- current_regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT;
-#endif
+ current_regs[REG_XPSR] = CORTEXM3_XPSR_T;
/* And make sure that the saved context in the TCB
* is the same as the interrupt return context.
@@ -196,24 +189,16 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
tcb->xcp.sigdeliver = sigdeliver;
tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC];
-#ifdef __thumb2__
tcb->xcp.saved_primask = tcb->xcp.regs[REG_PRIMASK];
tcb->xcp.saved_xpsr = tcb->xcp.regs[REG_XPSR];
-#else
- tcb->xcp.saved_cpsr = tcb->xcp.regs[REG_CPSR];
-#endif
/* Then set up to vector to the trampoline with interrupts
* disabled
*/
tcb->xcp.regs[REG_PC] = (uint32)up_sigdeliver;
-#ifdef __thumb2__
tcb->xcp.regs[REG_PRIMASK] = 1;
- tcb->xcp.regs[REG_XPSR] = 0;
-#else
- tcb->xcp.regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT;
-#endif
+ tcb->xcp.regs[REG_XPSR] = CORTEXM3_XPSR_T;
}
irqrestore(flags);
diff --git a/nuttx/arch/arm/src/cortexm3/up_sigdeliver.c b/nuttx/arch/arm/src/cortexm3/up_sigdeliver.c
new file mode 100644
index 000000000..d0241dfa1
--- /dev/null
+++ b/nuttx/arch/arm/src/cortexm3/up_sigdeliver.c
@@ -0,0 +1,144 @@
+/****************************************************************************
+ * arch/arm/src/cortexm3/up_sigdeliver.c
+ *
+ * Copyright (C) 2009 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 NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#ifndef CONFIG_DISABLE_SIGNALS
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_sigdeliver
+ *
+ * Description:
+ * This is the a signal handling trampoline. When a
+ * signal action was posted. The task context was mucked
+ * with and forced to branch to this location with interrupts
+ * disabled.
+ *
+ ****************************************************************************/
+
+void up_sigdeliver(void)
+{
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+ uint32 regs[XCPTCONTEXT_REGS];
+ sig_deliver_t sigdeliver;
+
+ /* Save the errno. This must be preserved throughout the
+ * signal handling so that the the user code final gets
+ * the correct errno value (probably EINTR).
+ */
+
+ int saved_errno = rtcb->pterrno;
+
+ up_ledon(LED_SIGNAL);
+
+ sdbg("rtcb=%p sigdeliver=%p sigpendactionq.head=%p\n",
+ rtcb, rtcb->xcp.sigdeliver, rtcb->sigpendactionq.head);
+ ASSERT(rtcb->xcp.sigdeliver != NULL);
+
+ /* Save the real return state on the stack. */
+
+ up_copystate(regs, rtcb->xcp.regs);
+ regs[REG_PC] = rtcb->xcp.saved_pc;
+ regs[REG_PRIMASK] = rtcb->xcp.saved_primask;
+ regs[REG_XPSR] = rtcb->xcp.saved_xpsr;
+
+ /* Get a local copy of the sigdeliver function pointer.
+ * we do this so that we can nullify the sigdeliver
+ * function point in the TCB and accept more signal
+ * deliveries while processing the current pending
+ * signals.
+ */
+
+ sigdeliver = rtcb->xcp.sigdeliver;
+ rtcb->xcp.sigdeliver = NULL;
+
+ /* Then restore the task interrupt statat. */
+
+ irqrestore((uint16)regs[REG_PRIMASK]);
+
+ /* Deliver the signals */
+
+ sigdeliver(rtcb);
+
+ /* Output any debug messaged BEFORE restoreing errno
+ * (becuase they may alter errno), then restore the
+ * original errno that is needed by the user logic
+ * (it is probably EINTR).
+ */
+
+ sdbg("Resuming\n");
+ rtcb->pterrno = saved_errno;
+
+ /* Then restore the correct state for this thread of
+ * execution.
+ */
+
+ up_ledoff(LED_SIGNAL);
+ up_fullcontextrestore(regs);
+}
+
+#endif /* !CONFIG_DISABLE_SIGNALS */
+
diff --git a/nuttx/arch/arm/src/lm3s/Make.defs b/nuttx/arch/arm/src/lm3s/Make.defs
index 3eb33dd58..3e0ab3488 100644
--- a/nuttx/arch/arm/src/lm3s/Make.defs
+++ b/nuttx/arch/arm/src/lm3s/Make.defs
@@ -37,13 +37,12 @@ HEAD_ASRC = lm3s_vectors.S
CMN_ASRCS =
CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
- up_createstack.c up_dataabort.c up_mdelay.c up_udelay.c up_exit.c \
+ up_createstack.c up_mdelay.c up_udelay.c up_exit.c \
up_idle.c up_initialize.c up_initialstate.c up_interruptcontext.c \
up_modifyreg8.c up_modifyreg16.c up_modifyreg32.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_doirq.c
+ up_releasepending.c up_releasestack.c up_reprioritizertr.c \
+ up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c \
+ up_usestack.c up_doirq.c
CHIP_ASRCS = lm3s_context.S
CHIP_CSRCS = lm3s_start.c lm3s_syscontrol.c lm3s_irq.c lm3s_svcall.c \
diff --git a/nuttx/arch/arm/src/lm3s/chip.h b/nuttx/arch/arm/src/lm3s/chip.h
index 129cd9f37..6d113cbb7 100644
--- a/nuttx/arch/arm/src/lm3s/chip.h
+++ b/nuttx/arch/arm/src/lm3s/chip.h
@@ -47,7 +47,6 @@
#include "lm3s_syscontrol.h" /* System control module */
#include "lm3s_gpio.h" /* GPIO module */
#include "lm3s_uart.h" /* UART peripherals */
-#include "cortexm3_nvic.h" /* Nested, vectored interrupt controller */
/************************************************************************************
* Definitions
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_context.S b/nuttx/arch/arm/src/lm3s/lm3s_context.S
index 7641b0109..efef06630 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_context.S
+++ b/nuttx/arch/arm/src/lm3s/lm3s_context.S
@@ -40,7 +40,7 @@
#include <nuttx/config.h>
#include <arch/irq.h>
-#include "cortexm3_nvic.h"
+#include "nvic.h"
/************************************************************************************
* Preprocessor Definitions
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_hardfault.c b/nuttx/arch/arm/src/lm3s/lm3s_hardfault.c
index 7a9c76611..7a3e60623 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_hardfault.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_hardfault.c
@@ -49,7 +49,7 @@
#include "up_arch.h"
#include "os_internal.h"
-#include "cortexm3_nvic.h"
+#include "nvic.h"
#include "lm3s_internal.h"
/****************************************************************************
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_irq.c b/nuttx/arch/arm/src/lm3s/lm3s_irq.c
index d75d33304..374c4bfc7 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_irq.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_irq.c
@@ -47,6 +47,7 @@
#include <nuttx/arch.h>
#include <arch/irq.h>
+#include "nvic.h"
#include "up_arch.h"
#include "os_internal.h"
#include "up_internal.h"
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_timerisr.c b/nuttx/arch/arm/src/lm3s/lm3s_timerisr.c
index 95b358df1..714d68c7d 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_timerisr.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_timerisr.c
@@ -44,6 +44,7 @@
#include <nuttx/arch.h>
#include <arch/board/board.h>
+#include "nvic.h"
#include "clock_internal.h"
#include "up_internal.h"
#include "up_arch.h"
diff --git a/nuttx/configs/c5471evm/src/Makefile b/nuttx/configs/c5471evm/src/Makefile
index a44558a45..fab7141e5 100644
--- a/nuttx/configs/c5471evm/src/Makefile
+++ b/nuttx/configs/c5471evm/src/Makefile
@@ -46,7 +46,7 @@ SRCS = $(ASRCS) $(CSRCS)
OBJS = $(AOBJS) $(COBJS)
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
-CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common
+CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/arm
all: libboard$(LIBEXT)
diff --git a/nuttx/configs/eagle100/src/Makefile b/nuttx/configs/eagle100/src/Makefile
index 5d5e93cc3..80f3d2741 100644
--- a/nuttx/configs/eagle100/src/Makefile
+++ b/nuttx/configs/eagle100/src/Makefile
@@ -46,7 +46,7 @@ SRCS = $(ASRCS) $(CSRCS)
OBJS = $(AOBJS) $(COBJS)
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
-CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common
+CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/cortexm3
all: libboard$(LIBEXT)
diff --git a/nuttx/configs/mcu123-lpc214x/src/Makefile b/nuttx/configs/mcu123-lpc214x/src/Makefile
index 82ae474b3..d71ee10ee 100644
--- a/nuttx/configs/mcu123-lpc214x/src/Makefile
+++ b/nuttx/configs/mcu123-lpc214x/src/Makefile
@@ -36,7 +36,7 @@
-include $(TOPDIR)/Make.defs
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
-CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched
+CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/arm -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
diff --git a/nuttx/configs/mx1ads/src/Makefile b/nuttx/configs/mx1ads/src/Makefile
index 9078d5832..56d3af3f3 100644
--- a/nuttx/configs/mx1ads/src/Makefile
+++ b/nuttx/configs/mx1ads/src/Makefile
@@ -46,7 +46,7 @@ SRCS = $(ASRCS) $(CSRCS)
OBJS = $(AOBJS) $(COBJS)
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
-CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common
+CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/arm
all: libboard$(LIBEXT)
diff --git a/nuttx/configs/ntosd-dm320/src/Makefile b/nuttx/configs/ntosd-dm320/src/Makefile
index 51ab671d0..1bd4b6291 100644
--- a/nuttx/configs/ntosd-dm320/src/Makefile
+++ b/nuttx/configs/ntosd-dm320/src/Makefile
@@ -46,7 +46,7 @@ SRCS = $(ASRCS) $(CSRCS)
OBJS = $(AOBJS) $(COBJS)
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
-CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common
+CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/arm
all: libboard$(LIBEXT)
diff --git a/nuttx/configs/olimex-strp711/src/Makefile b/nuttx/configs/olimex-strp711/src/Makefile
index bff294aef..5d8c82b97 100644
--- a/nuttx/configs/olimex-strp711/src/Makefile
+++ b/nuttx/configs/olimex-strp711/src/Makefile
@@ -36,7 +36,7 @@
-include $(TOPDIR)/Make.defs
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
-CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched
+CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/arm -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))