summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/include/armv7-m/irq.h21
-rw-r--r--nuttx/arch/arm/include/armv7-m/irq_cmnvector.h6
-rw-r--r--nuttx/arch/arm/include/armv7-m/irq_lazyfpu.h6
-rw-r--r--nuttx/arch/arm/include/types.h6
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_assert.c7
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_exception.S11
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_hardfault.c16
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_initialstate.c12
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_schedulesigaction.c18
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_sigdeliver.c10
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_irq.c3
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_vectors.S9
-rw-r--r--nuttx/arch/arm/src/lm/lm_irq.c3
-rw-r--r--nuttx/arch/arm/src/lm/lm_vectors.S9
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_irq.c3
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S9
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_irq.c3
-rw-r--r--nuttx/arch/arm/src/sam3u/sam3u_irq.c3
-rw-r--r--nuttx/arch/arm/src/sam3u/sam3u_vectors.S11
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_irq.c3
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_vectors.S17
21 files changed, 148 insertions, 38 deletions
diff --git a/nuttx/arch/arm/include/armv7-m/irq.h b/nuttx/arch/arm/include/armv7-m/irq.h
index 9491e57c0..8acec4c07 100644
--- a/nuttx/arch/arm/include/armv7-m/irq.h
+++ b/nuttx/arch/arm/include/armv7-m/irq.h
@@ -118,7 +118,11 @@ struct xcptcontext
*/
uint32_t saved_pc;
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ uint32_t saved_basepri;
+#else
uint32_t saved_primask;
+#endif
uint32_t saved_xpsr;
#endif
@@ -134,7 +138,7 @@ struct xcptcontext
#ifndef __ASSEMBLY__
-/* Get/set the primask register */
+/* Get/set the PRIMASK register */
static inline uint8_t getprimask(void) inline_function;
static inline uint8_t getprimask(void)
@@ -161,7 +165,11 @@ static inline void setprimask(uint32_t primask)
: "memory");
}
-/* Get/set the basepri register */
+/* Get/set the BASEPRI register. The BASEPRI register defines the minimum
+ * priority for exception processing. When BASEPRI is set to a nonzero
+ * value, it prevents the activation of all exceptions with the same or
+ * lower priority level as the BASEPRI value.
+ */
static inline uint8_t getbasepri(void) inline_function;
static inline uint8_t getbasepri(void)
@@ -210,7 +218,7 @@ static inline irqstate_t irqsave(void)
uint8_t basepri = getbasepri();
setbasepri(NVIC_SYSH_DISABLE_PRIORITY);
- return basepri;
+ return (irqstate_t)basepri;
#else
@@ -237,11 +245,8 @@ static inline irqstate_t irqsave(void)
static inline void irqenable(void) inline_function;
static inline void irqenable(void)
{
-#ifdef CONFIG_ARMV7M_USEBASEPRI
- setbasepri(NVIC_SYSH_PRIORITY_MIN);
-#else
+ setbasepri(0);
__asm__ __volatile__ ("\tcpsie i\n");
-#endif
}
/* Restore saved primask state */
@@ -250,7 +255,7 @@ static inline void irqrestore(irqstate_t flags) inline_function;
static inline void irqrestore(irqstate_t flags)
{
#ifdef CONFIG_ARMV7M_USEBASEPRI
- setbasepri(flags);
+ setbasepri((uint32_t)flags);
#else
/* If bit 0 of the primask is 0, then we need to restore
* interupts.
diff --git a/nuttx/arch/arm/include/armv7-m/irq_cmnvector.h b/nuttx/arch/arm/include/armv7-m/irq_cmnvector.h
index e646731eb..bc67004ed 100644
--- a/nuttx/arch/arm/include/armv7-m/irq_cmnvector.h
+++ b/nuttx/arch/arm/include/armv7-m/irq_cmnvector.h
@@ -51,7 +51,11 @@
*/
#define REG_R13 (0) /* R13 = SP at time of interrupt */
-#define REG_PRIMASK (1) /* PRIMASK */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+# define REG_BASEPRI (1) /* BASEPRI */
+#else
+# define REG_PRIMASK (1) /* PRIMASK */
+#endif
#define REG_R4 (2) /* R4 */
#define REG_R5 (3) /* R5 */
#define REG_R6 (4) /* R6 */
diff --git a/nuttx/arch/arm/include/armv7-m/irq_lazyfpu.h b/nuttx/arch/arm/include/armv7-m/irq_lazyfpu.h
index 2c3600b7f..f2380cbb6 100644
--- a/nuttx/arch/arm/include/armv7-m/irq_lazyfpu.h
+++ b/nuttx/arch/arm/include/armv7-m/irq_lazyfpu.h
@@ -51,7 +51,11 @@
*/
#define REG_R13 (0) /* R13 = SP at time of interrupt */
-#define REG_PRIMASK (1) /* PRIMASK */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+# define REG_BASEPRI (1) /* BASEPRI */
+#else
+# define REG_PRIMASK (1) /* PRIMASK */
+#endif
#define REG_R4 (2) /* R4 */
#define REG_R5 (3) /* R5 */
#define REG_R6 (4) /* R6 */
diff --git a/nuttx/arch/arm/include/types.h b/nuttx/arch/arm/include/types.h
index c06b28950..1d2ea4cfe 100644
--- a/nuttx/arch/arm/include/types.h
+++ b/nuttx/arch/arm/include/types.h
@@ -44,6 +44,8 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
/****************************************************************************
* Definitions
****************************************************************************/
@@ -87,7 +89,11 @@ typedef unsigned int _uintptr_t;
*/
#ifdef __thumb2__
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+typedef unsigned char irqstate_t;
+#else
typedef unsigned short irqstate_t;
+#endif
#else /* __thumb2__ */
typedef unsigned int irqstate_t;
#endif /* __thumb2__ */
diff --git a/nuttx/arch/arm/src/armv7-m/up_assert.c b/nuttx/arch/arm/src/armv7-m/up_assert.c
index 282ff6a57..ab30b09f3 100644
--- a/nuttx/arch/arm/src/armv7-m/up_assert.c
+++ b/nuttx/arch/arm/src/armv7-m/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_assert.c
*
- * Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -147,8 +147,13 @@ static inline void up_registerdump(void)
current_regs[REG_R10], current_regs[REG_R11],
current_regs[REG_R12], current_regs[REG_R13],
current_regs[REG_R14], current_regs[REG_R15]);
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ lldbg("xPSR: %08x BASEPRI: %08x\n",
+ current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
+#else
lldbg("xPSR: %08x PRIMASK: %08x\n",
current_regs[REG_XPSR], current_regs[REG_PRIMASK]);
+#endif
}
}
#else
diff --git a/nuttx/arch/arm/src/armv7-m/up_exception.S b/nuttx/arch/arm/src/armv7-m/up_exception.S
index c9f216027..17344db41 100644
--- a/nuttx/arch/arm/src/armv7-m/up_exception.S
+++ b/nuttx/arch/arm/src/armv7-m/up_exception.S
@@ -2,7 +2,7 @@
* arch/arm/src/stm32/up_exception.S
* arch/arm/src/chip/up_exception.S
*
- * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
* Copyright (C) 2012 Michael Smith. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
@@ -100,7 +100,11 @@ exception_common:
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
/* (ignoring the xPSR[9] alignment bit) */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ mrs r3, basepri /* R3=Current BASEPRI setting */
+#else
mrs r3, primask /* R3=Current PRIMASK setting */
+#endif
#ifdef CONFIG_ARCH_FPU
@@ -205,7 +209,12 @@ exception_common:
/* Restore the interrupt state */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ msr basepri, r3 /* Restore interrupts priority masking*/
+ cpsie i /* Re-enable interrupts */
+#else
msr primask, r3 /* Restore interrupts */
+#endif
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) select the correct stack.
diff --git a/nuttx/arch/arm/src/armv7-m/up_hardfault.c b/nuttx/arch/arm/src/armv7-m/up_hardfault.c
index b043db3df..fa750b525 100644
--- a/nuttx/arch/arm/src/armv7-m/up_hardfault.c
+++ b/nuttx/arch/arm/src/armv7-m/up_hardfault.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_hardfault.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -55,7 +55,9 @@
* Pre-processor Definitions
****************************************************************************/
-/* Debug output from this file may interfere with context switching! */
+/* If CONFIG_ARMV7M_USEBASEPRI=n, then debug output from this file may
+ * interfere with context switching!
+ */
#ifdef CONFIG_DEBUG_HARDFAULT
# define hfdbg(format, arg...) lldbg(format, ##arg)
@@ -92,7 +94,9 @@
int up_hardfault(int irq, FAR void *context)
{
+#if defined(CONFIG_DEBUG_HARDFAULT) || !defined(CONFIG_ARMV7M_USEBASEPRI)
uint32_t *regs = (uint32_t*)context;
+#endif
/* Get the value of the program counter where the fault occurred */
@@ -133,7 +137,13 @@ int up_hardfault(int irq, FAR void *context)
hfdbg(" R8: %08x %08x %08x %08x %08x %08x %08x %08x\n",
regs[REG_R8], regs[REG_R9], regs[REG_R10], regs[REG_R11],
regs[REG_R12], regs[REG_R13], regs[REG_R14], regs[REG_R15]);
- hfdbg(" PSR=%08x\n", regs[REG_XPSR]);
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ hfdbg(" xPSR: %08x BASEPRI: %08x (saved)\n",
+ current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
+#else
+ hfdbg(" xPSR: %08x PRIMASK: %08x (saved)\n",
+ current_regs[REG_XPSR], current_regs[REG_PRIMASK]);
+#endif
(void)irqsave();
lldbg("PANIC!!! Hard fault: %08x\n", getreg32(NVIC_HFAULTS));
diff --git a/nuttx/arch/arm/src/armv7-m/up_initialstate.c b/nuttx/arch/arm/src/armv7-m/up_initialstate.c
index 81a4dc9ea..635a700fd 100644
--- a/nuttx/arch/arm/src/armv7-m/up_initialstate.c
+++ b/nuttx/arch/arm/src/armv7-m/up_initialstate.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_initialstate.c
*
- * Copyright (C) 2009, 2011-2 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -148,7 +148,7 @@ void up_initial_state(_TCB *tcb)
xcp->regs[REG_FPSCR] = 0; // XXX initial FPSCR should be configurable
xcp->regs[REG_FPReserved] = 0;
-#endif
+#endif /* CONFIG_ARCH_FPU */
#ifdef CONFIG_NUTTX_KERNEL
if ((tcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_KERNEL)
@@ -157,7 +157,7 @@ void up_initial_state(_TCB *tcb)
xcp->regs[REG_EXC_RETURN] = EXC_RETURN_PROCESS_STACK;
}
-#endif
+#endif /* CONFIG_NUTTX_KERNEL */
#else /* CONFIG_ARMV7M_CMNVECTOR */
@@ -181,12 +181,16 @@ void up_initial_state(_TCB *tcb)
xcp->regs[REG_EXC_RETURN] = EXC_RETURN_UNPRIVTHR;
}
-#endif
+#endif /* CONFIG_NUTTX_KERNEL */
#endif /* CONFIG_ARMV7M_CMNVECTOR */
/* Enable or disable interrupts, based on user configuration */
#ifdef CONFIG_SUPPRESS_INTERRUPTS
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ xcp->regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
+#else
xcp->regs[REG_PRIMASK] = 1;
#endif
+#endif /* CONFIG_SUPPRESS_INTERRUPTS */
}
diff --git a/nuttx/arch/arm/src/armv7-m/up_schedulesigaction.c b/nuttx/arch/arm/src/armv7-m/up_schedulesigaction.c
index 9e6dbd14b..9221a69a2 100644
--- a/nuttx/arch/arm/src/armv7-m/up_schedulesigaction.c
+++ b/nuttx/arch/arm/src/armv7-m/up_schedulesigaction.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_schedulesigaction.c
*
- * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -155,7 +155,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
tcb->xcp.sigdeliver = sigdeliver;
tcb->xcp.saved_pc = current_regs[REG_PC];
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ tcb->xcp.saved_basepri = current_regs[REG_BASEPRI];
+#else
tcb->xcp.saved_primask = current_regs[REG_PRIMASK];
+#endif
tcb->xcp.saved_xpsr = current_regs[REG_XPSR];
/* Then set up to vector to the trampoline with interrupts
@@ -163,7 +167,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
*/
current_regs[REG_PC] = (uint32_t)up_sigdeliver;
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ current_regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
+#else
current_regs[REG_PRIMASK] = 1;
+#endif
current_regs[REG_XPSR] = ARMV7M_XPSR_T;
/* And make sure that the saved context in the TCB
@@ -189,7 +197,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
tcb->xcp.sigdeliver = sigdeliver;
tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC];
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ tcb->xcp.saved_basepri = tcb->xcp.regs[REG_BASEPRI];
+#else
tcb->xcp.saved_primask = tcb->xcp.regs[REG_PRIMASK];
+#endif
tcb->xcp.saved_xpsr = tcb->xcp.regs[REG_XPSR];
/* Then set up to vector to the trampoline with interrupts
@@ -197,7 +209,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
*/
tcb->xcp.regs[REG_PC] = (uint32_t)up_sigdeliver;
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ tcb->xcp.regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
+#else
tcb->xcp.regs[REG_PRIMASK] = 1;
+#endif
tcb->xcp.regs[REG_XPSR] = ARMV7M_XPSR_T;
}
diff --git a/nuttx/arch/arm/src/armv7-m/up_sigdeliver.c b/nuttx/arch/arm/src/armv7-m/up_sigdeliver.c
index 38673c41d..654214b39 100644
--- a/nuttx/arch/arm/src/armv7-m/up_sigdeliver.c
+++ b/nuttx/arch/arm/src/armv7-m/up_sigdeliver.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_sigdeliver.c
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -102,7 +102,11 @@ void up_sigdeliver(void)
up_copystate(regs, rtcb->xcp.regs);
regs[REG_PC] = rtcb->xcp.saved_pc;
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ regs[REG_BASEPRI] = rtcb->xcp.saved_basepri;
+#else
regs[REG_PRIMASK] = rtcb->xcp.saved_primask;
+#endif
regs[REG_XPSR] = rtcb->xcp.saved_xpsr;
/* Get a local copy of the sigdeliver function pointer. We do this so that
@@ -115,7 +119,11 @@ void up_sigdeliver(void)
/* Then restore the task interrupt state */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ irqrestore((uint8_t)regs[REG_BASEPRI]);
+#else
irqrestore((uint16_t)regs[REG_PRIMASK]);
+#endif
/* Deliver the signals */
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_irq.c b/nuttx/arch/arm/src/kinetis/kinetis_irq.c
index 31310b03c..37a6a4a63 100644
--- a/nuttx/arch/arm/src/kinetis/kinetis_irq.c
+++ b/nuttx/arch/arm/src/kinetis/kinetis_irq.c
@@ -428,8 +428,7 @@ void up_irqinitialize(void)
/* And finally, enable interrupts */
#ifndef CONFIG_SUPPRESS_INTERRUPTS
- setbasepri(NVIC_SYSH_PRIORITY_MAX);
- irqrestore(0);
+ irqenable();
#endif
}
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_vectors.S b/nuttx/arch/arm/src/kinetis/kinetis_vectors.S
index faa1ce7a7..7fa223615 100644
--- a/nuttx/arch/arm/src/kinetis/kinetis_vectors.S
+++ b/nuttx/arch/arm/src/kinetis/kinetis_vectors.S
@@ -605,7 +605,11 @@ kinetis_common:
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ mrs r3, basepri /* R3=Current BASEPRI setting */
+#else
mrs r3, primask /* R3=Current PRIMASK setting */
+#endif
#ifdef CONFIG_NUTTX_KERNEL
stmdb r1!, {r2-r11,r14} /* Save the remaining registers plus the SP value */
#else
@@ -691,7 +695,12 @@ kinetis_common:
/* Restore the interrupt state */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ msr basepri, r3 /* Restore interrupts priority masking*/
+ cpsie i /* Re-enable interrupts */
+#else
msr primask, r3 /* Restore interrupts */
+#endif
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP
diff --git a/nuttx/arch/arm/src/lm/lm_irq.c b/nuttx/arch/arm/src/lm/lm_irq.c
index dc9997afa..7d8d2135a 100644
--- a/nuttx/arch/arm/src/lm/lm_irq.c
+++ b/nuttx/arch/arm/src/lm/lm_irq.c
@@ -379,8 +379,7 @@ void up_irqinitialize(void)
/* And finally, enable interrupts */
- setbasepri(NVIC_SYSH_PRIORITY_MAX);
- irqrestore(0);
+ irqenable();
#endif
}
diff --git a/nuttx/arch/arm/src/lm/lm_vectors.S b/nuttx/arch/arm/src/lm/lm_vectors.S
index d3798fbb7..1d3553b4e 100644
--- a/nuttx/arch/arm/src/lm/lm_vectors.S
+++ b/nuttx/arch/arm/src/lm/lm_vectors.S
@@ -203,7 +203,11 @@ lm_irqcommon:
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ mrs r3, basepri /* R3=Current BASEPRI setting */
+#else
mrs r3, primask /* R3=Current PRIMASK setting */
+#endif
#ifdef CONFIG_NUTTX_KERNEL
stmdb r1!, {r2-r11,r14} /* Save the remaining registers plus the SP value */
#else
@@ -289,7 +293,12 @@ lm_irqcommon:
/* Restore the interrupt state */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ msr basepri, r3 /* Restore interrupts priority masking*/
+ cpsie i /* Re-enable interrupts */
+#else
msr primask, r3 /* Restore interrupts */
+#endif
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_irq.c b/nuttx/arch/arm/src/lpc17xx/lpc17_irq.c
index 2d66dd0b1..c9b289d4e 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_irq.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_irq.c
@@ -374,8 +374,7 @@ void up_irqinitialize(void)
/* And finally, enable interrupts */
#ifndef CONFIG_SUPPRESS_INTERRUPTS
- setbasepri(NVIC_SYSH_PRIORITY_MAX);
- irqrestore(0);
+ irqenable();
#endif
}
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S b/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S
index 74e53b411..e2cf91b1c 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S
@@ -217,7 +217,11 @@ lpc17_common:
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ mrs r3, basepri /* R3=Current BASEPRI setting */
+#else
mrs r3, primask /* R3=Current PRIMASK setting */
+#endif
#ifdef CONFIG_NUTTX_KERNEL
stmdb r1!, {r2-r11,r14} /* Save the remaining registers plus the SP value */
#else
@@ -303,7 +307,12 @@ lpc17_common:
/* Restore the interrupt state */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ msr basepri, r3 /* Restore interrupts priority masking*/
+ cpsie i /* Re-enable interrupts */
+#else
msr primask, r3 /* Restore interrupts */
+#endif
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_irq.c b/nuttx/arch/arm/src/lpc43xx/lpc43_irq.c
index 2fddd79ad..1867aa150 100644
--- a/nuttx/arch/arm/src/lpc43xx/lpc43_irq.c
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_irq.c
@@ -403,8 +403,7 @@ void up_irqinitialize(void)
/* And finally, enable interrupts */
#ifndef CONFIG_SUPPRESS_INTERRUPTS
- setbasepri(LPC43M4_SYSH_PRIORITY_MAX);
- irqrestore(0);
+ irqenable();
#endif
}
diff --git a/nuttx/arch/arm/src/sam3u/sam3u_irq.c b/nuttx/arch/arm/src/sam3u/sam3u_irq.c
index d9fd4dac8..690a075ef 100644
--- a/nuttx/arch/arm/src/sam3u/sam3u_irq.c
+++ b/nuttx/arch/arm/src/sam3u/sam3u_irq.c
@@ -366,8 +366,7 @@ void up_irqinitialize(void)
/* And finally, enable interrupts */
- setbasepri(NVIC_SYSH_PRIORITY_MAX);
- irqrestore(0);
+ irqenable();
#endif
}
diff --git a/nuttx/arch/arm/src/sam3u/sam3u_vectors.S b/nuttx/arch/arm/src/sam3u/sam3u_vectors.S
index 3ed17f767..53e2f636c 100644
--- a/nuttx/arch/arm/src/sam3u/sam3u_vectors.S
+++ b/nuttx/arch/arm/src/sam3u/sam3u_vectors.S
@@ -2,7 +2,7 @@
* arch/arm/src/sam3u/sam3u_vectors.S
* arch/arm/src/chip/sam3u_vectors.S
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -249,7 +249,11 @@ sam3u_common:
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ mrs r3, basepri /* R3=Current BASEPRI setting */
+#else
mrs r3, primask /* R3=Current PRIMASK setting */
+#endif
#ifdef CONFIG_NUTTX_KERNEL
stmdb r1!, {r2-r11,r14} /* Save the remaining registers plus the SP value */
#else
@@ -335,7 +339,12 @@ sam3u_common:
/* Restore the interrupt state */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ msr basepri, r3 /* Restore interrupts priority masking*/
+ cpsie i /* Re-enable interrupts */
+#else
msr primask, r3 /* Restore interrupts */
+#endif
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP
diff --git a/nuttx/arch/arm/src/stm32/stm32_irq.c b/nuttx/arch/arm/src/stm32/stm32_irq.c
index 8f2b070fb..bff3eb2b7 100644
--- a/nuttx/arch/arm/src/stm32/stm32_irq.c
+++ b/nuttx/arch/arm/src/stm32/stm32_irq.c
@@ -397,8 +397,7 @@ void up_irqinitialize(void)
/* And finally, enable interrupts */
- setbasepri(NVIC_SYSH_PRIORITY_MAX);
- irqrestore(0);
+ irqenable();
#endif
}
diff --git a/nuttx/arch/arm/src/stm32/stm32_vectors.S b/nuttx/arch/arm/src/stm32/stm32_vectors.S
index ab4dadb77..c9b62d762 100644
--- a/nuttx/arch/arm/src/stm32/stm32_vectors.S
+++ b/nuttx/arch/arm/src/stm32/stm32_vectors.S
@@ -2,7 +2,7 @@
* arch/arm/src/stm32/stm32_vectors.S
* arch/arm/src/chip/stm32_vectors.S
*
- * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -235,7 +235,11 @@ stm32_common:
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ mrs r3, basepri /* R3=Current BASEPRI setting */
+#else
mrs r3, primask /* R3=Current PRIMASK setting */
+#endif
#ifdef CONFIG_ARCH_FPU
/* Skip over the block of memory reserved for floating pointer register save.
@@ -248,8 +252,8 @@ stm32_common:
#endif
/* Save the the remaining registers on the stack after the registers pushed
- * by the exception handling logic. r2=SP and r3=primask, r4-r11,r14=register
- * values.
+ * by the exception handling logic. r2=SP and r3=primask or basepri, r4-r11,
+ * r14=register values.
*/
#ifdef CONFIG_NUTTX_KERNEL
@@ -349,7 +353,7 @@ stm32_common:
* Here:
* r1 = Address on the target thread's stack position at the start of
* the registers saved by hardware
- * r3 = primask
+ * r3 = primask or basepri
* r4-r11 = restored register values
*/
2:
@@ -375,7 +379,12 @@ stm32_common:
/* Restore the interrupt state */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ msr basepri, r3 /* Restore interrupts priority masking*/
+ cpsie i /* Re-enable interrupts */
+#else
msr primask, r3 /* Restore interrupts */
+#endif
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP