From 225413bf763536b5de137eeb6d702b173e67a9fc Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 6 Mar 2011 00:08:40 +0000 Subject: QEMU i486 port is code complete git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3342 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/x86/include/i486/irq.h | 12 ++- nuttx/arch/x86/src/i486/i486_utils.S | 4 +- nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S | 56 ++++++++----- nuttx/arch/x86/src/qemu/qemu_head.S | 2 +- nuttx/arch/x86/src/qemu/qemu_saveusercontext.S | 41 ++++++++-- nuttx/arch/x86/src/qemu/qemu_vectors.S | 96 +++++++++++++++++------ 6 files changed, 158 insertions(+), 53 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/x86/include/i486/irq.h b/nuttx/arch/x86/include/i486/irq.h index c82c92859..cb78e4d81 100755 --- a/nuttx/arch/x86/include/i486/irq.h +++ b/nuttx/arch/x86/include/i486/irq.h @@ -62,19 +62,25 @@ #define REG_EDI (1) /* Saved by pusha */ #define REG_ESI (2) /* " " "" " " */ #define REG_EBP (3) /* " " "" " " */ -#define REG_ESP (4) /* " " "" " " */ +#define REG_ESP (4) /* " " "" " " (NOTE 1)*/ #define REG_EBX (5) /* " " "" " " */ #define REG_EDX (6) /* " " "" " " */ #define REG_ECX (7) /* " " "" " " */ #define REG_EAX (8) /* " " "" " " */ -#define REG_IRQNO (9) /* Interrupt number */ -#define REG_ERRCODE (10) /* Error code */ +#define REG_IRQNO (9) /* Interrupt number (NOTE 2) */ +#define REG_ERRCODE (10) /* Error code (NOTE 2) */ #define REG_EIP (11) /* Pushed by process on interrupt processing */ #define REG_CS (12) /* " " "" " " "" " " " " */ #define REG_EFLAGS (13) /* " " "" " " "" " " " " */ #define REG_SP (14) /* " " "" " " "" " " " " */ #define REG_SS (15) /* " " "" " " "" " " " " */ +/* NOTE 1: Two versions of the ESP are saved: One from the interrupt + * processing and one from pusha. Only the interrupt ESP (REG_SP) is used. + * NOTE 2: This is not really state data. Rather, this is just a convenient + * way to pass parameters from the interrupt handler to C cod. + */ + #define XCPTCONTEXT_REGS (16) #define XCPTCONTEXT_SIZE (4 * XCPTCONTEXT_REGS) diff --git a/nuttx/arch/x86/src/i486/i486_utils.S b/nuttx/arch/x86/src/i486/i486_utils.S index 12a420d14..eae168fbd 100644 --- a/nuttx/arch/x86/src/i486/i486_utils.S +++ b/nuttx/arch/x86/src/i486/i486_utils.S @@ -100,7 +100,7 @@ SYMBOL(gdt_flush): SYMBOL(idt_flush): mov eax, [esp+4] /* Get the pointer to the IDT, passed as a parameter */ - lidt [eax] /* Load the IDT pointer */ + lidt [eax] /* Load the IDT pointer */ ret #else /* !CONFIG_X86_NASM (GAS) */ @@ -141,7 +141,7 @@ SYMBOL(gdt_flush): mov %fs, %ax mov %gs, %ax mov %ss, %ax - ljmp *.Lgflush /* 0x08 is the offset to our code segment: Far jump! */ + jmp $0x08, $.Lgflush /* 0x08 is the offset to our code segment: Far jump! */ .Lgflush: ret #ifndef __CYGWIN__ diff --git a/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S b/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S index 8083c3b8f..b4704f23a 100644 --- a/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S +++ b/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S @@ -97,35 +97,55 @@ .type SYMBOL(up_fullcontextrestore), @function #endif SYMBOL(up_fullcontextrestore): - movl 4(%esp), %ecx /* Register save area in %ecx. */ + /* Fetch the pointer to the register save array in EAX. */ - /* Disable interrupts now (the will be conditionally re-enabled below) */ + movl 4(%esp), %eax + + /* Disable interrupts now (the correct EFLAGS will be restored before we + * return + */ cli - /* Save the return address. */ + /* We now have everything we need from the old stack. Now get the new + * stack pointer. + */ + + movl (REG_SP)(%eax), %esp + + /* Save the return address, EFLAGS, and the values as well the + * values of EBX and EAC on the new stack. + */ - movl (REG_EIP)(%ecx), %edx + movl (REG_EIP)(%eax), %ebx + push %ebx + movl (REG_EFLAGS)(%eax), %ebx + push %ebx + movl (REG_EAX)(%eax), %ebx + push %ebx + movl (REG_EBX)(%eax), %ebx + push %ebx - /* Restore registers. */ + /* Now restore the remaining registers */ - movl (REG_EBX)(%ecx), %ebx - movl (REG_ESI)(%ecx), %esi - movl (REG_EDI)(%ecx), %edi - movl (REG_EBP)(%ecx), %ebp - movl (REG_SP)(%ecx), %esp + movl (REG_EDI)(%ebx), %edi + movl (REG_ESI)(%ebx), %esi + movl (REG_EBP)(%ebx), %ebp + movl (REG_EDX)(%ebx), %edx + movl (REG_ECX)(%ebx), %ecx - /* Conditionally restore interrupts */ + /* Restore the segment registers */ - testl $512, (REG_EFLAGS)(%ecx) - je .Ldisabled - sti -.Ldisabled: + mov (REG_DS)(%ebx), %ds + mov (REG_CS)(%ebx), %cs + mov (REG_SS)(%ebx), %ss - /* Jump to saved PC with non-zero return value in %eax. */ + /* Restore the correct value of EAX, EBX, and the EFLAGS then return */ - movl $1, %eax - jmp *%edx + popl %ebx + popl %eax + popf + ret #ifndef __CYGWIN__ .size SYMBOL(up_fullcontextrestore), . - SYMBOL(up_fullcontextrestore) #endif diff --git a/nuttx/arch/x86/src/qemu/qemu_head.S b/nuttx/arch/x86/src/qemu/qemu_head.S index bef18cd60..f1c39b651 100755 --- a/nuttx/arch/x86/src/qemu/qemu_head.S +++ b/nuttx/arch/x86/src/qemu/qemu_head.S @@ -225,7 +225,7 @@ hang: .type SYMBOL(g_heapbase), @object #endif SYMBOL(g_heapbase): - .word _ebss + .long _ebss #ifndef __CYGWIN__ .size SYMBOL(g_heapbase), . - SYMBOL(g_heapbase) #endif diff --git a/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S b/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S index dc352c181..841023b40 100644 --- a/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S +++ b/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S @@ -85,6 +85,20 @@ * Full C prototype: * int up_saveusercontext(uint32_t *regs); * + * Description: + * Save the "user" context. It is not necessary to save all of the + * registers because it is acceptable for certain registers to be + * modified upon return from a subroutine call. On a context switch + * back to user mode, it will appear as a return from this function. + * + * According to the Intel ABI, the EAX, EDX, and ECX are to be free for + * use within a procedure or function, and need not be preserved. These + * are the so-called caller-saved registers are EAX, ECX, EDX. + * + * On entry, + * sp points to the return address + * sp+4 points to register save array + * **************************************************************************/ #ifdef CONFIG_X86_NASM @@ -97,21 +111,34 @@ .type SYMBOL(up_saveusercontext), @function #endif SYMBOL(up_saveusercontext): - - /* %ebx, %esi, %edi, and %ebp must be preserved. - * save %ebx, $esi, and %edi now... */ + /* Fetch the pointer to the register save array. %eax is a available + * because it must be modified later to provide the return value. + */ movl 4(%esp), %eax + + /* %ebx, %esi, %edi, and %ebp must be preserved. We can freely used %eax + * because it will be the return value from this function. + */ + movl %ebx, (REG_EBX)(%eax) movl %esi, (REG_ESI)(%eax) movl %edi, (REG_EDI)(%eax) - /* Save the value of SP as will be after we return */ + /* Save the segment registers */ + + mov %ss, (REG_SS)(%eax) + mov %cs, (REG_CS)(%eax) + mov %ds, (REG_DS)(%eax) + + /* Save the value of SP as will be after we return (don't bother to save + * REG_ESP). + */ leal 4(%esp), %ecx movl %ecx, (REG_SP)(%eax) - /* Save the return PC */ + /* Fetch the PC from the stack and save it in the save block */ movl 0(%esp), %ecx movl %ecx, (REG_EIP)(%eax) @@ -120,13 +147,13 @@ SYMBOL(up_saveusercontext): movl %ebp, (REG_EBP)(%eax) - /* Save the interrupt state */ + /* Get and save the interrupt state */ pushf pop %ecx movl %ecx, (REG_EFLAGS)(%eax) - /* And return 0 */ + /* And return 0. 'ret' will remove the EIP from the top of the stack. */ xorl %eax, %eax ret diff --git a/nuttx/arch/x86/src/qemu/qemu_vectors.S b/nuttx/arch/x86/src/qemu/qemu_vectors.S index 2d66ca01c..810904538 100755 --- a/nuttx/arch/x86/src/qemu/qemu_vectors.S +++ b/nuttx/arch/x86/src/qemu/qemu_vectors.S @@ -200,18 +200,14 @@ isr_common: mov fs, ax mov gs, ax - call SYMBOL(isr_handler) - - pop ebx /* Reload the original data segment descriptor */ - mov ds, bx - mov es, bx - mov fs, bx - mov gs, bx + /* The current value of the SP points to the beginning of the state save + * structure. Save that on the stack as the input parameter to isr_handler. + */ - popa /* Pops edi,esi,ebp... */ - add esp, 8 /* Cleans up the pushed error code and pushed ISR number */ - sti - iret /* Pops 5 things at once: CS, EIP, EFLAGS, SS, and ESP */ + mov esp, eax + push eax + call SYMBOL(isr_handler) + jmp .Lreturn /**************************************************************************** * Name: irq_common @@ -236,8 +232,38 @@ irq_common: mov fs, ax mov gs, ax + /* The current value of the SP points to the beginning of the state save + * structure. Save that on the stack as the input parameter to irq_handler. + */ + + mov esp, eax + push eax call SYMBOL(irq_handler) + /* The common return point for both isr_handler and irq_handler */ + +.Lreturn: + add 4, esp + + /* EAX may possibly hold a pointer to a different regiser save area on + * return. Are we switching to a new context? + */ + + cmp eax, esp + je .Lnoswitch + + /* A context swith will be performed. EAX holds the address of the new + * register save structure. + * + * 'Jump' to up_fullcontextrestore(). We perform a call here, but that function + * never returns. The address of the new register save block is the argument + * to the up_fullcontextrestore(). + */ + + push eax + jmp SYMBOL(up_fullcontext) + +.Lnoswitch: pop ebx /* Reload the original data segment descriptor */ mov ds, bx mov es, bx @@ -395,21 +421,17 @@ isr_common: mov %fs, %ax mov %gs, %ax - call SYMBOL(isr_handler) - - pop %ebx /* Reload the original data segment descriptor */ - mov %ds, %bx - mov %es, %bx - mov %fs, %bx - mov %gs, %bx + /* The current value of the SP points to the beginning of the state save + * structure. Save that on the stack as the input parameter to isr_handler. + */ - popa /* Pops edi,esi,ebp... */ - add %esp, 8 /* Cleans up the pushed error code and pushed ISR number */ - sti + mov %esp, %eax + push %eax + call SYMBOL(isr_handler) + jmp .Lreturn #ifndef __CYGWIN__ .size isr_common, . - isr_common #endif - iret /* Pops 5 things at once: CS, EIP, EFLAGS, SS, and ESP */ /**************************************************************************** * Name: irq_common @@ -437,8 +459,38 @@ irq_common: mov %fs, %ax mov %gs, %ax + /* The current value of the SP points to the beginning of the state save + * structure. Save that on the stack as the input parameter to irq_handler. + */ + + mov %esp, %eax + push %eax call SYMBOL(irq_handler) + /* The common return point for both isr_handler and irq_handler */ + +.Lreturn: + add $4, %esp + + /* EAX may possibly hold a pointer to a different regiser save area on + * return. Are we switching to a new context? + */ + + cmp %eax, %esp + je .Lnoswitch + + /* A context swith will be performed. EAX holds the address of the new + * register save structure. + * + * Jump to up_fullcontextrestore(). We perform a call here, but that function + * never returns. The address of the new register save block is the argument + * to the up_fullcontextrestore(). + */ + + push %eax + call SYMBOL(up_fullcontextrestore) + +.Lnoswitch: pop %ebx /* Reload the original data segment descriptor */ mov %ds, %bx mov %es, %bx -- cgit v1.2.3