summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-04-16 18:00:59 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-04-16 18:00:59 -0600
commit9255670a9d9fab07e941008aa9e9edbf5b460c0b (patch)
treef31c4ec2141db41f31b1de70af701d45b695e3a7
parent82b1ed85155de4cac47551adb2363cc36b8806d0 (diff)
downloadpx4-nuttx-9255670a9d9fab07e941008aa9e9edbf5b460c0b.tar.gz
px4-nuttx-9255670a9d9fab07e941008aa9e9edbf5b460c0b.tar.bz2
px4-nuttx-9255670a9d9fab07e941008aa9e9edbf5b460c0b.zip
Fix major misthink in Cortex-M0 port: The Cortex-M0 has no BASEPRI register. We have to revert to using the nasty PRIMASK register
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/arch/arm/include/armv6-m/irq.h68
-rw-r--r--nuttx/arch/arm/include/armv7-m/irq.h2
-rw-r--r--nuttx/arch/arm/include/kl/chip.h3
-rw-r--r--nuttx/arch/arm/include/nuc1xx/chip.h3
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_assert.c8
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_exception.S10
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_hardfault.c55
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_initialstate.c2
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_schedulesigaction.c8
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_sigdeliver.c4
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_svcall.c16
-rw-r--r--nuttx/arch/arm/src/kl/chip.h2
-rw-r--r--nuttx/arch/arm/src/kl/kl_irq.c22
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip.h2
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_irq.c22
16 files changed, 110 insertions, 122 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 4fc39c64b..8e180e574 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4556,3 +4556,8 @@
contributed by Alan Carvalho de Assis. NOTE: This is still
very much a work inprogress as of this initial commit
(2013-04-16).
+ * arm/arm/src/armv6-m and arch/arm/include/armv6-m: Ooops. Fix
+ a major screw-up: The Cortex-M0 has no BASEPRI register but
+ the current logic was using it to manage interrupts. Switch
+ to using the PRIMASK. This means that hardfaults will (again)
+ occur when SVC instructions are executed (2013-4-16).
diff --git a/nuttx/arch/arm/include/armv6-m/irq.h b/nuttx/arch/arm/include/armv6-m/irq.h
index f4b026c41..4538317e3 100644
--- a/nuttx/arch/arm/include/armv6-m/irq.h
+++ b/nuttx/arch/arm/include/armv6-m/irq.h
@@ -71,7 +71,7 @@
*/
#define REG_R13 (0) /* R13 = SP at time of interrupt */
-#define REG_BASEPRI (1) /* BASEPRI */
+#define REG_PRIMASK (1) /* PRIMASK */
#define REG_R4 (2) /* R4 */
#define REG_R5 (3) /* R5 */
#define REG_R6 (4) /* R6 */
@@ -176,7 +176,7 @@ struct xcptcontext
*/
uint32_t saved_pc;
- uint32_t saved_basepri;
+ uint32_t saved_primask;
uint32_t saved_xpsr;
# ifdef CONFIG_NUTTX_KERNEL
@@ -237,44 +237,12 @@ static inline void setprimask(uint32_t primask)
: "memory");
}
-/* 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)
-{
- uint32_t basepri;
-
- __asm__ __volatile__
- (
- "\tmrs %0, basepri\n"
- : "=r" (basepri)
- :
- : "memory");
-
- return (uint8_t)basepri;
-}
-
-static inline void setbasepri(uint32_t basepri) inline_function;
-static inline void setbasepri(uint32_t basepri)
-{
- __asm__ __volatile__
- (
- "\tmsr basepri, %0\n"
- :
- : "r" (basepri)
- : "memory");
-}
-
/* Disable IRQs */
static inline void irqdisable(void) inline_function;
static inline void irqdisable(void)
{
- setbasepri(NVIC_SYSH_DISABLE_PRIORITY);
+ __asm__ __volatile__ ("\tcpsid i\n");
}
/* Save the current primask state & disable IRQs */
@@ -282,9 +250,21 @@ static inline void irqdisable(void)
static inline irqstate_t irqsave(void) inline_function;
static inline irqstate_t irqsave(void)
{
- uint8_t basepri = getbasepri();
- setbasepri(NVIC_SYSH_DISABLE_PRIORITY);
- return (irqstate_t)basepri;
+ unsigned short primask;
+
+ /* Return the current value of primask register and set
+ * bit 0 of the primask register to disable interrupts
+ */
+
+ __asm__ __volatile__
+ (
+ "\tmrs %0, primask\n"
+ "\tcpsid i\n"
+ : "=r" (primask)
+ :
+ : "memory");
+
+ return primask;
}
/* Enable IRQs */
@@ -292,7 +272,6 @@ static inline irqstate_t irqsave(void)
static inline void irqenable(void) inline_function;
static inline void irqenable(void)
{
- setbasepri(0);
__asm__ __volatile__ ("\tcpsie i\n");
}
@@ -301,7 +280,16 @@ static inline void irqenable(void)
static inline void irqrestore(irqstate_t flags) inline_function;
static inline void irqrestore(irqstate_t flags)
{
- setbasepri((uint32_t)flags);
+ /* If bit 0 of the primask is 0, then we need to restore
+ * interrupts.
+ */
+
+ __asm__ __volatile__
+ (
+ "\tmsr primask, %0\n"
+ :
+ : "r" (flags)
+ : "memory");
}
/* Get/set IPSR */
diff --git a/nuttx/arch/arm/include/armv7-m/irq.h b/nuttx/arch/arm/include/armv7-m/irq.h
index 663a703e3..30ce8993b 100644
--- a/nuttx/arch/arm/include/armv7-m/irq.h
+++ b/nuttx/arch/arm/include/armv7-m/irq.h
@@ -293,7 +293,7 @@ static inline void irqrestore(irqstate_t flags)
setbasepri((uint32_t)flags);
#else
/* If bit 0 of the primask is 0, then we need to restore
- * interupts.
+ * interrupts.
*/
__asm__ __volatile__
diff --git a/nuttx/arch/arm/include/kl/chip.h b/nuttx/arch/arm/include/kl/chip.h
index c1e84245d..56bd0588c 100644
--- a/nuttx/arch/arm/include/kl/chip.h
+++ b/nuttx/arch/arm/include/kl/chip.h
@@ -103,9 +103,6 @@
#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */
#define NVIC_SYSH_PRIORITY_STEP 0x40 /* Steps between supported priority values */
-#define NVIC_SYSH_DISABLE_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP)
-#define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX
-
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/arm/include/nuc1xx/chip.h b/nuttx/arch/arm/include/nuc1xx/chip.h
index bfc018947..6a7e6e087 100644
--- a/nuttx/arch/arm/include/nuc1xx/chip.h
+++ b/nuttx/arch/arm/include/nuc1xx/chip.h
@@ -646,9 +646,6 @@
#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */
#define NVIC_SYSH_PRIORITY_STEP 0x40 /* Five bits of interrupt priority used */
-#define NVIC_SYSH_DISABLE_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP)
-#define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX
-
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/arm/src/armv6-m/up_assert.c b/nuttx/arch/arm/src/armv6-m/up_assert.c
index de5e5f6a1..86347672e 100644
--- a/nuttx/arch/arm/src/armv6-m/up_assert.c
+++ b/nuttx/arch/arm/src/armv6-m/up_assert.c
@@ -148,12 +148,12 @@ static inline void up_registerdump(void)
current_regs[REG_R12], current_regs[REG_R13],
current_regs[REG_R14], current_regs[REG_R15]);
#ifdef CONFIG_NUTTX_KERNEL
- lldbg("xPSR: %08x BASEPRI: %08x EXEC_RETURN: %08x\n",
- current_regs[REG_XPSR], current_regs[REG_BASEPRI],
+ lldbg("xPSR: %08x PRIMASK: %08x EXEC_RETURN: %08x\n",
+ current_regs[REG_XPSR], current_regs[REG_PRIMASK],
current_regs[REG_EXC_RETURN]);
#else
- lldbg("xPSR: %08x BASEPRI: %08x\n",
- current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
+ lldbg("xPSR: %08x PRIMASK: %08x\n",
+ current_regs[REG_XPSR], current_regs[REG_PRIMASK]);
#endif
}
}
diff --git a/nuttx/arch/arm/src/armv6-m/up_exception.S b/nuttx/arch/arm/src/armv6-m/up_exception.S
index d442a28b7..249fb9e54 100644
--- a/nuttx/arch/arm/src/armv6-m/up_exception.S
+++ b/nuttx/arch/arm/src/armv6-m/up_exception.S
@@ -113,15 +113,15 @@ exception_common:
*/
2:
- /* Save SP, BASEPRI, and R4-R7 in the context array */
+ /* Save SP, PRIMASK, and R4-R7 in the context array */
sub r1, #SW_XCPT_SIZE /* R1=Beginning of context array on the stack */
mov r2, #XCPTCONTEXT_SIZE /* R2=Size of the context array */
add r2, r1 /* R2=MSP/PSP before the interrupt was taken */
/* (ignoring the xPSR[9] alignment bit) */
- mrs r3, basepri /* R3=Current BASEPRI setting */
+ mrs r3, primask /* R3=Current PRIMASK setting */
mov r0, r1 /* Copy the context array pointer */
- stmia r0!, {r2-r7} /* Save the SP, BASEPRI, and R4-R7 in the context array */
+ stmia r0!, {r2-r7} /* Save the SP, PRIMASK, and R4-R7 in the context array */
/* Save R8-R11 and the EXEC_RETURN value in the context array */
@@ -215,7 +215,7 @@ exception_common:
mov r11, r5
#endif
- /* Recover SP (R2), BASEPRI (R3), and R4-R7. Determine the value of
+ /* Recover SP (R2), PRIMASK (R3), and R4-R7. Determine the value of
* the stack pointer as it was on entry to the exception handler.
*/
@@ -246,7 +246,7 @@ exception_common:
/* Restore the interrupt state */
- msr basepri, r3 /* Restore interrupts priority masking*/
+ msr primask, r3 /* Restore interrupts priority masking*/
cpsie i /* Re-enable interrupts */
/* Always return with R14 containing the special value that will: (1)
diff --git a/nuttx/arch/arm/src/armv6-m/up_hardfault.c b/nuttx/arch/arm/src/armv6-m/up_hardfault.c
index afbcda9c2..19c63e77b 100644
--- a/nuttx/arch/arm/src/armv6-m/up_hardfault.c
+++ b/nuttx/arch/arm/src/armv6-m/up_hardfault.c
@@ -90,23 +90,68 @@
int up_hardfault(int irq, FAR void *context)
{
-#if defined(CONFIG_DEBUG_HARDFAULT)
+#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 */
+
+#ifndef CONFIG_ARMV7M_USEBASEPRI
+ uint16_t *pc = (uint16_t*)regs[REG_PC] - 1;
+
+ /* Check if the pc lies in known FLASH memory.
+ * REVISIT: What if the PC lies in "unknown" external memory? Best
+ * use the BASEPRI register if you have external memory.
+ */
+
+#ifdef CONFIG_NUTTX_KERNEL
+ /* In the kernel build, SVCalls are expected in either the base, kernel
+ * FLASH region or in the user FLASH region.
+ */
+ if (((uintptr_t)pc >= (uintptr_t)&_stext &&
+ (uintptr_t)pc < (uintptr_t)&_etext) ||
+ ((uintptr_t)pc >= (uintptr_t)USERSPACE->us_textstart &&
+ (uintptr_t)pc < (uintptr_t)USERSPACE->us_textend))
+#else
+ /* SVCalls are expected only from the base, kernel FLASH region */
+
+ if ((uintptr_t)pc >= (uintptr_t)&_stext &&
+ (uintptr_t)pc < (uintptr_t)&_etext)
+#endif
+ {
+ /* Fetch the instruction that caused the Hard fault */
+
+ uint16_t insn = *pc;
+ hfdbg(" PC: %p INSN: %04x\n", pc, insn);
+
+ /* If this was the instruction 'svc 0', then forward processing
+ * to the SVCall handler
+ */
+
+ if (insn == INSN_SVC0)
+ {
+ hfdbg("Forward SVCall\n");
+ return up_svcall(irq, context);
+ }
+ }
+#endif
+
+#if defined(CONFIG_DEBUG_HARDFAULT)
/* Dump some hard fault info */
hfdbg("\nHard Fault:\n");
hfdbg(" IRQ: %d regs: %p\n", irq, regs);
- hfdbg(" BASEPRI: %08x PRIMASK: %08x IPSR: %08x\n",
- getbasepri(), getprimask(), getipsr());
+ hfdbg(" PRIMASK: %08x IPSR: %08x\n",
+ getprimask(), getipsr());
hfdbg(" R0: %08x %08x %08x %08x %08x %08x %08x %08x\n",
regs[REG_R0], regs[REG_R1], regs[REG_R2], regs[REG_R3],
regs[REG_R4], regs[REG_R5], regs[REG_R6], regs[REG_R7]);
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(" xPSR: %08x BASEPRI: %08x (saved)\n",
- current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
+ hfdbg(" xPSR: %08x PRIMASK: %08x (saved)\n",
+ current_regs[REG_XPSR], current_regs[REG_PRIMASK]);
#endif
(void)irqsave();
diff --git a/nuttx/arch/arm/src/armv6-m/up_initialstate.c b/nuttx/arch/arm/src/armv6-m/up_initialstate.c
index 97c048ef4..62c1d2780 100644
--- a/nuttx/arch/arm/src/armv6-m/up_initialstate.c
+++ b/nuttx/arch/arm/src/armv6-m/up_initialstate.c
@@ -139,6 +139,6 @@ void up_initial_state(struct tcb_s *tcb)
/* Enable or disable interrupts, based on user configuration */
#ifdef CONFIG_SUPPRESS_INTERRUPTS
- xcp->regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
+ xcp->regs[REG_PRIMASK] = 1;
#endif /* CONFIG_SUPPRESS_INTERRUPTS */
}
diff --git a/nuttx/arch/arm/src/armv6-m/up_schedulesigaction.c b/nuttx/arch/arm/src/armv6-m/up_schedulesigaction.c
index fa1232704..e41a1a33a 100644
--- a/nuttx/arch/arm/src/armv6-m/up_schedulesigaction.c
+++ b/nuttx/arch/arm/src/armv6-m/up_schedulesigaction.c
@@ -156,7 +156,7 @@ void up_schedule_sigaction(struct tcb_s *tcb, sig_deliver_t sigdeliver)
tcb->xcp.sigdeliver = sigdeliver;
tcb->xcp.saved_pc = current_regs[REG_PC];
- tcb->xcp.saved_basepri = current_regs[REG_BASEPRI];
+ tcb->xcp.saved_primask = current_regs[REG_PRIMASK];
tcb->xcp.saved_xpsr = current_regs[REG_XPSR];
/* Then set up to vector to the trampoline with interrupts
@@ -165,7 +165,7 @@ void up_schedule_sigaction(struct tcb_s *tcb, sig_deliver_t sigdeliver)
*/
current_regs[REG_PC] = (uint32_t)up_sigdeliver;
- current_regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
+ current_regs[REG_PRIMASK] = 1;
current_regs[REG_XPSR] = ARMV6M_XPSR_T;
#ifdef CONFIG_NUTTX_KERNEL
current_regs[REG_XPSR] = EXC_RETURN_PRIVTHR;
@@ -194,7 +194,7 @@ void up_schedule_sigaction(struct tcb_s *tcb, sig_deliver_t sigdeliver)
tcb->xcp.sigdeliver = sigdeliver;
tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC];
- tcb->xcp.saved_basepri = tcb->xcp.regs[REG_BASEPRI];
+ tcb->xcp.saved_primask = tcb->xcp.regs[REG_PRIMASK];
tcb->xcp.saved_xpsr = tcb->xcp.regs[REG_XPSR];
/* Then set up to vector to the trampoline with interrupts
@@ -203,7 +203,7 @@ void up_schedule_sigaction(struct tcb_s *tcb, sig_deliver_t sigdeliver)
*/
tcb->xcp.regs[REG_PC] = (uint32_t)up_sigdeliver;
- tcb->xcp.regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
+ tcb->xcp.regs[REG_PRIMASK] = 1;
tcb->xcp.regs[REG_XPSR] = ARMV6M_XPSR_T;
}
diff --git a/nuttx/arch/arm/src/armv6-m/up_sigdeliver.c b/nuttx/arch/arm/src/armv6-m/up_sigdeliver.c
index 83a064e12..e688fa96f 100644
--- a/nuttx/arch/arm/src/armv6-m/up_sigdeliver.c
+++ b/nuttx/arch/arm/src/armv6-m/up_sigdeliver.c
@@ -107,7 +107,7 @@ void up_sigdeliver(void)
up_copystate(regs, rtcb->xcp.regs);
regs[REG_PC] = rtcb->xcp.saved_pc;
- regs[REG_BASEPRI] = rtcb->xcp.saved_basepri;
+ 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
@@ -120,7 +120,7 @@ void up_sigdeliver(void)
/* Then restore the task interrupt state */
- irqrestore((uint8_t)regs[REG_BASEPRI]);
+ irqrestore((uint8_t)regs[REG_PRIMASK]);
/* Deliver the signal */
diff --git a/nuttx/arch/arm/src/armv6-m/up_svcall.c b/nuttx/arch/arm/src/armv6-m/up_svcall.c
index 84f8712a5..ef9ca5c05 100644
--- a/nuttx/arch/arm/src/armv6-m/up_svcall.c
+++ b/nuttx/arch/arm/src/armv6-m/up_svcall.c
@@ -183,11 +183,11 @@ int up_svcall(int irq, FAR void *context)
regs[REG_R8], regs[REG_R9], regs[REG_R10], regs[REG_R11],
regs[REG_R12], regs[REG_R13], regs[REG_R14], regs[REG_R15]);
# ifdef CONFIG_NUTTX_KERNEL
- svcdbg(" PSR: %08x BASEPRI: %08x EXC_RETURN: %08x\n",
- regs[REG_XPSR], regs[REG_BASEPRI], regs[REG_EXC_RETURN]);
+ svcdbg(" PSR: %08x PRIMASK: %08x EXC_RETURN: %08x\n",
+ regs[REG_XPSR], regs[REG_PRIMASK], regs[REG_EXC_RETURN]);
# else
- svcdbg(" PSR: %08x BASEPRI: %08x\n",
- regs[REG_XPSR], regs[REG_BASEPRI]);
+ svcdbg(" PSR: %08x PRIMASK: %08x\n",
+ regs[REG_XPSR], regs[REG_PRIMASK]);
# endif
}
#endif
@@ -495,12 +495,12 @@ int up_svcall(int irq, FAR void *context)
current_regs[REG_R8], current_regs[REG_R9], 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_NUTTX_KERNEL
- svcdbg(" PSR: %08x BASEPRI: %08x EXC_RETURN: %08x\n",
- current_regs[REG_XPSR], current_regs[REG_BASEPRI],
+ svcdbg(" PSR: %08x PRIMASK: %08x EXC_RETURN: %08x\n",
+ current_regs[REG_XPSR], current_regs[REG_PRIMASK],
current_regs[REG_EXC_RETURN]);
#else
- svcdbg(" PSR: %08x BASEPRI: %08x\n",
- current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
+ svcdbg(" PSR: %08x PRIMASK: %08x\n",
+ current_regs[REG_XPSR], current_regs[REG_PRIMASK]);
#endif
}
# ifdef CONFIG_DEBUG_SVCALL
diff --git a/nuttx/arch/arm/src/kl/chip.h b/nuttx/arch/arm/src/kl/chip.h
index 2f24e1501..0f4df66c9 100644
--- a/nuttx/arch/arm/src/kl/chip.h
+++ b/nuttx/arch/arm/src/kl/chip.h
@@ -46,7 +46,7 @@
#include <arch/kl/chip.h>
-/* Define the number of interrupt vectors that needed to be support for this chip */
+/* Define the number of interrupt vectors that need to be supported for this chip */
#define ARMV6M_PERIPHERAL_INTERRUPTS 32
diff --git a/nuttx/arch/arm/src/kl/kl_irq.c b/nuttx/arch/arm/src/kl/kl_irq.c
index 62c1a41b8..7adc438db 100644
--- a/nuttx/arch/arm/src/kl/kl_irq.c
+++ b/nuttx/arch/arm/src/kl/kl_irq.c
@@ -160,27 +160,6 @@ static int kl_reserved(int irq, FAR void *context)
#endif
/****************************************************************************
- * Name: kl_prioritize_syscall
- *
- * Description:
- * Set the priority of an exception. This function may be needed
- * internally even if support for prioritized interrupts is not enabled.
- *
- ****************************************************************************/
-
-static inline void kl_prioritize_syscall(int priority)
-{
- uint32_t regval;
-
- /* SVCALL is system handler 11 */
-
- regval = getreg32(ARMV6M_SYSCON_SHPR2);
- regval &= ~SYSCON_SHPR2_PRI_11_MASK;
- regval |= (priority << SYSCON_SHPR2_PRI_11_SHIFT);
- putreg32(regval, ARMV6M_SYSCON_SHPR2);
-}
-
-/****************************************************************************
* Name: kl_clrpend
*
* Description:
@@ -256,7 +235,6 @@ void up_irqinitialize(void)
#ifdef CONFIG_ARCH_IRQPRIO
/* up_prioritize_irq(KL_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
#endif
- kl_prioritize_syscall(NVIC_SYSH_SVCALL_PRIORITY);
/* Attach all other processor exceptions (except reset and sys tick) */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip.h b/nuttx/arch/arm/src/nuc1xx/chip.h
index 482c20bb7..d47f4f5e2 100644
--- a/nuttx/arch/arm/src/nuc1xx/chip.h
+++ b/nuttx/arch/arm/src/nuc1xx/chip.h
@@ -46,7 +46,7 @@
#include <arch/nuc1xx/chip.h>
-/* Define the number of interrupt vectors that needed to be support for this chip */
+/* Define the number of interrupt vectors that need to be supported for this chip */
#define ARMV6M_PERIPHERAL_INTERRUPTS 32
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_irq.c b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
index fc3bd4d7e..d80bfe16f 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
@@ -160,27 +160,6 @@ static int nuc_reserved(int irq, FAR void *context)
#endif
/****************************************************************************
- * Name: nuc_prioritize_syscall
- *
- * Description:
- * Set the priority of an exception. This function may be needed
- * internally even if support for prioritized interrupts is not enabled.
- *
- ****************************************************************************/
-
-static inline void nuc_prioritize_syscall(int priority)
-{
- uint32_t regval;
-
- /* SVCALL is system handler 11 */
-
- regval = getreg32(ARMV6M_SYSCON_SHPR2);
- regval &= ~SYSCON_SHPR2_PRI_11_MASK;
- regval |= (priority << SYSCON_SHPR2_PRI_11_SHIFT);
- putreg32(regval, ARMV6M_SYSCON_SHPR2);
-}
-
-/****************************************************************************
* Name: nuc_clrpend
*
* Description:
@@ -256,7 +235,6 @@ void up_irqinitialize(void)
#ifdef CONFIG_ARCH_IRQPRIO
/* up_prioritize_irq(NUC_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
#endif
- nuc_prioritize_syscall(NVIC_SYSH_SVCALL_PRIORITY);
/* Attach all other processor exceptions (except reset and sys tick) */