From 08f35466fe32b14d64946f45da6777e8d66fc698 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 9 Mar 2011 02:04:45 +0000 Subject: Fix fullcontextrestore bug git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3353 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/x86/src/common/up_assert.c | 282 ++++++++++++++++++++ nuttx/arch/x86/src/common/up_internal.h | 22 +- nuttx/arch/x86/src/i486/up_assert.c | 309 ---------------------- nuttx/arch/x86/src/i486/up_regdump.c | 82 ++++++ nuttx/arch/x86/src/qemu/Make.defs | 4 +- nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S | 16 +- 6 files changed, 375 insertions(+), 340 deletions(-) create mode 100644 nuttx/arch/x86/src/common/up_assert.c delete mode 100644 nuttx/arch/x86/src/i486/up_assert.c create mode 100644 nuttx/arch/x86/src/i486/up_regdump.c (limited to 'nuttx/arch/x86/src') diff --git a/nuttx/arch/x86/src/common/up_assert.c b/nuttx/arch/x86/src/common/up_assert.c new file mode 100644 index 000000000..55ba376b4 --- /dev/null +++ b/nuttx/arch/x86/src/common/up_assert.c @@ -0,0 +1,282 @@ +/**************************************************************************** + * arch/x86/src/common/up_assert.c + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "up_arch.h" +#include "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Pre-processor 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 + +/* The following is just intended to keep some ugliness out of the mainline + * code. We are going to print the task name if: + * + * CONFIG_TASK_NAME_SIZE > 0 && <-- The task has a name + * (defined(CONFIG_DEBUG) || <-- And the debug is enabled (lldbg used) + * defined(CONFIG_ARCH_STACKDUMP) <-- Or lib_lowprintf() is used + */ + +#undef CONFIG_PRINT_TASKNAME +#if CONFIG_TASK_NAME_SIZE > 0 && (defined(CONFIG_DEBUG) || defined(CONFIG_ARCH_STACKDUMP)) +# define CONFIG_PRINT_TASKNAME 1 +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_stackdump + ****************************************************************************/ + +#ifdef CONFIG_ARCH_STACKDUMP +static void up_stackdump(uint32_t sp, uint32_t stack_base) +{ + uint32_t stack ; + + for (stack = sp & ~0x1f; stack < stack_base; stack += 32) + { + uint32_t *ptr = (uint32_t*)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_dumpstate + ****************************************************************************/ + +#ifdef CONFIG_ARCH_STACKDUMP +static void up_dumpstate(void) +{ + _TCB *rtcb = (_TCB*)g_readytorun.head; + uint32_t sp = up_getsp(); + uint32_t ustackbase; + uint32_t ustacksize; +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + uint32_t istackbase; + uint32_t 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_t)rtcb->adj_stack_ptr; + ustacksize = (uint32_t)rtcb->adj_stack_size; + } + + /* Get the limits on the interrupt stack memory */ + +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + istackbase = (uint32_t)&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) */ + + if (current_regs != NULL) + { + up_registerdump(current_regs); + } +} +#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 uint8_t *filename, int lineno) +{ +#ifdef CONFIG_PRINT_TASKNAME + _TCB *rtcb = (_TCB*)g_readytorun.head; +#endif + + up_ledon(LED_ASSERTION); +#ifdef CONFIG_PRINT_TASKNAME + 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 uint8_t *filename, int lineno, int errorcode) +{ +#ifdef CONFIG_PRINT_TASKNAME + _TCB *rtcb = (_TCB*)g_readytorun.head; +#endif + + up_ledon(LED_ASSERTION); + +#ifdef CONFIG_PRINT_TASKNAME + 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/x86/src/common/up_internal.h b/nuttx/arch/x86/src/common/up_internal.h index 35b4e7b5c..d8e25329e 100644 --- a/nuttx/arch/x86/src/common/up_internal.h +++ b/nuttx/arch/x86/src/common/up_internal.h @@ -163,28 +163,8 @@ extern void up_lowputc(char ch); extern void up_puts(const char *str); extern void up_lowputs(const char *str); -extern void up_doirq(int irq, uint32_t *regs); -#ifdef CONFIG_PAGING -extern void up_pginitialize(void); -extern uint32_t *up_va2pte(uintptr_t vaddr); -extern void up_dataabort(uint32_t *regs, uint32_t far, uint32_t fsr); -#else /* CONFIG_PAGING */ -# define up_pginitialize() -extern void up_dataabort(uint32_t *regs); -#endif /* CONFIG_PAGING */ -extern void up_prefetchabort(uint32_t *regs); extern void up_syscall(uint32_t *regs); -extern void up_undefinedinsn(uint32_t *regs); - -/* Defined in up_vectors.S */ - -extern void up_vectorundefinsn(void); -extern void up_vectorswi(void); -extern void up_vectorprefetch(void); -extern void up_vectordata(void); -extern void up_vectoraddrexcptn(void); -extern void up_vectorirq(void); -extern void up_vectorfiq(void); +extern void up_registerdump(uint32_t *regs); /* Defined in up_allocateheap.c */ diff --git a/nuttx/arch/x86/src/i486/up_assert.c b/nuttx/arch/x86/src/i486/up_assert.c deleted file mode 100644 index 69a6fe923..000000000 --- a/nuttx/arch/x86/src/i486/up_assert.c +++ /dev/null @@ -1,309 +0,0 @@ -/**************************************************************************** - * arch/x86/src/i486/up_assert.c - * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include -#include -#include - -#include -#include -#include -#include - -#include "up_arch.h" -#include "os_internal.h" -#include "up_internal.h" - -/**************************************************************************** - * Pre-processor 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 - -/* The following is just intended to keep some ugliness out of the mainline - * code. We are going to print the task name if: - * - * CONFIG_TASK_NAME_SIZE > 0 && <-- The task has a name - * (defined(CONFIG_DEBUG) || <-- And the debug is enabled (lldbg used) - * defined(CONFIG_ARCH_STACKDUMP) <-- Or lib_lowprintf() is used - */ - -#undef CONFIG_PRINT_TASKNAME -#if CONFIG_TASK_NAME_SIZE > 0 && (defined(CONFIG_DEBUG) || defined(CONFIG_ARCH_STACKDUMP)) -# define CONFIG_PRINT_TASKNAME 1 -#endif - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_stackdump - ****************************************************************************/ - -#ifdef CONFIG_ARCH_STACKDUMP -static void up_stackdump(uint32_t sp, uint32_t stack_base) -{ - uint32_t stack ; - - for (stack = sp & ~0x1f; stack < stack_base; stack += 32) - { - uint32_t *ptr = (uint32_t*)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) - { - lldbg(" ds:%08x irq:%08x err:%08x\n", - current_regs[REG_DS], current_regs[REG_IRQNO], - current_regs[REG_ERRCODE]); - lldbg("edi:%08x esi:%08x ebp:%08x esp:%08x\n", - current_regs[REG_EDI], current_regs[REG_ESI], - current_regs[REG_EBP], current_regs[REG_ESP]); - lldbg("ebx:%08x edx:%08x ecx:%08x eax:%08x\n", - current_regs[REG_EBX], current_regs[REG_EDX], - current_regs[REG_ECX], current_regs[REG_EAX]); - lldbg("eip:%08x cs:%08x flg:%08x sp:%08x ss:%08x\n", - current_regs[REG_EIP], current_regs[REG_CS], - current_regs[REG_EFLAGS], current_regs[REG_SP], - current_regs[REG_SS]); - } -} -#else -# define up_registerdump() -#endif - -/**************************************************************************** - * Name: up_dumpstate - ****************************************************************************/ - -#ifdef CONFIG_ARCH_STACKDUMP -static void up_dumpstate(void) -{ - _TCB *rtcb = (_TCB*)g_readytorun.head; - uint32_t sp = up_getsp(); - uint32_t ustackbase; - uint32_t ustacksize; -#if CONFIG_ARCH_INTERRUPTSTACK > 3 - uint32_t istackbase; - uint32_t 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_t)rtcb->adj_stack_ptr; - ustacksize = (uint32_t)rtcb->adj_stack_size; - } - - /* Get the limits on the interrupt stack memory */ - -#if CONFIG_ARCH_INTERRUPTSTACK > 3 - istackbase = (uint32_t)&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 uint8_t *filename, int lineno) -{ -#ifdef CONFIG_PRINT_TASKNAME - _TCB *rtcb = (_TCB*)g_readytorun.head; -#endif - - up_ledon(LED_ASSERTION); -#ifdef CONFIG_PRINT_TASKNAME - 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 uint8_t *filename, int lineno, int errorcode) -{ -#ifdef CONFIG_PRINT_TASKNAME - _TCB *rtcb = (_TCB*)g_readytorun.head; -#endif - - up_ledon(LED_ASSERTION); - -#ifdef CONFIG_PRINT_TASKNAME - 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/x86/src/i486/up_regdump.c b/nuttx/arch/x86/src/i486/up_regdump.c new file mode 100644 index 000000000..68d31cdce --- /dev/null +++ b/nuttx/arch/x86/src/i486/up_regdump.c @@ -0,0 +1,82 @@ +/**************************************************************************** + * arch/x86/src/i486/up_regdump.c + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include "up_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Output debug info -- even if debug is not selected. */ + +#undef lldbg +#define lldbg lib_lowprintf + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/**************************************************************************** + * Name: up_registerdump + ****************************************************************************/ + +void up_registerdump(uint32_t *regs) +{ + lldbg(" ds:%08x irq:%08x err:%08x\n", + regs[REG_DS], regs[REG_IRQNO], regs[REG_ERRCODE]); + lldbg("edi:%08x esi:%08x ebp:%08x esp:%08x\n", + regs[REG_EDI], regs[REG_ESI], regs[REG_EBP], regs[REG_ESP]); + lldbg("ebx:%08x edx:%08x ecx:%08x eax:%08x\n", + regs[REG_EBX], regs[REG_EDX], regs[REG_ECX], regs[REG_EAX]); + lldbg("eip:%08x cs:%08x flg:%08x sp:%08x ss:%08x\n", + regs[REG_EIP], regs[REG_CS], regs[REG_EFLAGS], regs[REG_SP], + regs[REG_SS]); +} diff --git a/nuttx/arch/x86/src/qemu/Make.defs b/nuttx/arch/x86/src/qemu/Make.defs index 6bcf102f9..4c3a83380 100755 --- a/nuttx/arch/x86/src/qemu/Make.defs +++ b/nuttx/arch/x86/src/qemu/Make.defs @@ -41,9 +41,9 @@ HEAD_ASRC = qemu_head.S CMN_ASRCS = i486_utils.S CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ - up_createstack.c up_mdelay.c up_udelay.c up_exit.c \ + up_createstack.c up_mdelay.c up_udelay.c up_exit.c\ up_initialize.c up_initialstate.c up_interruptcontext.c \ - up_modifyreg8.c up_modifyreg16.c up_modifyreg32.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_usestack.c diff --git a/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S b/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S index 6f63f2382..0396753f7 100644 --- a/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S +++ b/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S @@ -120,17 +120,17 @@ up_fullcontextrestore: /* Now restore the remaining registers */ - movl (4*REG_EDI)(%ebx), %edi - movl (4*REG_ESI)(%ebx), %esi - movl (4*REG_EBP)(%ebx), %ebp - movl (4*REG_EDX)(%ebx), %edx - movl (4*REG_ECX)(%ebx), %ecx + movl (4*REG_EDI)(%eax), %edi + movl (4*REG_ESI)(%eax), %esi + movl (4*REG_EBP)(%eax), %ebp + movl (4*REG_EDX)(%eax), %edx + movl (4*REG_ECX)(%eax), %ecx /* Restore the segment registers */ - mov (4*REG_DS)(%ebx), %ds - mov (4*REG_CS)(%ebx), %cs - mov (4*REG_SS)(%ebx), %ss + mov (4*REG_DS)(%eax), %ds + mov (4*REG_CS)(%eax), %cs + mov (4*REG_SS)(%eax), %ss /* Restore the correct value of EAX, EBX, and the EFLAGS then return */ -- cgit v1.2.3