summaryrefslogtreecommitdiff
path: root/nuttx/arch/x86/src
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/x86/src')
-rw-r--r--nuttx/arch/x86/src/common/up_internal.h2
-rw-r--r--nuttx/arch/x86/src/i486/up_initialstate.c5
-rw-r--r--nuttx/arch/x86/src/i486/up_savestate.c113
-rwxr-xr-xnuttx/arch/x86/src/qemu/Make.defs2
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S34
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_saveusercontext.S21
-rwxr-xr-xnuttx/arch/x86/src/qemu/qemu_vectors.S3
7 files changed, 163 insertions, 17 deletions
diff --git a/nuttx/arch/x86/src/common/up_internal.h b/nuttx/arch/x86/src/common/up_internal.h
index d8e25329e..51f79beb3 100644
--- a/nuttx/arch/x86/src/common/up_internal.h
+++ b/nuttx/arch/x86/src/common/up_internal.h
@@ -80,7 +80,6 @@
* referenced is passed to get the state from the TCB.
*/
-#define up_savestate(regs) up_copystate(regs, current_regs)
#define up_restorestate(regs) (current_regs = regs)
/****************************************************************************
@@ -150,6 +149,7 @@ extern uint32_t _ebss; /* End+1 of .bss */
extern void up_boot(void);
extern void up_copystate(uint32_t *dest, uint32_t *src);
+extern void up_savestate(uint32_t *regs);
extern void up_decodeirq(uint32_t *regs);
extern void up_irqinitialize(void);
#ifdef CONFIG_ARCH_DMA
diff --git a/nuttx/arch/x86/src/i486/up_initialstate.c b/nuttx/arch/x86/src/i486/up_initialstate.c
index 1a13b8991..9ca40feb3 100644
--- a/nuttx/arch/x86/src/i486/up_initialstate.c
+++ b/nuttx/arch/x86/src/i486/up_initialstate.c
@@ -85,7 +85,10 @@ void up_initial_state(_TCB *tcb)
memset(xcp, 0, sizeof(struct xcptcontext));
- /* Save the initial stack pointer */
+ /* Save the initial stack pointer... the value of the stackpointer before
+ * the "interrupt occurs." We don't know the value of REG_ESP yet..
+ * that depends on if a priority change is required or not.
+ */
xcp->regs[REG_SP] = (uint32_t)tcb->adj_stack_ptr;
diff --git a/nuttx/arch/x86/src/i486/up_savestate.c b/nuttx/arch/x86/src/i486/up_savestate.c
new file mode 100644
index 000000000..d5f97fa85
--- /dev/null
+++ b/nuttx/arch/x86/src/i486/up_savestate.c
@@ -0,0 +1,113 @@
+/****************************************************************************
+ * arch/x86/src/i486/up_savestate.c
+ *
+ * Copyright (C) 2011 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 <debug.h>
+
+#include <arch/arch.h>
+#include <arch/irq.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: up_savestate
+ *
+ * Description:
+ * This function saves the interrupt level context information in the
+ * TCB. This would just be a up_copystate but we have to handle one
+ * special case. In the case where the privilige level changes, the
+ * value of sp and ss will not be saved on stack by the interrupt handler.
+ * So, in that case, we will have to fudge those values here.
+ *
+ ****************************************************************************/
+
+void up_savestate(uint32_t *regs)
+{
+ uint8_t cpl;
+ uint8_t rpl;
+
+ /* First, just copy all of the registers */
+
+ up_copystate(regs, current_regs);
+
+ /* The RES_SP and REG_SS values will not be saved by the interrupt handling
+ * logic if there is no change in privilege level. In that case, we will
+ * have to "fudge" those values here. For now, just overwrite the REG_SP
+ * and REG_SS values with what we believe to be correct. Obviously, this
+ * will have to change in the future to support multi-segment operation.
+ *
+ * Check for a change in privilege level.
+ */
+
+ rpl = regs[REG_CS] & 3;
+ cpl = up_getcs() & 3;
+ DEBUGASSERT(rpl >= cpl);
+
+ if (rpl == cpl)
+ {
+ /* No priority change, SP and SS are not present in the stack frame.
+ *
+ * The value saved in the REG_ESP will be the stackpointer value prior to
+ * the execution of the PUSHA. It will point at REG_IRQNO.
+ */
+
+ regs[REG_SP] = current_regs[REG_ESP] + 4*BOTTOM_NOPRIO;
+ regs[REG_SS] = up_getss();
+ }
+ else
+ {
+ DEBUGASSERT(regs[REG_SP] == current_regs[REG_ESP] + 4*BOTTOM_PRIO);
+ }
+}
diff --git a/nuttx/arch/x86/src/qemu/Make.defs b/nuttx/arch/x86/src/qemu/Make.defs
index 3177f3db4..ee239910b 100755
--- a/nuttx/arch/x86/src/qemu/Make.defs
+++ b/nuttx/arch/x86/src/qemu/Make.defs
@@ -45,7 +45,7 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
up_initialize.c up_initialstate.c up_interruptcontext.c up_irq.c \
up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c up_regdump.c \
up_releasepending.c up_releasestack.c up_reprioritizertr.c \
- up_sigdeliver.c up_schedulesigaction.c up_unblocktask.c \
+ up_savestate.c up_sigdeliver.c up_schedulesigaction.c up_unblocktask.c \
up_usestack.c
# Required QEMU files
diff --git a/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S b/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S
index 9a1e1e64e..ded55a147 100644
--- a/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S
+++ b/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S
@@ -106,26 +106,43 @@ up_fullcontextrestore:
cli
- /* We now have everything we need from the old stack. Now get the new
- * stack pointer.
+ /* Get the value of the stack pointer as it was when the pusha was
+ * executed the interrupt handler.
*/
movl (4*REG_SP)(%eax), %esp
/* Create an interrupt stack frame for the final iret.
*
- * SP Before ->
- * SS
- * ESP
- * EFLAGS
- * CS
- * SP After -> EIP
+ *
+ * IRET STACK
+ * PRIO CHANGE No PRIO CHANGE
+ * --------------- -----------------
+ * SP Before ->
+ * SS EFLAGS
+ * ESP CS
+ * EFLAGS -> EIP
+ * CS ...
+ * SP After -> EIP
+ *
+ * So, first check for a priority change.
*/
+ movl (4*REG_CS)(%eax), %edx
+ andl $3, %edx
+ mov %cs, %ebx
+ andl $3, %ebx
+ cmpb %bl, %dl
+ je .Lnopriochange
+
+ /* The priority will change... put SS and ESP on the stack */
+
mov (4*REG_SS)(%eax), %ebx
push %ebx
movl (4*REG_SP)(%eax), %ebx
push %ebx
+
+.Lnopriochange:
movl (4*REG_EFLAGS)(%eax), %ebx
push %ebx
mov (4*REG_CS)(%eax), %ebx
@@ -162,4 +179,3 @@ up_fullcontextrestore:
iret
.size up_fullcontextrestore, . - up_fullcontextrestore
.end
-
diff --git a/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S b/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S
index e9a98b331..427c3bd5d 100644
--- a/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S
+++ b/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S
@@ -126,11 +126,26 @@ up_saveusercontext:
mov %cs, (4*REG_CS)(%eax)
mov %ds, (4*REG_DS)(%eax)
- /* Save the value of SP as will be after we return (don't bother to save
- * REG_ESP).
+ /* Save the value of SP as will be at the time of the IRET that will
+ * appear to be the return from this function.
+ *
+ *
+ * CURRENT STACK IRET STACK
+ * PRIO CHANGE No PRIO CHANGE
+ * --------------- --------------- -----------------
+ * EIP
+ * CS ...
+ * EFLAGS EIP
+ * -> ESP CS
+ * ESP->Return address SS EFLAGS
+ * Argument Argument Argument
+ *
+ * NOTE: We don't yet know the value for REG_ESP! That depends upon
+ * if a priority change occurs or not.
*/
- leal 4(%esp), %ecx
+
+ leal -4(%esp), %ecx
movl %ecx, (4*REG_SP)(%eax)
/* Fetch the PC from the stack and save it in the save block */
diff --git a/nuttx/arch/x86/src/qemu/qemu_vectors.S b/nuttx/arch/x86/src/qemu/qemu_vectors.S
index 87412c21b..d6e17e57b 100755
--- a/nuttx/arch/x86/src/qemu/qemu_vectors.S
+++ b/nuttx/arch/x86/src/qemu/qemu_vectors.S
@@ -266,7 +266,6 @@ irq_common:
popa /* Pops edi,esi,ebp... */
add $8, %esp /* Cleans up the pushed error code and pushed ISR number */
- sti
- iret /* Pops 5 things at once: CS, EIP, EFLAGS, SS, and ESP */
+ iret /* Pops 3-5 things at once: CS, EIP, EFLAGS (and maybe SS and ESP) */
.size irq_common, . - irq_common
.end