summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-25 23:00:19 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-25 23:00:19 +0000
commit2839e79985e189fdbe5f1ab1d7229369aa70072b (patch)
treec069bbe3087d996317e7524e9cf3e7a7950117e4 /nuttx
parent92cf55e8394678b98d46e2bc964c7793f190909f (diff)
downloadpx4-nuttx-2839e79985e189fdbe5f1ab1d7229369aa70072b.tar.gz
px4-nuttx-2839e79985e189fdbe5f1ab1d7229369aa70072b.tar.bz2
px4-nuttx-2839e79985e189fdbe5f1ab1d7229369aa70072b.zip
More Cortex-M0 fixes
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5671 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/include/armv6-m/irq.h13
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_assert.c8
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_exception.S29
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_initialstate.c2
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_sigdeliver.c7
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_svcall.c16
6 files changed, 65 insertions, 10 deletions
diff --git a/nuttx/arch/arm/include/armv6-m/irq.h b/nuttx/arch/arm/include/armv6-m/irq.h
index bad7883fa..68f8c75d4 100644
--- a/nuttx/arch/arm/include/armv6-m/irq.h
+++ b/nuttx/arch/arm/include/armv6-m/irq.h
@@ -74,11 +74,20 @@
#define REG_R9 (7) /* R9 */
#define REG_R10 (8) /* R10 */
#define REG_R11 (9) /* R11 */
-#define REG_EXC_RETURN (10) /* EXC_RETURN */
+
+/* In the kernel build, we may return to either privileged or unprivileged
+ * modes.
+ */
+
+#ifdef CONFIG_NUTTX_KERNEL
+# define REG_EXC_RETURN (10) /* EXC_RETURN */
+# define SW_XCPT_REGS (11)
+#else
+# define SW_XCPT_REGS (10)
+#endif
/* The total number of registers saved by software */
-#define SW_XCPT_REGS (11)
#define SW_XCPT_SIZE (4 * SW_XCPT_REGS)
/* On entry into an IRQ, the hardware automatically saves the following
diff --git a/nuttx/arch/arm/src/armv6-m/up_assert.c b/nuttx/arch/arm/src/armv6-m/up_assert.c
index f2a18c28b..15ba1f53f 100644
--- a/nuttx/arch/arm/src/armv6-m/up_assert.c
+++ b/nuttx/arch/arm/src/armv6-m/up_assert.c
@@ -147,8 +147,14 @@ 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_NUTTX_KERNEL
+ lldbg("xPSR: %08x BASEPRI: %08x EXEC_RETURN: %08x\n",
+ current_regs[REG_XPSR], current_regs[REG_BASEPRI],
+ current_regs[REG_EXC_RETURN]);
+#else
lldbg("xPSR: %08x BASEPRI: %08x\n",
- current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
+ current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
+#endif
}
}
#else
diff --git a/nuttx/arch/arm/src/armv6-m/up_exception.S b/nuttx/arch/arm/src/armv6-m/up_exception.S
index 6a74d4dd6..d442a28b7 100644
--- a/nuttx/arch/arm/src/armv6-m/up_exception.S
+++ b/nuttx/arch/arm/src/armv6-m/up_exception.S
@@ -92,6 +92,7 @@ exception_common:
* the context is on the MSP or PSP.
*/
+#ifdef CONFIG_NUTTX_KERNEL
mov r0, r14 /* Copy high register to low register */
lsl r0, #(31 - EXC_RETURN_PROCESS_BITNO) /* Move to bit 31 */
bmi 1f /* Test bit 31 */
@@ -100,6 +101,9 @@ exception_common:
1:
mrs r1, psp /* R1=The process stack pointer */
+#else
+ mrs r1, msp /* R1=The main stack pointer */
+#endif
/* R1 is the current stack pointer. HW_XCPT_REGS were pushed onto the stack
* when the interrupt was taken so (R1)+HW_XCPT_SIZE is the value of the
@@ -125,8 +129,12 @@ exception_common:
mov r3, r9
mov r4, r10
mov r5, r11
+#ifdef CONFIG_NUTTX_KERNEL
mov r6, r14
stmia r0!, {r2-r6} /* Save the high registers r8-r11 and r14 */
+#else
+ stmia r0!, {r2-r5} /* Save the high registers r8-r11 */
+#endif
/* Get the exception number in R0=IRQ, R1=register save area on stack */
@@ -170,10 +178,10 @@ exception_common:
/* Copy the hardware-saved context to the new stack */
- mov r2, #SW_XCPT_SIZE /* R2=Size of sofware-saved portion of the context array */
+ mov r2, #SW_XCPT_SIZE /* R2=Size of software-saved portion of the context array */
add r1, r0, r2 /* R1=Address of HW save area in reg array */
- ldr r2, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */
- sub r2, #HW_XCPT_SIZE /* R1=Address of HW save area on stack */
+ ldr r2, [r0, #(4*REG_SP)] /* R2=Value of SP before the interrupt */
+ sub r2, #HW_XCPT_SIZE /* R2=Address of HW save area on the return stack */
ldmia r1!, {r4-r7} /* Fetch four registers from the HW save area */
stmia r2!, {r4-r7} /* Copy four registers to the return stack */
ldmia r1!, {r4-r7} /* Fetch four registers from the HW save area */
@@ -192,12 +200,20 @@ exception_common:
mov r2, #(4*REG_R8) /* R2=Offset to R8 storage */
add r0, r1, r2 /* R0=Address of R8 storage */
+#ifdef CONFIG_NUTTX_KERNEL
ldmia r0!, {r2-r6} /* Recover R8-R11 and R14 (5 registers)*/
mov r8, r2 /* Move to position in high registers */
mov r9, r3
mov r10, r4
mov r11, r5
mov r14, r6 /* EXEC_RETURN */
+#else
+ ldmia r0!, {r2-r5} /* Recover R8-R11 and R14 (5 registers)*/
+ mov r8, r2 /* Move to position in high registers */
+ mov r9, r3
+ mov r10, r4
+ mov r11, r5
+#endif
/* Recover SP (R2), BASEPRI (R3), and R4-R7. Determine the value of
* the stack pointer as it was on entry to the exception handler.
@@ -211,6 +227,7 @@ exception_common:
* context is on the MSP or PSP.
*/
+#ifdef CONFIG_NUTTX_KERNEL
mov r0, r14 /* Copy high register to low register */
lsl r0, #(31 - EXC_RETURN_PROCESS_BITNO) /* Move to bit 31 */
bmi 5f /* Test bit 31 */
@@ -221,6 +238,12 @@ exception_common:
msr psp, r1 /* R1=The process stack pointer */
6:
+#else
+ msr msp, r1 /* R1=The main stack pointer */
+ ldr r0, =EXC_RETURN_PRIVTHR /* R0=EXC_RETURN to privileged mode */
+ mov r14, r0 /* R14=EXC_RETURN to privileged mode */
+#endif
+
/* Restore the interrupt state */
msr basepri, r3 /* Restore interrupts priority masking*/
diff --git a/nuttx/arch/arm/src/armv6-m/up_initialstate.c b/nuttx/arch/arm/src/armv6-m/up_initialstate.c
index ccb924ebe..3e7e3a48f 100644
--- a/nuttx/arch/arm/src/armv6-m/up_initialstate.c
+++ b/nuttx/arch/arm/src/armv6-m/up_initialstate.c
@@ -138,7 +138,6 @@ void up_initial_state(struct tcb_s *tcb)
xcp->regs[REG_EXC_RETURN] = EXC_RETURN_UNPRIVTHR;
}
else
-#endif /* CONFIG_NUTTX_KERNEL */
{
/* If the kernel build is not selected -OR- if this is a kernel
* thread, then start it in privileged thread mode.
@@ -146,6 +145,7 @@ void up_initial_state(struct tcb_s *tcb)
xcp->regs[REG_EXC_RETURN] = EXC_RETURN_PRIVTHR;
}
+#endif /* CONFIG_NUTTX_KERNEL */
/* Enable or disable interrupts, based on user configuration */
diff --git a/nuttx/arch/arm/src/armv6-m/up_sigdeliver.c b/nuttx/arch/arm/src/armv6-m/up_sigdeliver.c
index a69d64bf4..ca60b68c5 100644
--- a/nuttx/arch/arm/src/armv6-m/up_sigdeliver.c
+++ b/nuttx/arch/arm/src/armv6-m/up_sigdeliver.c
@@ -81,8 +81,13 @@
void up_sigdeliver(void)
{
+ /* NOTE the "magic" guard space added to regs. This is a little kludge
+ * because up_fullcontextrestore (called below) will do a stack-to-stack
+ * copy an may overwrite the regs[] array contents. Sorry.
+ */
+
struct tcb_s *rtcb = (struct tcb_s*)g_readytorun.head;
- uint32_t regs[XCPTCONTEXT_REGS];
+ uint32_t regs[XCPTCONTEXT_REGS + 4];
sig_deliver_t sigdeliver;
/* Save the errno. This must be preserved throughout the signal handling
diff --git a/nuttx/arch/arm/src/armv6-m/up_svcall.c b/nuttx/arch/arm/src/armv6-m/up_svcall.c
index c1e35d6ab..60dde4bf5 100644
--- a/nuttx/arch/arm/src/armv6-m/up_svcall.c
+++ b/nuttx/arch/arm/src/armv6-m/up_svcall.c
@@ -249,7 +249,13 @@ int up_svcall(int irq, FAR void *context)
svcdbg(" 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]);
- svcdbg(" PSR=%08x\n", regs[REG_XPSR]);
+#ifdef CONFIG_NUTTX_KERNEL
+ svcdbg("xPSR: %08x BASEPRI: %08x EXEC_RETURN: %08x\n",
+ regs[REG_XPSR], regs[REG_BASEPRI], regs[REG_EXC_RETURN]);
+#else
+ svcdbg("xPSR: %08x BASEPRI: %08x\n",
+ regs[REG_XPSR], regs[REG_BASEPRI]);
+#endif
/* Handle the SVCall according to the command in R0 */
@@ -346,7 +352,13 @@ int up_svcall(int irq, FAR void *context)
svcdbg(" R8: %08x %08x %08x %08x %08x %08x %08x %08x\n",
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]);
- svcdbg(" PSR=%08x\n", current_regs[REG_XPSR]);
+#ifdef CONFIG_NUTTX_KERNEL
+ svcdbg("xPSR: %08x BASEPRI: %08x EXEC_RETURN: %08x\n",
+ current_regs[REG_XPSR], current_regs[REG_BASEPRI], current_regs[REG_EXC_RETURN]);
+#else
+ svcdbg("xPSR: %08x BASEPRI: %08x\n",
+ current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
+#endif
}
else
{