aboutsummaryrefslogtreecommitdiff
path: root/nuttx/arch/x86
diff options
context:
space:
mode:
authorpatacongo <patacongo@7fd9a85b-ad96-42d3-883c-3090e2eb8679>2011-12-19 19:24:09 +0000
committerpatacongo <patacongo@7fd9a85b-ad96-42d3-883c-3090e2eb8679>2011-12-19 19:24:09 +0000
commitadd995c32e86f9de8fa8fc05172435332c25a895 (patch)
tree0191fde92a5c4dcd55a24b2aa760fa4c88713242 /nuttx/arch/x86
downloadpx4-firmware-add995c32e86f9de8fa8fc05172435332c25a895.tar.gz
px4-firmware-add995c32e86f9de8fa8fc05172435332c25a895.tar.bz2
px4-firmware-add995c32e86f9de8fa8fc05172435332c25a895.zip
Completes coding of the PWM module
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4200 7fd9a85b-ad96-42d3-883c-3090e2eb8679
Diffstat (limited to 'nuttx/arch/x86')
-rwxr-xr-xnuttx/arch/x86/include/README.txt31
-rwxr-xr-xnuttx/arch/x86/include/arch.h91
-rwxr-xr-xnuttx/arch/x86/include/i486/arch.h451
-rw-r--r--nuttx/arch/x86/include/i486/io.h148
-rwxr-xr-xnuttx/arch/x86/include/i486/irq.h287
-rwxr-xr-xnuttx/arch/x86/include/i486/limits.h81
-rw-r--r--nuttx/arch/x86/include/i486/syscall.h138
-rwxr-xr-xnuttx/arch/x86/include/i486/types.h97
-rwxr-xr-xnuttx/arch/x86/include/io.h86
-rwxr-xr-xnuttx/arch/x86/include/irq.h98
-rwxr-xr-xnuttx/arch/x86/include/limits.h53
-rwxr-xr-xnuttx/arch/x86/include/qemu/arch.h80
-rwxr-xr-xnuttx/arch/x86/include/qemu/irq.h80
-rw-r--r--nuttx/arch/x86/include/syscall.h88
-rwxr-xr-xnuttx/arch/x86/include/types.h65
-rw-r--r--nuttx/arch/x86/src/Makefile163
-rwxr-xr-xnuttx/arch/x86/src/README.txt31
-rw-r--r--nuttx/arch/x86/src/common/up_allocateheap.c82
-rw-r--r--nuttx/arch/x86/src/common/up_arch.h90
-rw-r--r--nuttx/arch/x86/src/common/up_assert.c282
-rwxr-xr-xnuttx/arch/x86/src/common/up_blocktask.c166
-rw-r--r--nuttx/arch/x86/src/common/up_copystate.c82
-rw-r--r--nuttx/arch/x86/src/common/up_exit.c174
-rw-r--r--nuttx/arch/x86/src/common/up_initialize.c168
-rw-r--r--nuttx/arch/x86/src/common/up_internal.h237
-rw-r--r--nuttx/arch/x86/src/common/up_interruptcontext.c72
-rw-r--r--nuttx/arch/x86/src/common/up_lowputs.c74
-rw-r--r--nuttx/arch/x86/src/common/up_mdelay.c90
-rw-r--r--nuttx/arch/x86/src/common/up_modifyreg16.c85
-rw-r--r--nuttx/arch/x86/src/common/up_modifyreg32.c85
-rw-r--r--nuttx/arch/x86/src/common/up_modifyreg8.c85
-rw-r--r--nuttx/arch/x86/src/common/up_puts.c75
-rwxr-xr-xnuttx/arch/x86/src/common/up_releasepending.c132
-rwxr-xr-xnuttx/arch/x86/src/common/up_reprioritizertr.c187
-rw-r--r--nuttx/arch/x86/src/common/up_udelay.c129
-rwxr-xr-xnuttx/arch/x86/src/common/up_unblocktask.c158
-rw-r--r--nuttx/arch/x86/src/i486/i486_utils.S96
-rw-r--r--nuttx/arch/x86/src/i486/up_createstack.c135
-rw-r--r--nuttx/arch/x86/src/i486/up_initialstate.c126
-rwxr-xr-xnuttx/arch/x86/src/i486/up_irq.c376
-rw-r--r--nuttx/arch/x86/src/i486/up_regdump.c82
-rw-r--r--nuttx/arch/x86/src/i486/up_releasestack.c79
-rw-r--r--nuttx/arch/x86/src/i486/up_savestate.c113
-rw-r--r--nuttx/arch/x86/src/i486/up_schedulesigaction.c198
-rw-r--r--nuttx/arch/x86/src/i486/up_sigdeliver.c139
-rwxr-xr-xnuttx/arch/x86/src/i486/up_syscall6.S97
-rw-r--r--nuttx/arch/x86/src/i486/up_usestack.c119
-rwxr-xr-xnuttx/arch/x86/src/qemu/Make.defs57
-rwxr-xr-xnuttx/arch/x86/src/qemu/chip.h74
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S181
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_handlers.c204
-rwxr-xr-xnuttx/arch/x86/src/qemu/qemu_head.S161
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_idle.c88
-rwxr-xr-xnuttx/arch/x86/src/qemu/qemu_internal.h448
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_lowputc.c104
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_lowsetup.c140
-rwxr-xr-xnuttx/arch/x86/src/qemu/qemu_memorymap.h67
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_saveusercontext.S182
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_serial.c116
-rwxr-xr-xnuttx/arch/x86/src/qemu/qemu_timerisr.c148
-rwxr-xr-xnuttx/arch/x86/src/qemu/qemu_vectors.S271
61 files changed, 8322 insertions, 0 deletions
diff --git a/nuttx/arch/x86/include/README.txt b/nuttx/arch/x86/include/README.txt
new file mode 100755
index 000000000..1f6cdeb91
--- /dev/null
+++ b/nuttx/arch/x86/include/README.txt
@@ -0,0 +1,31 @@
+arch/x86/include/README.txt
+^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+This directory holds x86-specific header files. The top-level header files in
+arch/x86/include simply include corresponding header files from lower lower-
+level chip-specific and architecture-specific directories.
+
+Architecture-Specific Directories
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+Architecture-specific directories hold common header files for specific x86
+architectures. Separating these header file makes it easy to manage such
+things as differences in sizeof(long) on 32- and 64-bit x86 architectures.
+
+i486
+ This directory holds definitions appropriate for any instantiation of the
+ 32-bit i486 architecture.
+
+Chip-Specific directories
+^^^^^^^^^^^^^^^^^^^^^^^^^
+
+The same x86 architecture may be realized in different chip implementations.
+For SoC chips, in particular, on-chip devices and differing interrupt
+structures may require special, chip-specific definitions in these chip-
+specific directories.
+
+qemu
+ This is the implementation of NuttX on the QEMU x86 simulation.
+
+
+
diff --git a/nuttx/arch/x86/include/arch.h b/nuttx/arch/x86/include/arch.h
new file mode 100755
index 000000000..966bfbc56
--- /dev/null
+++ b/nuttx/arch/x86/include/arch.h
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * arch/x86/include/arch.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through arch/arch.h
+ */
+
+#ifndef __ARCH_X86_INCLUDE_ARCH_H
+#define __ARCH_X86_INCLUDE_ARCH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/* Include chip-specific definitions */
+
+# include <arch/chip/arch.h>
+
+/* Include architecture-specific definitions */
+
+#ifdef CONFIG_ARCH_I486
+# include <arch/i486/arch.h>
+#endif
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ARCH_X86_INCLUDE_ARCH_H */
diff --git a/nuttx/arch/x86/include/i486/arch.h b/nuttx/arch/x86/include/i486/arch.h
new file mode 100755
index 000000000..077c76626
--- /dev/null
+++ b/nuttx/arch/x86/include/i486/arch.h
@@ -0,0 +1,451 @@
+/****************************************************************************
+ * arch/x86/include/i486/arch.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through nuttx/arch.h
+ */
+
+#ifndef __ARCH_X86_INCLUDE_I486_ARCH_H
+#define __ARCH_X86_INCLUDE_I486_ARCH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* FLAGS bits */
+
+#define X86_FLAGS_CF (1 << 0) /* Bit 0: Carry Flag */
+ /* Bit 1: Reserved */
+#define X86_FLAGS_PF (1 << 2) /* Bit 2: Parity Flag */
+ /* Bit 3: Reserved */
+#define X86_FLAGS_AF (1 << 4) /* Bit 4: Auxillary carry Flag */
+ /* Bit 5: Reserved */
+#define X86_FLAGS_ZF (1 << 6) /* Bit 6: Zero Flag */
+#define X86_FLAGS_SF (1 << 7) /* Bit 7: Sign Flag */
+#define X86_FLAGS_TF (1 << 8) /* Bit 8: Trap Flag */
+#define X86_FLAGS_IF (1 << 9) /* Bit 9: Interrupt Flag */
+#define X86_FLAGS_DF (1 << 10) /* Bit 10: Direction Flag */
+#define X86_FLAGS_OF (1 << 11) /* Bit 11: Overflow Flag */
+#define X86_FLAGS_IOPL_SHIFT (12) /* Bits 12-13: IOPL mask (286+ only)*/
+#define X86_FLAGS_IOPL_MASK (3 << X86_FLAGS_IOPL_SHIFT)
+#define X86_FLAGS_NT (1 << 14) /* Bit 14: Nested Task */
+ /* Bit 15: Reserved */
+
+/* EFLAGS bits (Extend the basic FLAGS bit definitions) */
+
+#define X86_EFLAGS_RF (1 << 16) /* Bit 16: Resume Flag (386+ only) */
+#define X86_EFLAGS_VM (1 << 17) /* Bit 17: Virtual Mode (386+ only) */
+#define X86_EFLAGS_AC (1 << 18) /* Bit 18: Alignment Check (486SX+ only) */
+#define X86_EFLAGS_VIF (1 << 19) /* Bit 19: Virtual Interrupt Flag (Pentium+) */
+#define X86_EFLAGS_VIP (1 << 20) /* Bit 20: Virtual Interrupt Pending (Pentium+) */
+#define X86_EFLAGS_ID (1 << 21) /* Bit 21: CPUID detection flag (Pentium+) */
+
+/* Programmable Interrupt Controller (PIC) */
+
+/* Operational Control Words
+ *
+ * The first instruction the Operation Control Word 1 (OCW1) to set which
+ * IRQ's to mask and which IRQ's not to.
+ */
+
+#define PIC1_OCW1 0x20
+#define PIC2_OCW1 0xa0
+
+# define PIC1_OCW1_IRQ0 (1 << 0) /* IRQ0 System Timer */
+# define PIC1_OCW1_IRQ1 (1 << 1) /* IRQ1 Keyboard */
+# define PIC1_OCW1_IRQ2 (1 << 2) /* IRQ2 PIC2 */
+# define PIC1_OCW1_IRQ3 (1 << 3) /* IRQ3 Serial Port */
+# define PIC1_OCW1_IRQ4 (1 << 4) /* IRQ4 Serial Port */
+# define PIC1_OCW1_IRQ5 (1 << 5) /* IRQ5 Reserved/Sound Card */
+# define PIC1_OCW1_IRQ6 (1 << 6) /* IRQ6 Floppy Disk Controller */
+# define PIC1_OCW1_IRQ7 (1 << 7) /* IRQ7 Parallel Port */
+# define PIC1_OCW1_ALL
+
+# define PIC2_OCW1_IRQ8 (1 << 0) /* IRQ8 Real Time Clock */
+# define PIC2_OCW1_IRQ9 (1 << 1) /* IRQ9 Redirected IRQ2 */
+# define PIC2_OCW1_IRQ10 (1 << 2) /* IRQ10 Reserved */
+# define PIC2_OCW1_IRQ11 (1 << 3) /* IRQ11 Reserved */
+# define PIC2_OCW1_IRQ12 (1 << 4) /* IRQ12 PS/2 Mouse */
+# define PIC2_OCW1_IRQ13 (1 << 5) /* IRQ13 Maths Co-Processor */
+# define PIC2_OCW1_IRQ14 (1 << 6) /* IRQ14 Hard Disk Drive */
+# define PIC2_OCW1_IRQ15 (1 << 7) /* IRQ15 Reserved */
+# define PIC2_OCW1_ALL
+
+/* Operation Control Word 2 selects how the End of Interrupt (EOI) procedure
+ * works. The only thing of interest to us in this register is the non-
+ * specific EOI command, which we must send at the end of our ISR's.
+ */
+
+#define PIC1_OCW2 0x20
+#define PIC2_OCW2 0xa0
+
+# define PIC_OCW2_ACT_SHIFT (0)
+# define PIC_OCW2_ACT_MASK (7 << PIC_OCW2_ACT_SHIFT)
+# define PIC1_OCW2_ACT_IRQ0 (0 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 0 */
+# define PIC1_OCW2_ACT_IRQ1 (1 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 1 */
+# define PIC1_OCW2_ACT_IRQ2 (2 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 2 */
+# define PIC1_OCW2_ACT_IRQ3 (3 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 3 */
+# define PIC1_OCW2_ACT_IRQ4 (4 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 4 */
+# define PIC1_OCW2_ACT_IRQ5 (5 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 5 */
+# define PIC1_OCW2_ACT_IRQ6 (6 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 6 */
+# define PIC1_OCW2_ACT_IRQ7 (7 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 7 */
+
+# define PIC2_OCW2_ACT_IRQ8 (0 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 8 */
+# define PIC2_OCW2_ACT_IRQ9 (1 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 9 */
+# define PIC2_OCW2_ACT_IRQ10 (2 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 10 */
+# define PIC2_OCW2_ACT_IRQ11 (3 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 11 */
+# define PIC2_OCW2_ACT_IRQ12 (4 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 12 */
+# define PIC2_OCW2_ACT_IRQ13 (5 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 13 */
+# define PIC2_OCW2_ACT_IRQ14 (6 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 14 */
+# define PIC2_OCW2_ACT_IRQ15 (7 << PIC_OCW2_ACT_SHIFT) /* Act on IRQ 15 */
+
+# define PIC_OCW2_EOI_SHIFT (5)
+# define PIC_OCW2_EOI_MASK (7 << PIC_OCW2_EOI_SHIFT)
+# define PIC_OCW2_EOI_AUTO (0 << PIC_OCW2_EOI_SHIFT) /* Rotate in Auto EOI Mode (Clear) */
+# define PIC_OCW2_EOI_NONSPEC (1 << PIC_OCW2_EOI_SHIFT) /* Non Specific EOI */
+# define PIC_OCW2_EOI_SPEC (3 << PIC_OCW2_EOI_SHIFT) /* Specific EOI */
+# define PIC_OCW2_EOI_RAUTO (4 << PIC_OCW2_EOI_SHIFT) /* Rotate in Auto EOI Mode (Set) */
+# define PIC_OCW2_EOI_RNSPEC (5 << PIC_OCW2_EOI_SHIFT) /* Rotate on Non-Specific EOI */
+# define PIC_OCW2_EOI_PRIO (6 << PIC_OCW2_EOI_SHIFT) /* Set Priority Command (Use Bits 2:0) */
+# define PIC_OCW2_EOI_RSPEC (7 << PIC_OCW2_EOI_SHIFT) /* Rotate on Specific EOI (Use Bits 2:0) */
+
+/* Operation Control Word 3. Bits 0 and 1 bitsenable us to read the status
+ * of the Interrupt Request Register (IRR) and the In-Service Register (ISR).
+ * This is done by setting the appropriate bits correctly and reading the
+ * register at the Base Address.
+ *
+ * For example if we wanted to read the In-Service Register (ISR), then we
+ * would set both bits 1 and 0 to 1. The next read to the base register,
+ * (0x20 for PIC1 or 0xa0 for PIC2) will return the status of the In-Service
+ * Register.
+ */
+
+#define PIC1_OCW3 0x20
+#define PIC2_OCW3 0xa0
+
+# define PIC_OCW3_PCMD_SHIFT (0) /* Poll command */
+# define PIC_OCW3_PCMD_MASK (3 << PIC_OCW3_PCMD_SHIFT)
+# define PIC_OCW3_PCMD_IRR (2 << PIC_OCW3_PCMD_SHIFT) /* Next Read Returns Interrupt Request Register */
+# define PIC_OCW3_PCMD_ISR (3 << PIC_OCW3_PCMD_SHIFT) /* Next Read Returns In-Service Register */
+# define PIC_OCW3_POLLCMD (1 << 2) /* Poll command */
+# define PIC_OCW3_ONE (1 << 3) /* Must be set to 1 */
+# define PIC_OCW3_SM_SHIFT (5)
+# define PIC_OCW3_SM_MASK (3 << PIC_OCW3_SM_SHIFT)
+# define PIC_OCW3_RSM (2 << PIC_OCW3_SM_SHIFT) /* Reset Special Mask */
+# define PIC_OCW3_SSM (3 << PIC_OCW3_SM_SHIFT) /* Set Special Mask */
+
+/* If the PIC has been reset, it must be initialized with 2 to 4 Initialization
+ * Command Words (ICW) before it will accept and process Interrupt Requests. The
+ * following outlines the four possible Initialization Command Words.
+ */
+
+#define PIC1_ICW1 0x20
+#define PIC2_ICW1 0xa0
+
+# define PIC_ICW1_ICW4 (1 << 0) /* Will be Sending ICW4 (no ICW4) */
+# define PIC_ICW1_SINGLE (1 << 1) /* Single PIC (vs. Cascaded pics) */
+# define PIC_ICW1_INTERVAL (1 << 2) /* Call Address Interval of 4 (vs 8) */
+# define PIC_ICW1_LEVEL (1 << 3) /* Level Triggered Interrupts (vs Edge) */
+# define PIC_ICW1_ICW1 (1 << 4) /* Must be set to 1 for ICW1 */
+# define PIC_ICW1_VEC_SHIFT (5) /* Interrupt Vector Addresses for MCS-80/85 Mode */
+# define PIC_ICW1_VEC_MASK (7 << PIC_ICW1_VEC_SHIFT)
+
+/* Initialization Command Word 2 (ICW2) selects which vector information is
+ * released onto the bus, during the 2nd INTA Pulse. Using the 8086 mode,
+ * only bits 7:3 need to be used. This will be 00001000 (0x08) for PIC1 and
+ * 01110000 (0x70) for PIC2. If you wish to relocate the IRQ Vector Table,
+ * then you can use this register.
+ */
+
+#define PIC1_ICW2 0x21
+#define PIC2_ICW2 0xa1
+
+/* There are two different Initialization Command Word 3's. One is used, if
+ * the PIC is a master, while the other is used for slaves.
+ */
+
+#define PIC1_ICW3 0x21
+#define PIC2_ICW3 0xa1
+
+/* Master ICW3 */
+
+# define PIC1_ICW3_IRQ0 (1 << 0) /* IRQ0 is connected to a Slave */
+# define PIC1_ICW3_IRQ1 (1 << 1) /* IRQ1 is connected to a Slave */
+# define PIC1_ICW3_IRQ2 (1 << 2) /* IRQ2 is connected to a Slave */
+# define PIC1_ICW3_IRQ3 (1 << 3) /* IRQ3 is connected to a Slave */
+# define PIC1_ICW3_IRQ4 (1 << 4) /* IRQ4 is connected to a Slave */
+# define PIC1_ICW3_IRQ5 (1 << 5) /* IRQ5 is connected to a Slave */
+# define PIC1_ICW3_IRQ6 (1 << 6) /* IRQ6 is connected to a Slave */
+# define PIC1_ICW3_IRQ7 (1 << 7) /* IRQ7 is connected to a Slave */
+
+/* And for the slave device, the ICW3 below is used. */
+
+# define PIC_ICW3_SID_MASK (0) /* Slave ID */
+# define PIC_ICW3_SID_SHIFT (7 << PIC_ICW3_SID_MASK)
+# define PIC_ICW3_SID0 (0 << PIC_ICW3_SID_MASK) /* Slave 0 */
+# define PIC_ICW3_SID1 (1 << PIC_ICW3_SID_MASK) /* Slave 1 */
+# define PIC_ICW3_SID2 (2 << PIC_ICW3_SID_MASK) /* Slave 2 */
+# define PIC_ICW3_SID3 (3 << PIC_ICW3_SID_MASK) /* Slave 3 */
+# define PIC_ICW3_SID4 (4 << PIC_ICW3_SID_MASK) /* Slave 4 */
+# define PIC_ICW3_SID5 (5 << PIC_ICW3_SID_MASK) /* Slave 5 */
+# define PIC_ICW3_SID6 (6 << PIC_ICW3_SID_MASK) /* Slave 6 */
+# define PIC_ICW3_SID7 (7 << PIC_ICW3_SID_MASK) /* Slave 7 */
+
+#define PIC1_ICW4 0x21
+#define PIC2_ICW4 0xa1
+
+# define PIC_ICW4_FNM (1 << 4) /* Special Fully Nested Mode */
+# define PIC_ICW4_BMODE_SHIFT (2) /* Bufferd mode */
+# define PIC_ICW4_BMODE_MASK (3 << PIC_ICW4_BMODE_SHIFT)
+# define PIC_ICW4_BMODE_NON (0 << PIC_ICW4_BMODE_SHIFT) /* Non - Buffered Mode */
+# define PIC_ICW4_BMODE_SLAVE (2 << PIC_ICW4_BMODE_SHIFT) /* Buffered Mode - Slave */
+# define PIC_ICW4_BMODE_MSTR (3 << PIC_ICW4_BMODE_SHIFT) /* Buffered Mode - Master */
+# define PIC_ICW4_AEOI (1 << 1) /* Auto EOI */
+# define PIC_ICW4_808xMODE (1 << 0) /* 8086/8080 Mode (vs MCS-80/85) */
+
+/* Interrupt Mask Register */
+
+#define PIC1_IMR 0x21
+#define PIC2_IMR 0xa1
+
+# define PIC1_IMR_IRQ0 (1 << 0) /* IRQ0 System Timer */
+# define PIC1_IMR_IRQ1 (1 << 1) /* IRQ1 Keyboard */
+# define PIC1_IMR_IRQ2 (1 << 2) /* IRQ2 PIC2 */
+# define PIC1_IMR_IRQ3 (1 << 3) /* IRQ3 Serial Port */
+# define PIC1_IMR_IRQ4 (1 << 4) /* IRQ4 Serial Port */
+# define PIC1_IMR_IRQ5 (1 << 5) /* IRQ5 Reserved/Sound Card */
+# define PIC1_IMR_IRQ6 (1 << 6) /* IRQ6 Floppy Disk Controller */
+# define PIC1_IMR_IRQ7 (1 << 7) /* IRQ7 Parallel Port */
+# define PIC1_IMR_ALL 0xff
+
+# define PIC2_IMR_IRQ8 (1 << 0) /* IRQ8 Real Time Clock */
+# define PIC2_IMR_IRQ9 (1 << 1) /* IRQ9 Redirected IRQ2 */
+# define PIC2_IMR_IRQ10 (1 << 2) /* IRQ10 Reserved */
+# define PIC2_IMR_IRQ11 (1 << 3) /* IRQ11 Reserved */
+# define PIC2_IMR_IRQ12 (1 << 4) /* IRQ12 PS/2 Mouse */
+# define PIC2_IMR_IRQ13 (1 << 5) /* IRQ13 Maths Co-Processor */
+# define PIC2_IMR_IRQ14 (1 << 6) /* IRQ14 Hard Disk Drive */
+# define PIC2_IMR_IRQ15 (1 << 7) /* IRQ15 Reserved */
+# define PIC2_IMR_ALL 0xff
+
+/* Programmable Interrupt Timer Definitions */
+
+#define PIT_REG_COUNTER0 0x40
+#define PIT_REG_COUNTER1 0x41
+#define PIT_REG_COUNTER2 0x42
+#define PIT_REG_COMMAND 0x43
+
+/* PIT command bit defintions */
+
+# define PIT_OCW_BINCOUNT_BCD (1 << 0) /* vs binary */
+# define PIT_OCW_MODE_SHIFT (1)
+# define PIT_OCW_MODE_MASK (7 << PIT_OCW_MODE_SHIFT)
+# define PIT_OCW_MODE_TMCNT (0 << PIT_OCW_MODE_SHIFT) /* Terminal count */
+# define PIT_OCW_MODE_ONESHOT (1 << PIT_OCW_MODE_SHIFT) /* One shot */
+# define PIT_OCW_MODE_RATEGEN (2 << PIT_OCW_MODE_SHIFT) /* Rate gen */
+# define PIT_OCW_MODE_SQUARE (3 << PIT_OCW_MODE_SHIFT) /* Square wave generation */
+# define PIT_OCW_MODE_SWTRIG (4 << PIT_OCW_MODE_SHIFT) /* Software trigger */
+# define PIT_OCW_MODE_HWTRIG (5 << PIT_OCW_MODE_SHIFT) /* Hardware trigger */
+# define PIT_OCW_RL_SHIFT (4)
+# define PIT_OCW_RL_MASK (3 << PIT_OCW_RL_SHIFT)
+# define PIT_OCW_RL_LATCH (0 << PIT_OCW_RL_SHIFT)
+# define PIT_OCW_RL_LSBONLY (1 << PIT_OCW_RL_SHIFT)
+# define PIT_OCW_RL_MSBONLY (2 << PIT_OCW_RL_SHIFT)
+# define PIT_OCW_RL_DATA (3 << PIT_OCW_RL_SHIFT)
+# define PIT_OCW_COUNTER_SHIFT (6)
+# define PIT_OCW_COUNTER_MASK (3 << PIT_OCW_COUNTER_SHIFT)
+# define PIT_OCW_COUNTER_0 (0 << PIT_OCW_COUNTER_SHIFT)
+# define PIT_OCW_COUNTER_1 (1 << PIT_OCW_COUNTER_SHIFT)
+# define PIT_OCW_COUNTER_2 (2 << PIT_OCW_COUNTER_SHIFT)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* GDT data structures ******************************************************
+ *
+ * The Global Descriptor Table or GDT is a data structure used by Intel x86-
+ * family processors starting with the 80286 in order to define the
+ * characteristics of the various memory areas used during program execution,
+ * for example the base address, the size and access privileges like
+ * executability and writability. These memory areas are called segments in
+ * Intel terminology.
+ */
+
+/* This structure defines one segment */
+
+struct gdt_entry_s
+{
+ uint16_t lowlimit; /* The lower 16 bits of the limit */
+ uint16_t lowbase; /* The lower 16 bits of the base */
+ uint8_t midbase; /* The next 8 bits of the base */
+ uint8_t access; /* Access flags, determine ring segment can be used in */
+ uint8_t granularity;
+ uint8_t hibase; /* The last 8 bits of the base */
+} __attribute__((packed));
+
+/* This structure refers to the array of GDT entries, and is in the format
+ * required by the lgdt instruction.
+ */
+
+struct gdt_ptr_s
+{
+ uint16_t limit; /* The upper 16 bits of all selector limits */
+ uint32_t base; /* The address of the first GDT entry */
+} __attribute__((packed));
+
+/* IDT data structures ******************************************************
+ *
+ * The Interrupt Descriptor Table (IDT) is a data structure used by the x86
+ * architecture to implement an interrupt vector table. The IDT is used by the
+ * processor to determine the correct response to interrupts and exceptions.
+ */
+
+struct idt_entry_s
+{
+ uint16_t lobase; /* Lower 16-bits of vector address for interrupt */
+ uint16_t sel; /* Kernel segment selector */
+ uint8_t zero; /* This must always be zero */
+ uint8_t flags; /* (See documentation) */
+ uint16_t hibase; /* Upper 16-bits of vector address for interrupt */
+} __attribute__((packed));
+
+/* A struct describing a pointer to an array of interrupt handlers. This is
+ * in a format suitable for giving to 'lidt'.
+ */
+
+struct idt_ptr_s
+{
+ uint16_t limit;
+ uint32_t base; /* The address of the first GDT entry */
+} __attribute__((packed));
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* Return stack pointer */
+
+static inline uint32_t up_getsp()
+{
+ uint32_t regval;
+
+ asm volatile(
+ "\tmovl %%esp, %0\n"
+ : "=rm" (regval)
+ :
+ : "memory");
+ return regval;
+}
+
+/* Get segment registers */
+
+static inline uint32_t up_getds()
+{
+ uint32_t regval;
+
+ asm volatile(
+ "\tmov %%ds, %0\n"
+ : "=rm" (regval)
+ :
+ : "memory");
+ return regval;
+}
+
+static inline uint32_t up_getcs()
+{
+ uint32_t regval;
+
+ asm volatile(
+ "\tmov %%cs, %0\n"
+ : "=rm" (regval)
+ :
+ : "memory");
+ return regval;
+}
+
+static inline uint32_t up_getss()
+{
+ uint32_t regval;
+
+ asm volatile(
+ "\tmov %%ss, %0\n"
+ : "=rm" (regval)
+ :
+ : "memory");
+ return regval;
+}
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+EXTERN void gdt_flush(uint32_t gdt_addr);
+EXTERN void idt_flush(uint32_t idt_addr);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_X86_INCLUDE_I486_ARCH_H */
+
diff --git a/nuttx/arch/x86/include/i486/io.h b/nuttx/arch/x86/include/i486/io.h
new file mode 100644
index 000000000..ce3c37ecb
--- /dev/null
+++ b/nuttx/arch/x86/include/i486/io.h
@@ -0,0 +1,148 @@
+/****************************************************************************
+ * arch/x86/include/i486/io.h
+ * arch/chip/io.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through arch/io.h
+ */
+
+#ifndef __ARCH_X86_INCLUDE_I486_IO_H
+#define __ARCH_X86_INCLUDE_I486_IO_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <stdint.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+ #ifndef __ASSEMBLY__
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/* Standard x86 Port I/O */
+
+static inline void outb(uint8_t regval, uint16_t port)
+{
+ asm volatile(
+ "\toutb %0,%1\n"
+ :
+ : "a" (regval), "dN" (port)
+ );
+}
+
+static inline uint8_t inb(uint16_t port)
+{
+ uint8_t regval;
+ asm volatile(
+ "\tinb %1,%0\n"
+ : "=a" (regval)
+ : "dN" (port)
+ );
+ return regval;
+}
+
+static inline void outw(uint16_t regval, uint16_t port)
+{
+ asm volatile(
+ "\toutw %0,%1\n"
+ :
+ : "a" (regval), "dN" (port)
+ );
+}
+
+static inline uint16_t inw(uint16_t port)
+{
+ uint16_t regval;
+
+ asm volatile(
+ "\tinw %1,%0\n"
+ : "=a" (regval)
+ : "dN" (port)
+ );
+ return regval;
+}
+
+static inline void outl(uint32_t regval, uint16_t port)
+{
+ asm volatile(
+ "\toutl %0,%1\n"
+ :
+ : "a" (regval), "dN" (port)
+ );
+}
+
+static inline uint32_t inl(uint16_t port)
+{
+ uint32_t regval;
+ asm volatile(
+ "\tinl %1,%0\n"
+ : "=a" (regval)
+ : "dN" (port)
+ );
+ return regval;
+}
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_X86_INCLUDE_I486_IO_H */
diff --git a/nuttx/arch/x86/include/i486/irq.h b/nuttx/arch/x86/include/i486/irq.h
new file mode 100755
index 000000000..bca34b3ba
--- /dev/null
+++ b/nuttx/arch/x86/include/i486/irq.h
@@ -0,0 +1,287 @@
+/****************************************************************************
+ * arch/x86/include/i486/irq.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through nuttx/irq.h
+ */
+
+#ifndef __ARCH_X86_INCLUDE_I486_IRQ_H
+#define __ARCH_X86_INCLUDE_I486_IRQ_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+# include <stdbool.h>
+# include <arch/arch.h>
+#endif
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* ISR and IRQ numbers */
+
+#define ISR0 0 /* Division by zero exception */
+#define ISR1 1 /* Debug exception */
+#define ISR2 2 /* Non maskable interrupt */
+#define ISR3 3 /* Breakpoint exception */
+#define ISR4 4 /* 'Into detected overflow' */
+#define ISR5 5 /* Out of bounds exception */
+#define ISR6 6 /* Invalid opcode exception */
+#define ISR7 7 /* No coprocessor exception */
+#define ISR8 8 /* Double fault (pushes an error code) */
+#define ISR9 9 /* Coprocessor segment overrun */
+#define ISR10 10 /* Bad TSS (pushes an error code) */
+#define ISR11 11 /* Segment not present (pushes an error code) */
+#define ISR12 12 /* Stack fault (pushes an error code) */
+#define ISR13 13 /* General protection fault (pushes an error code) */
+#define ISR14 14 /* Page fault (pushes an error code) */
+#define ISR15 15 /* Unknown interrupt exception */
+#define ISR16 16 /* Coprocessor fault */
+#define ISR17 17 /* Alignment check exception */
+#define ISR18 18 /* Machine check exception */
+#define ISR19 19 /* Reserved */
+#define ISR20 20 /* Reserved */
+#define ISR21 21 /* Reserved */
+#define ISR22 22 /* Reserved */
+#define ISR23 23 /* Reserved */
+#define ISR24 24 /* Reserved */
+#define ISR25 25 /* Reserved */
+#define ISR26 26 /* Reserved */
+#define ISR27 27 /* Reserved */
+#define ISR28 28 /* Reserved */
+#define ISR29 29 /* Reserved */
+#define ISR30 30 /* Reserved */
+#define ISR31 31 /* Reserved */
+
+#define IRQ0 32 /* System timer (cannot be changed) */
+#define IRQ1 33 /* Keyboard controller (cannot be changed) */
+#define IRQ2 34 /* Cascaded signals from IRQs 8–15 */
+#define IRQ3 35 /* Serial port controller for COM2/4 */
+#define IRQ4 36 /* serial port controller for COM1/3 */
+#define IRQ5 37 /* LPT port 2 or sound card */
+#define IRQ6 38 /* Floppy disk controller */
+#define IRQ7 39 /* LPT port 1 or sound card */
+#define IRQ8 40 /* Real time clock (RTC) */
+#define IRQ9 41 /* Open interrupt/available or SCSI host adapter */
+#define IRQ10 42 /* Open interrupt/available or SCSI or NIC */
+#define IRQ11 43 /* Open interrupt/available or SCSI or NIC */
+#define IRQ12 44 /* Mouse on PS/2 connector */
+#define IRQ13 45 /* Math coprocessor */
+#define IRQ14 46 /* Primary ATA channel */
+#define IRQ15 47 /* Secondary ATA channel */
+
+#define NR_IRQS 48
+
+/* Common register save structgure created by up_saveusercontext() and by
+ * ISR/IRQ interrupt processing.
+ */
+
+#define REG_DS (0) /* Data segment selector */
+#define REG_EDI (1) /* Saved by pusha */
+#define REG_ESI (2) /* " " "" " " */
+#define REG_EBP (3) /* " " "" " " */
+#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 (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)
+
+/* Some special landmarks in the stack frame:
+ *
+ * TOP_PUSHA - The offset (in 32-bit words) from the beginning of the
+ * save area on the stack to the value that should be in REG_ESP.
+ * BOTTOM_PUSHA - The offset (in 32-bit words) from the stack position before
+ * the interrupt occurred to the value that should be in REG_ESP.
+ * save area on the stack to the value that should be in REG_ESP.
+ * OFFSET_PRIO - The offset from the value of REG_ESP to the value of the
+ * stack pointer before the interrupt occurred (assuming that a priority
+ * change occurred.
+ * OFFSET_PRIO - The offset from the value of REG_ESP to the value of the
+ * stack pointer before the interrupt occurred (assuming that NO priority
+ * change occurred.
+ */
+
+#define TOP_PUSHA REG_IRQNO
+#define BOTTOM_PRIO (XCPTCONTEXT_REGS-REG_IRQNO)
+#define BOTTOM_NOPRIO (REG_SP-REG_IRQNO)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* This struct defines the way the registers are stored */
+
+#ifndef __ASSEMBLY__
+struct xcptcontext
+{
+ /* The following function pointer is non-zero if there are pending signals
+ * to be processed.
+ */
+
+#ifndef CONFIG_DISABLE_SIGNALS
+ void *sigdeliver; /* Actual type is sig_deliver_t */
+
+ /* These are saved copies of instruction pointer and EFLAGS used during
+ * signal processing.
+ */
+
+ uint32_t saved_eip;
+ uint32_t saved_eflags;
+#endif
+
+ /* Register save area */
+
+ uint32_t regs[XCPTCONTEXT_REGS];
+};
+#endif
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* Get the current FLAGS register contents */
+
+static inline irqstate_t irqflags()
+{
+ irqstate_t flags;
+
+ asm volatile(
+ "\tpushf\n"
+ "\tpop %0\n"
+ : "=rm" (flags)
+ :
+ : "memory");
+ return flags;
+}
+
+/* Get a sample of the FLAGS register, determine if interrupts are disabled.
+ * If the X86_FLAGS_IF is cleared by cli, then interrupts are disabled. If
+ * if the X86_FLAGS_IF is set by sti, then interrupts are enable.
+ */
+
+static inline bool irqdisabled(irqstate_t flags)
+{
+ return ((flags & X86_FLAGS_IF) == 0);
+}
+
+static inline bool irqenabled(irqstate_t flags)
+{
+ return ((flags & X86_FLAGS_IF) != 0);
+}
+
+/* Disable interrupts unconditionally */
+
+static inline void irqdisable(void)
+{
+ asm volatile("cli": : :"memory");
+}
+
+/* Enable interrupts unconditionally */
+
+static inline void irqenable(void)
+{
+ asm volatile("sti": : :"memory");
+}
+
+/* Disable interrupts, but return previous interrupt state */
+
+static inline irqstate_t irqsave(void)
+{
+ irqstate_t flags = irqflags();
+ irqdisable();
+ return flags;
+}
+
+/* Conditionally disable interrupts */
+
+static inline void irqrestore(irqstate_t flags)
+{
+ if (irqenabled(flags))
+ {
+ irqenable();
+ }
+}
+
+static inline void system_call3(unsigned int nbr, uintptr_t parm1,
+ uintptr_t parm2, uintptr_t parm3)
+{
+ /* To be provided */
+}
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_X86_INCLUDE_I486_IRQ_H */
+
diff --git a/nuttx/arch/x86/include/i486/limits.h b/nuttx/arch/x86/include/i486/limits.h
new file mode 100755
index 000000000..ac0755ef9
--- /dev/null
+++ b/nuttx/arch/x86/include/i486/limits.h
@@ -0,0 +1,81 @@
+/****************************************************************************
+ * arch/x86/include/i486/limits.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_X86_INCLUDE_I486_LIMITS_H
+#define __ARCH_X86_INCLUDE_I486_LIMITS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define CHAR_BIT 8
+#define SCHAR_MIN 0x80
+#define SCHAR_MAX 0x7f
+#define UCHAR_MAX 0xff
+
+/* These could be different on machines where char is unsigned */
+
+#define CHAR_MIN SCHAR_MIN
+#define CHAR_MAX SCHAR_MAX
+
+#define SHRT_MIN 0x8000
+#define SHRT_MAX 0x7fff
+#define USHRT_MAX 0xffff
+
+#define INT_MIN 0x80000000
+#define INT_MAX 0x7fffffff
+#define UINT_MAX 0xffffffff
+
+/* These change on 32-bit and 64-bit platforms */
+
+#define LONG_MAX 0x80000000
+#define LONG_MIN 0x7fffffff
+#define ULONG_MAX 0xffffffff
+
+#define LLONG_MAX 0x8000000000000000
+#define LLONG_MIN 0x7fffffffffffffff
+#define ULLONG_MAX 0xffffffffffffffff
+
+/* A pointer is 4 bytes */
+
+#define PTR_MIN 0x80000000
+#define PTR_MAX 0x7fffffff
+#define UPTR_MAX 0xffffffff
+
+#endif /* __ARCH_X86_INCLUDE_I486_LIMITS_H */
diff --git a/nuttx/arch/x86/include/i486/syscall.h b/nuttx/arch/x86/include/i486/syscall.h
new file mode 100644
index 000000000..7ca5f81ea
--- /dev/null
+++ b/nuttx/arch/x86/include/i486/syscall.h
@@ -0,0 +1,138 @@
+/****************************************************************************
+ * arch/x86/include/i486/syscall.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through include/syscall.h or include/sys/sycall.h
+ */
+
+#ifndef __ARCH_X86_INCLUDE_I486_SYSCALL_H
+#define __ARCH_X86_INCLUDE_I486_SYSCALL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <stdint.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+#define SYS_syscall 0x80
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* SWI with SYS_ call number and six parameters */
+
+EXTERN uintptr_t sys_call6(unsigned int nbr, uintptr_t parm1,
+ uintptr_t parm2, uintptr_t parm3,
+ uintptr_t parm4, uintptr_t parm5,
+ uintptr_t parm6);
+
+/* SWI with SYS_ call number and no parameters */
+
+static inline uintptr_t sys_call0(unsigned int nbr)
+{
+ return sys_call6(nbr, 0, 0, 0, 0, 0, 0);
+}
+
+/* SWI with SYS_ call number and one parameter */
+
+static inline uintptr_t sys_call1(unsigned int nbr, uintptr_t parm1)
+{
+ return sys_call6(nbr, parm1, 0, 0, 0, 0, 0);
+}
+
+/* SWI with SYS_ call number and two parameters */
+
+static inline uintptr_t sys_call2(unsigned int nbr, uintptr_t parm1,
+ uintptr_t parm2)
+{
+ return sys_call6(nbr, parm1, parm2, 0, 0, 0, 0);
+}
+
+/* SWI with SYS_ call number and three parameters */
+
+static inline uintptr_t sys_call3(unsigned int nbr, uintptr_t parm1,
+ uintptr_t parm2, uintptr_t parm3)
+{
+ return sys_call6(nbr, parm1, parm2, parm3, 0, 0, 0);
+}
+
+/* SWI with SYS_ call number and four parameters */
+
+static inline uintptr_t sys_call4(unsigned int nbr, uintptr_t parm1,
+ uintptr_t parm2, uintptr_t parm3,
+ uintptr_t parm4)
+{
+ return sys_call6(nbr, parm1, parm2, parm3, parm4, 0, 0);
+}
+
+/* SWI with SYS_ call number and five parameters */
+
+static inline uintptr_t sys_call5(unsigned int nbr, uintptr_t parm1,
+ uintptr_t parm2, uintptr_t parm3,
+ uintptr_t parm4, uintptr_t parm5)
+{
+ return sys_call6(nbr, parm1, parm2, parm3, parm4, parm5, 0);
+}
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_X86_INCLUDE_I486_SYSCALL_H */
+
diff --git a/nuttx/arch/x86/include/i486/types.h b/nuttx/arch/x86/include/i486/types.h
new file mode 100755
index 000000000..d6f25f3e0
--- /dev/null
+++ b/nuttx/arch/x86/include/i486/types.h
@@ -0,0 +1,97 @@
+/************************************************************************
+ * arch/x86/include/i486/types.h
+ *
+ * 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.
+ *
+ ************************************************************************/
+
+/* This file should never be included directed but, rather, only
+ * indirectly through arch/types.h (which is, in turn only accessed
+ * through sys/types.h or stdint.h).
+ */
+
+#ifndef __ARCH_X86_INCLUDE_I486_TYPES_H
+#define __ARCH_X86_INCLUDE_I486_TYPES_H
+
+/************************************************************************
+ * Included Files
+ ************************************************************************/
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Type Declarations
+ ************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* These are the sizes of the standard integer types. NOTE that these type
+ * names have a leading underscore character. This file will be included
+ * (indirectly) by include/stdint.h and typedef'ed to the final name without
+ * the underscore character. This roundabout way of doings things allows
+ * the stdint.h to be removed from the include/ directory in the event that
+ * the user prefers to use the definitions provided by their toolchain header
+ * files
+ */
+
+typedef signed char _int8_t;
+typedef unsigned char _uint8_t;
+
+typedef signed short _int16_t;
+typedef unsigned short _uint16_t;
+
+typedef signed int _int32_t;
+typedef unsigned int _uint32_t;
+
+typedef signed long long _int64_t;
+typedef unsigned long long _uint64_t;
+#define __INT64_DEFINED
+
+/* A pointer is 4 bytes */
+
+typedef signed int _intptr_t;
+typedef unsigned int _uintptr_t;
+
+/* This is the size of the interrupt state save returned by
+ * irqsave()
+ */
+
+typedef unsigned int irqstate_t;
+
+#endif /* __ASSEMBLY__ */
+
+/************************************************************************
+ * Global Function Prototypes
+ ************************************************************************/
+
+#endif /* __ARCH_X86_INCLUDE_I486_TYPES_H */
diff --git a/nuttx/arch/x86/include/io.h b/nuttx/arch/x86/include/io.h
new file mode 100755
index 000000000..4f88932c5
--- /dev/null
+++ b/nuttx/arch/x86/include/io.h
@@ -0,0 +1,86 @@
+/****************************************************************************
+ * arch/x86/include/io.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_X86_INCLUDE_IO_H
+#define __ARCH_X86_INCLUDE_IO_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/* Include architecture-specific IO definitions (These are probably common
+ * across all architectures, but this gives a little bit of flexibility).
+ */
+
+#ifdef CONFIG_ARCH_I486
+# include <arch/i486/io.h>
+#endif
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_X86_INCLUDE_IO_H */
+
diff --git a/nuttx/arch/x86/include/irq.h b/nuttx/arch/x86/include/irq.h
new file mode 100755
index 000000000..97c8c0f9c
--- /dev/null
+++ b/nuttx/arch/x86/include/irq.h
@@ -0,0 +1,98 @@
+/****************************************************************************
+ * arch/x86/include/irq.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through nuttx/irq.h
+ */
+
+#ifndef __ARCH_X86_INCLUDE_IRQ_H
+#define __ARCH_X86_INCLUDE_IRQ_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/* Include NuttX-specific IRQ definitions */
+
+#include <nuttx/irq.h>
+
+/* Include chip-specific IRQ definitions (including IRQ numbers) */
+
+#include <arch/chip/irq.h>
+
+/* Include architecture-specific IRQ definitions (including register save
+ * structure and irqsave()/irqrestore() macros).
+ */
+
+#ifdef CONFIG_ARCH_I486
+# include <arch/i486/irq.h>
+#endif
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_X86_INCLUDE_IRQ_H */
+
diff --git a/nuttx/arch/x86/include/limits.h b/nuttx/arch/x86/include/limits.h
new file mode 100755
index 000000000..729504edd
--- /dev/null
+++ b/nuttx/arch/x86/include/limits.h
@@ -0,0 +1,53 @@
+/****************************************************************************
+ * arch/x86/include/limits.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_X86_INCLUDE_LIMITS_H
+#define __ARCH_X86_INCLUDE_LIMITS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/* Include architecture-specific limits */
+
+#ifdef CONFIG_ARCH_I486
+# include <arch/i486/limits.h>
+#endif
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#endif /* __ARCH_X86_INCLUDE_LIMITS_H */
diff --git a/nuttx/arch/x86/include/qemu/arch.h b/nuttx/arch/x86/include/qemu/arch.h
new file mode 100755
index 000000000..fc2a7278b
--- /dev/null
+++ b/nuttx/arch/x86/include/qemu/arch.h
@@ -0,0 +1,80 @@
+/****************************************************************************
+ * arch/x86/include/qemu/arch.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through nuttx/arch.h
+ */
+
+#ifndef __ARCH_X86_INCLUDE_QEMU_ARCH_H
+#define __ARCH_X86_INCLUDE_QEMU_ARCH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ARCH_X86_INCLUDE_QEMU_ARCH_H */
+
diff --git a/nuttx/arch/x86/include/qemu/irq.h b/nuttx/arch/x86/include/qemu/irq.h
new file mode 100755
index 000000000..23611b83c
--- /dev/null
+++ b/nuttx/arch/x86/include/qemu/irq.h
@@ -0,0 +1,80 @@
+/****************************************************************************
+ * arch/x86/include/qemu/irq.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through nuttx/irq.h
+ */
+
+#ifndef __ARCH_X86_INCLUDE_QEMU_IRQ_H
+#define __ARCH_X86_INCLUDE_QEMU_IRQ_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ARCH_X86_INCLUDE_QEMU_IRQ_H */
+
diff --git a/nuttx/arch/x86/include/syscall.h b/nuttx/arch/x86/include/syscall.h
new file mode 100644
index 000000000..2d3f9a8c0
--- /dev/null
+++ b/nuttx/arch/x86/include/syscall.h
@@ -0,0 +1,88 @@
+/****************************************************************************
+ * arch/x86/include/syscall.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through include/syscall.h or include/sys/sycall.h
+ */
+
+#ifndef __ARCH_X86_INCLUDE_SYSCALL_H
+#define __ARCH_X86_INCLUDE_SYSCALL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/* Include x86 architecture-specific syscall macros */
+
+#ifdef CONFIG_ARCH_I486
+# include <arch/i486/syscall.h>
+#endif
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_X86_INCLUDE_SYSCALL_H */
+
diff --git a/nuttx/arch/x86/include/types.h b/nuttx/arch/x86/include/types.h
new file mode 100755
index 000000000..112de8525
--- /dev/null
+++ b/nuttx/arch/x86/include/types.h
@@ -0,0 +1,65 @@
+/****************************************************************************
+ * arch/x86/include/types.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through sys/types.h
+ */
+
+#ifndef __ARCH_X86_INCLUDE_TYPES_H
+#define __ARCH_X86_INCLUDE_TYPES_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/* Include architecture-specific limits */
+
+#ifdef CONFIG_ARCH_I486
+# include <arch/i486/types.h>
+#endif
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ARCH_X86_INCLUDE_TYPES_H */
diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile
new file mode 100644
index 000000000..d7b2140c8
--- /dev/null
+++ b/nuttx/arch/x86/src/Makefile
@@ -0,0 +1,163 @@
+############################################################################
+# arch/x86/src/Makefile
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+-include chip/Make.defs
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(CONFIG_ARCH_I486),y)
+ARCH_SUBDIR = i486
+endif
+
+ifeq ($(WINTOOL),y)
+ NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}"
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \
+ -I "${shell cygpath -w $(TOPDIR)/sched}"
+else
+ NUTTX = $(TOPDIR)/nuttx
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \
+ -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched
+endif
+
+HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT))
+
+ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS)
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+LDFLAGS = $(ARCHSCRIPT)
+EXTRA_LIBS =
+
+LINKLIBS =
+ifeq ($(WINTOOL),y)
+ LIBPATHS = ${shell for path in $(LINKLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done}
+ LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
+else
+ LIBPATHS = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
+ LIBPATHS += -L"$(BOARDDIR)"
+endif
+LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
+
+BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
+
+LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
+
+ifeq ($(HOSTOS),FreeBSD)
+ HOST_ARCH = ${shell uname -m 2>/dev/null || echo "Other"}
+ ifeq ($(HOST_ARCH),amd64)
+ LDFLAGS += -melf_i386
+ LIBGCC = "/usr/lib32/libgcc.a"
+ endif
+endif
+
+VPATH = chip:common:$(ARCH_SUBDIR)
+
+all: $(HEAD_OBJ) libarch$(LIBEXT)
+
+$(AOBJS) $(HEAD_OBJ): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libarch$(LIBEXT): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+board/libboard$(LIBEXT):
+ @$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
+
+nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT)
+ @echo "LD: nuttx$(EXEEXT)"
+ @$(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
+ --start-group $(LDLIBS) -lboard --end-group $(EXTRA_LIBS) $(LIBGCC)
+ifeq ($(CONFIG_BOOT_RUNFROMFLASH),y)
+ @export flashloc=`$(OBJDUMP) --all-headers $(NUTTX)$(EXEEXT) | grep _eronly | cut -d' ' -f1`; \
+ $(OBJCOPY) $(OBJCOPYARGS) --adjust-section-vma=.data=0x$$flashloc $(NUTTX)$(EXEEXT) $(NUTTX).flashimage
+ @mv $(NUTTX).flashimage $(NUTTX)$(EXEEXT)
+endif
+ @$(NM) $(NUTTX)$(EXEEXT) | \
+ grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
+ sort > $(TOPDIR)/System.map
+ @export vflashstart=`$(OBJDUMP) --all-headers $(NUTTX)$(EXEEXT) | grep _vflashstart | cut -d' ' -f1`; \
+ if [ ! -z "$$vflashstart" ]; then \
+ $(OBJCOPY) $(OBJCOPYARGS) --adjust-section-vma=.vector=0x$$vflashstart $(NUTTX)$(EXEEXT) $(NUTTX).flashimage; \
+ mv $(NUTTX).flashimage $(NUTTX)$(EXEEXT); \
+ fi
+
+# This is part of the top-level export target
+
+export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
+ @if [ -d "$(EXPORT_DIR)/startup" ]; then \
+ cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \
+ else \
+ echo "$(EXPORT_DIR)/startup does not exist"; \
+ exit 1; \
+ fi
+
+# Dependencies
+
+.depend: Makefile chip/Make.defs $(SRCS)
+ @if [ -e board/Makefile ]; then \
+ $(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
+ fi
+ @$(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
+ $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @if [ -e board/Makefile ]; then \
+ $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \
+ fi
+ @rm -f libarch$(LIBEXT) *~ .*.swp
+ $(call CLEAN)
+
+distclean: clean
+ @if [ -e board/Makefile ]; then \
+ $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \
+ fi
+ @rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/arch/x86/src/README.txt b/nuttx/arch/x86/src/README.txt
new file mode 100755
index 000000000..1b0c0590b
--- /dev/null
+++ b/nuttx/arch/x86/src/README.txt
@@ -0,0 +1,31 @@
+arch/x86/src/README.txt
+^^^^^^^^^^^^^^^^^^^^^^^
+
+This directory holds x86-specific source files. All x86 source reside in
+lower-level common, chip-specific, and architecture-specific directories.
+
+common/ Directory
+^^^^^^^^^^^^^^^^^
+
+This directory holds source files common to all x86 architectures.
+
+Architecture-Specific Directories
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+Architecture-specific directories hold common source files shared for by
+implementations of specific x86 architectures.
+
+i486
+ This directory holds logic appropriate for any instantiation of the 32-bit
+ i486 architecture.
+
+Chip-Specific directories
+^^^^^^^^^^^^^^^^^^^^^^^^^
+
+The same x86 architecture may be realized in different chip implementations.
+For SoC chips, in particular, on-chip devices and differing interrupt
+structures may require special, chip-specific definitions in these chip-
+specific directories.
+
+qemu
+ This is the implementation of NuttX on the QEMU x86 simulation.
diff --git a/nuttx/arch/x86/src/common/up_allocateheap.c b/nuttx/arch/x86/src/common/up_allocateheap.c
new file mode 100644
index 000000000..3273d681f
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_allocateheap.c
@@ -0,0 +1,82 @@
+/****************************************************************************
+ * arch/x86/src/common/up_allocateheap.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 <sys/types.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_allocate_heap
+ *
+ * Description:
+ * The heap may be statically allocated by defining CONFIG_HEAP_BASE and
+ * CONFIG_HEAP_SIZE. If these are not defined, then this function will be
+ * called to dynamically set aside the heap region.
+ *
+ ****************************************************************************/
+
+void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
+{
+ up_ledon(LED_HEAPALLOCATE);
+ *heap_start = (FAR void*)g_heapbase;
+ *heap_size = CONFIG_DRAM_END - g_heapbase;
+}
diff --git a/nuttx/arch/x86/src/common/up_arch.h b/nuttx/arch/x86/src/common/up_arch.h
new file mode 100644
index 000000000..96d49d306
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_arch.h
@@ -0,0 +1,90 @@
+/****************************************************************************
+ * arch/x86/src/common/up_arch.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef ___ARCH_X86_SRC_COMMON_UP_ARCH_H
+#define ___ARCH_X86_SRC_COMMON_UP_ARCH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+#include <arch/io.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline Functions
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+# define getreg8(p) inb(p)
+# define putreg8(v,p) outb(v,p)
+# define getreg16(p) inw(p)
+# define putreg16(v,p) outw(v,p)
+# define getreg32(p) inl(p)
+# define putreg32(v,p) outl(v,p)
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* Atomic modification of registers */
+
+EXTERN void modifyreg8(unsigned int addr, uint8_t clearbits, uint8_t setbits);
+EXTERN void modifyreg16(unsigned int addr, uint16_t clearbits, uint16_t setbits);
+EXTERN void modifyreg32(unsigned int addr, uint32_t clearbits, uint32_t setbits);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* ___ARCH_X86_SRC_COMMON_UP_ARCH_H */
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..776784656
--- /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 <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 <stdint.h>
+#include <stdlib.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <arch/arch.h>
+#include <arch/board/board.h>
+
+#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((uint32_t*)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_blocktask.c b/nuttx/arch/x86/src/common/up_blocktask.c
new file mode 100755
index 000000000..f11931103
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_blocktask.c
@@ -0,0 +1,166 @@
+/****************************************************************************
+ * arch/x86/src/common/up_blocktask.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 <stdbool.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_block_task
+ *
+ * Description:
+ * The currently executing task at the head of the ready to run list must
+ * be stopped. Save its context and move it to the inactive list specified
+ * by task_state.
+ *
+ * Inputs:
+ * tcb: Refers to a task in the ready-to-run list (normally the task at the
+ * head of the list). It most be stopped, its context saved and moved
+ * into one of the waiting task lists. It it was the task at the head
+ * of the ready-to-run list, then a context to the new ready to run task
+ * must be performed.
+ * task_state: Specifies which waiting task list should be
+ * hold the blocked task TCB.
+ *
+ ****************************************************************************/
+
+void up_block_task(_TCB *tcb, tstate_t task_state)
+{
+ /* Verify that the context switch can be performed */
+
+ if ((tcb->task_state < FIRST_READY_TO_RUN_STATE) ||
+ (tcb->task_state > LAST_READY_TO_RUN_STATE))
+ {
+ PANIC(OSERR_BADBLOCKSTATE);
+ }
+ else
+ {
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+ bool switch_needed;
+
+ /* Remove the tcb task from the ready-to-run list. If we
+ * are blocking the task at the head of the task list (the
+ * most likely case), then a context switch to the next
+ * ready-to-run task is needed. In this case, it should
+ * also be true that rtcb == tcb.
+ */
+
+ switch_needed = sched_removereadytorun(tcb);
+
+ /* Add the task to the specified blocked task list */
+
+ sched_addblocked(tcb, (tstate_t)task_state);
+
+ /* If there are any pending tasks, then add them to the g_readytorun
+ * task list now
+ */
+
+ if (g_pendingtasks.head)
+ {
+ switch_needed |= sched_mergepending();
+ }
+
+ /* Now, perform the context switch if one is needed */
+
+ if (switch_needed)
+ {
+ /* Are we in an interrupt handler? */
+
+ if (current_regs)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current_regs into the OLD rtcb.
+ */
+
+ up_savestate(rtcb->xcp.regs);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+
+ /* Then switch contexts */
+
+ up_restorestate(rtcb->xcp.regs);
+ }
+
+ /* Copy the user C context into the TCB at the (old) head of the
+ * g_readytorun Task list. if up_saveusercontext returns a non-zero
+ * value, then this is really the previously running task restarting!
+ */
+
+ else if (!up_saveusercontext(rtcb->xcp.regs))
+ {
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+
+ /* Then switch contexts */
+
+ up_fullcontextrestore(rtcb->xcp.regs);
+ }
+ }
+ }
+}
diff --git a/nuttx/arch/x86/src/common/up_copystate.c b/nuttx/arch/x86/src/common/up_copystate.c
new file mode 100644
index 000000000..4ae842308
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_copystate.c
@@ -0,0 +1,82 @@
+/****************************************************************************
+ * arch/x86/src/common/up_copystate.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 <stdint.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_undefinedinsn
+ ****************************************************************************/
+
+/* A little faster than most memcpy's */
+
+void up_copystate(uint32_t *dest, uint32_t *src)
+{
+ int i;
+
+ /* In the current ARM model, the state is always copied to and from the
+ * stack and TCB.
+ */
+
+ for (i = 0; i < XCPTCONTEXT_REGS; i++)
+ {
+ *dest++ = *src++;
+ }
+}
+
diff --git a/nuttx/arch/x86/src/common/up_exit.c b/nuttx/arch/x86/src/common/up_exit.c
new file mode 100644
index 000000000..ceca72c87
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_exit.c
@@ -0,0 +1,174 @@
+/****************************************************************************
+ * common/up_exit.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 <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+#ifdef CONFIG_DUMP_ON_EXIT
+#include <nuttx/fs.h>
+#endif
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: _up_dumponexit
+ *
+ * Description:
+ * Dump the state of all tasks whenever on task exits. This is debug
+ * instrumentation that was added to check file-related reference counting
+ * but could be useful again sometime in the future.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG)
+static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg)
+{
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0
+ int i;
+#endif
+
+ sdbg(" TCB=%p name=%s pid=%d\n", tcb, tcb->argv[0], tcb->pid);
+ sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state);
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ if (tcb->filelist)
+ {
+ sdbg(" filelist refcount=%d\n",
+ tcb->filelist->fl_crefs);
+
+ for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++)
+ {
+ struct inode *inode = tcb->filelist->fl_files[i].f_inode;
+ if (inode)
+ {
+ sdbg(" fd=%d refcount=%d\n",
+ i, inode->i_crefs);
+ }
+ }
+ }
+#endif
+
+#if CONFIG_NFILE_STREAMS > 0
+ if (tcb->streams)
+ {
+ sdbg(" streamlist refcount=%d\n",
+ tcb->streams->sl_crefs);
+
+ for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
+ {
+ struct file_struct *filep = &tcb->streams->sl_streams[i];
+ if (filep->fs_filedes >= 0)
+ {
+#if CONFIG_STDIO_BUFFER_SIZE > 0
+ sdbg(" fd=%d nbytes=%d\n",
+ filep->fs_filedes,
+ filep->fs_bufpos - filep->fs_bufstart);
+#else
+ sdbg(" fd=%d\n", filep->fs_filedes);
+#endif
+ }
+ }
+ }
+#endif
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: _exit
+ *
+ * Description:
+ * This function causes the currently executing task to cease to exist.
+ * This is a special case of task_delete() where the task to be deleted is
+ * the currently executing task. It is more complex because a context
+ * switch must be perform to the next ready to run task.
+ *
+ ****************************************************************************/
+
+void _exit(int status)
+{
+ _TCB* tcb;
+
+ /* Disable interrupts. They will be restored when the next
+ * task is started.
+ */
+
+ (void)irqsave();
+
+ slldbg("TCB=%p exitting\n", g_readytorun.head);
+
+#if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG)
+ slldbg("Other tasks:\n");
+ sched_foreach(_up_dumponexit, NULL);
+#endif
+
+ /* Destroy the task at the head of the ready to run list. */
+
+ (void)task_deletecurrent();
+
+ /* Now, perform the context switch to the new ready-to-run task at the
+ * head of the list.
+ */
+
+ tcb = (_TCB*)g_readytorun.head;
+
+ /* Then switch contexts */
+
+ up_fullcontextrestore(tcb->xcp.regs);
+}
+
diff --git a/nuttx/arch/x86/src/common/up_initialize.c b/nuttx/arch/x86/src/common/up_initialize.c
new file mode 100644
index 000000000..0ceeddbb6
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_initialize.c
@@ -0,0 +1,168 @@
+/****************************************************************************
+ * arch/x86/src/common/up_initialize.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 <nuttx/arch.h>
+#include <nuttx/fs.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_calibratedelay
+ *
+ * Description:
+ * Delay loops are provided for short timing loops. This function, if
+ * enabled, will just wait for 100 seconds. Using a stopwatch, you can
+ * can then determine if the timing loops are properly calibrated.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_ARCH_CALIBRATION) && defined(CONFIG_DEBUG)
+static void up_calibratedelay(void)
+{
+ int i;
+ lldbg("Beginning 100s delay\n");
+ for (i = 0; i < 100; i++)
+ {
+ up_mdelay(1000);
+ }
+ lldbg("End 100s delay\n");
+}
+#else
+# define up_calibratedelay()
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_initialize
+ *
+ * Description:
+ * up_initialize will be called once during OS initialization after the
+ * basic OS services have been initialized. The architecture specific
+ * details of initializing the OS will be handled here. Such things as
+ * setting up interrupt service routines, starting the clock, and
+ * registering device drivers are some of the things that are different
+ * for each processor and hardware platform.
+ *
+ * up_initialize is called after the OS initialized but before the user
+ * initialization logic has been started and before the libraries have
+ * been initialized. OS services and driver services are available.
+ *
+ ****************************************************************************/
+
+void up_initialize(void)
+{
+ /* Initialize global variables */
+
+ current_regs = NULL;
+
+ /* Calibrate the timing loop */
+
+ up_calibratedelay();
+
+ /* Add any extra memory fragments to the memory manager */
+
+ up_addregion();
+
+ /* Initialize the interrupt subsystem */
+
+ up_irqinitialize();
+
+ /* Initialize the DMA subsystem if the weak function up_dmainitialize has been
+ * brought into the build
+ */
+
+#ifdef CONFIG_ARCH_DMA
+#ifdef CONFIG_HAVE_WEAKFUNCTIONS
+ if (up_dmainitialize)
+#endif
+ {
+ up_dmainitialize();
+ }
+#endif
+
+ /* Initialize the system timer interrupt */
+
+#if !defined(CONFIG_SUPPRESS_INTERRUPTS) && !defined(CONFIG_SUPPRESS_TIMER_INTS)
+ up_timerinit();
+#endif
+
+ /* Register devices */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ devnull_register(); /* Standard /dev/null */
+#endif
+
+ /* Initialize the serial device driver */
+
+#ifdef CONFIG_USE_SERIALDRIVER
+ up_serialinit();
+#elif defined(CONFIG_DEV_LOWCONSOLE)
+ lowconsole_init();
+#endif
+
+ /* Initialize the netwok */
+
+ up_netinitialize();
+
+ /* Initialize USB -- device and/or host */
+
+ up_usbinitialize();
+ up_ledon(LED_IRQSENABLED);
+}
diff --git a/nuttx/arch/x86/src/common/up_internal.h b/nuttx/arch/x86/src/common/up_internal.h
new file mode 100644
index 000000000..185d0afc0
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_internal.h
@@ -0,0 +1,237 @@
+/****************************************************************************
+ * arch/x86/src/common/up_internal.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_X86_SRC_COMMON_UP_INTERNAL_H
+#define __ARCH_X86_SRC_COMMON_UP_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Bring-up debug configurations. These are here (vs defconfig) because
+ * these should only be controlled during low level board bring-up and not
+ * part of normal platform configuration.
+ */
+
+#undef CONFIG_SUPPRESS_INTERRUPTS /* DEFINED: Do not enable interrupts */
+#undef CONFIG_SUPPRESS_TIMER_INTS /* DEFINED: No timer */
+#undef CONFIG_SUPPRESS_SERIAL_INTS /* DEFINED: Console will poll */
+#undef CONFIG_SUPPRESS_UART_CONFIG /* DEFINED: Do not reconfig UART */
+#undef CONFIG_DUMP_ON_EXIT /* DEFINED: Dump task state on exit */
+
+/* Determine which (if any) console driver to use */
+
+#if CONFIG_NFILE_DESCRIPTORS == 0 || defined(CONFIG_DEV_LOWCONSOLE)
+# undef CONFIG_USE_SERIALDRIVER
+# undef CONFIG_USE_EARLYSERIALINIT
+#elif defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0
+# define CONFIG_USE_SERIALDRIVER 1
+# define CONFIG_USE_EARLYSERIALINIT 1
+#endif
+
+/* Check if an interrupt stack size is configured */
+
+#ifndef CONFIG_ARCH_INTERRUPTSTACK
+# define CONFIG_ARCH_INTERRUPTSTACK 0
+#endif
+
+/* Macros to handle saving and restore interrupt state. In the current
+ * model, the state is copied from the stack to the TCB, but only a
+ * referenced is passed to get the state from the TCB.
+ */
+
+#define up_restorestate(regs) (current_regs = regs)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+typedef void (*up_vector_t)(void);
+#endif
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+/* This holds a references to the current interrupt level register storage
+ * structure. If is non-NULL only during interrupt processing.
+ */
+
+extern volatile uint32_t *current_regs;
+
+/* This is the beginning of heap as provided from up_head.S. This is the first
+ * address in DRAM after the loaded program+bss+idle stack. The end of the
+ * heap is CONFIG_DRAM_END
+ */
+
+extern uint32_t g_heapbase;
+
+/* Address of the saved user stack pointer */
+
+#if CONFIG_ARCH_INTERRUPTSTACK > 3
+extern uint32_t g_userstack;
+#endif
+
+/* These 'addresses' of these values are setup by the linker script. They are
+ * not actual uint32_t storage locations! They are only used meaningfully in the
+ * following way:
+ *
+ * - The linker script defines, for example, the symbol_sdata.
+ * - The declareion extern uint32_t _sdata; makes C happy. C will believe
+ * that the value _sdata is the address of a uint32_t variable _data (it is
+ * not!).
+ * - We can recoved the linker value then by simply taking the address of
+ * of _data. like: uint32_t *pdata = &_sdata;
+ */
+
+extern uint32_t _stext; /* Start of .text */
+extern uint32_t _etext; /* End_1 of .text + .rodata */
+extern const uint32_t _eronly; /* End+1 of read only section (.text + .rodata) */
+extern uint32_t _sdata; /* Start of .data */
+extern uint32_t _edata; /* End+1 of .data */
+extern uint32_t _sbss; /* Start of .bss */
+extern uint32_t _ebss; /* End+1 of .bss */
+#endif
+
+/****************************************************************************
+ * Inline Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* Defined in files with the same name as the function */
+
+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
+extern void weak_function up_dmainitialize(void);
+#endif
+extern int up_saveusercontext(uint32_t *saveregs);
+extern void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+extern void up_switchcontext(uint32_t *saveregs, uint32_t *restoreregs);
+extern void up_sigdeliver(void);
+extern void up_lowputc(char ch);
+extern void up_puts(const char *str);
+extern void up_lowputs(const char *str);
+
+extern void up_syscall(uint32_t *regs);
+extern void up_registerdump(uint32_t *regs);
+
+/* Defined in up_allocateheap.c */
+
+#if CONFIG_MM_REGIONS > 1
+void up_addregion(void);
+#else
+# define up_addregion()
+#endif
+
+/* Defined in up_serial.c */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+extern void up_earlyserialinit(void);
+extern void up_serialinit(void);
+#else
+# define up_earlyserialinit()
+# define up_serialinit()
+#endif
+
+/* Defined in drivers/lowconsole.c */
+
+#ifdef CONFIG_DEV_LOWCONSOLE
+extern void lowconsole_init(void);
+#else
+# define lowconsole_init()
+#endif
+
+/* Defined in up_watchdog.c */
+
+extern void up_wdtinit(void);
+
+/* Defined in up_timerisr.c */
+
+extern void up_timerinit(void);
+
+/* Defined in up_irq.c */
+
+extern void up_maskack_irq(int irq);
+
+/* Defined in board/up_leds.c */
+
+#ifdef CONFIG_ARCH_LEDS
+extern void up_ledinit(void);
+extern void up_ledon(int led);
+extern void up_ledoff(int led);
+#else
+# define up_ledinit()
+# define up_ledon(led)
+# define up_ledoff(led)
+#endif
+
+/* Defined in board/up_network.c */
+
+#ifdef CONFIG_NET
+extern void up_netinitialize(void);
+#else
+# define up_netinitialize()
+#endif
+
+#ifdef CONFIG_USBDEV
+extern void up_usbinitialize(void);
+extern void up_usbuninitialize(void);
+#else
+# define up_usbinitialize()
+# define up_usbuninitialize()
+#endif
+
+#endif /* __ASSEMBLY__ */
+
+#endif /* __ARCH_X86_SRC_COMMON_UP_INTERNAL_H */
diff --git a/nuttx/arch/x86/src/common/up_interruptcontext.c b/nuttx/arch/x86/src/common/up_interruptcontext.c
new file mode 100644
index 000000000..6fbe67989
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_interruptcontext.c
@@ -0,0 +1,72 @@
+/****************************************************************************
+ * arch/x86/src/common/up_interruptcontext.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 <stdbool.h>
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_interrupt_context
+ *
+ * Description:
+ * Return true is we are currently executing in the interrupt handler
+ * context.
+ *
+ ****************************************************************************/
+
+bool up_interrupt_context(void)
+{
+ return current_regs != NULL;
+}
diff --git a/nuttx/arch/x86/src/common/up_lowputs.c b/nuttx/arch/x86/src/common/up_lowputs.c
new file mode 100644
index 000000000..46c8940cc
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_lowputs.c
@@ -0,0 +1,74 @@
+/****************************************************************************
+ * arch/x86/src/common/up_lowputs.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 "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_lowputs
+ *
+ * Description:
+ * This is a low-level helper function used to support debug.
+ *
+ ****************************************************************************/
+
+void up_lowputs(const char *str)
+{
+ while(*str)
+ {
+ up_lowputc(*str++);
+ }
+}
diff --git a/nuttx/arch/x86/src/common/up_mdelay.c b/nuttx/arch/x86/src/common/up_mdelay.c
new file mode 100644
index 000000000..22fc78d04
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_mdelay.c
@@ -0,0 +1,90 @@
+/****************************************************************************
+ * arch/x86/src/common/up_mdelay.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 <nuttx/arch.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_mdelay
+ *
+ * Description:
+ * Delay inline for the requested number of milliseconds.
+ * *** NOT multi-tasking friendly ***
+ *
+ * ASSUMPTIONS:
+ * The setting CONFIG_BOARD_LOOPSPERMSEC has been calibrated
+ *
+ ****************************************************************************/
+
+void up_mdelay(unsigned int milliseconds)
+{
+ volatile int i;
+ volatile int j;
+
+ for (i = 0; i < milliseconds; i++)
+ {
+ for (j = 0; j < CONFIG_BOARD_LOOPSPERMSEC; j++)
+ {
+ }
+ }
+}
diff --git a/nuttx/arch/x86/src/common/up_modifyreg16.c b/nuttx/arch/x86/src/common/up_modifyreg16.c
new file mode 100644
index 000000000..9a7ae4507
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_modifyreg16.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * arch/x86/src/common/up_modifyreg16.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 <stdint.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/arch.h>
+
+#include "up_arch.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: modifyreg16
+ *
+ * Description:
+ * Atomically modify the specified bits in a memory mapped register
+ *
+ ****************************************************************************/
+
+void modifyreg16(unsigned int addr, uint16_t clearbits, uint16_t setbits)
+{
+ irqstate_t flags;
+ uint16_t regval;
+
+ flags = irqsave();
+ regval = getreg16((uint16_t)addr);
+ regval &= ~clearbits;
+ regval |= setbits;
+ putreg16(regval, (uint16_t)addr);
+ irqrestore(flags);
+}
diff --git a/nuttx/arch/x86/src/common/up_modifyreg32.c b/nuttx/arch/x86/src/common/up_modifyreg32.c
new file mode 100644
index 000000000..c2a400335
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_modifyreg32.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * arch/x86/src/common/up_modifyreg32.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 <stdint.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/arch.h>
+
+#include "up_arch.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: modifyreg32
+ *
+ * Description:
+ * Atomically modify the specified bits in a memory mapped register
+ *
+ ****************************************************************************/
+
+void modifyreg32(unsigned int addr, uint32_t clearbits, uint32_t setbits)
+{
+ irqstate_t flags;
+ uint32_t regval;
+
+ flags = irqsave();
+ regval = getreg32((uint16_t)addr);
+ regval &= ~clearbits;
+ regval |= setbits;
+ putreg32(regval, (uint16_t)addr);
+ irqrestore(flags);
+}
diff --git a/nuttx/arch/x86/src/common/up_modifyreg8.c b/nuttx/arch/x86/src/common/up_modifyreg8.c
new file mode 100644
index 000000000..fd4031dc5
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_modifyreg8.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * arch/x86/src/common/up_modifyreg8.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 <stdint.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/arch.h>
+
+#include "up_arch.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: modifyreg8
+ *
+ * Description:
+ * Atomically modify the specified bits in a memory mapped register
+ *
+ ****************************************************************************/
+
+void modifyreg8(unsigned int addr, uint8_t clearbits, uint8_t setbits)
+{
+ irqstate_t flags;
+ uint8_t regval;
+
+ flags = irqsave();
+ regval = getreg8((uint16_t)addr);
+ regval &= ~clearbits;
+ regval |= setbits;
+ putreg8(regval, (uint16_t)addr);
+ irqrestore(flags);
+}
diff --git a/nuttx/arch/x86/src/common/up_puts.c b/nuttx/arch/x86/src/common/up_puts.c
new file mode 100644
index 000000000..58420c598
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_puts.c
@@ -0,0 +1,75 @@
+/****************************************************************************
+ * arch/x86/src/common/up_puts.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 <nuttx/arch.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_puts
+ *
+ * Description:
+ * This is a low-level helper function used to support debug.
+ *
+ ****************************************************************************/
+
+void up_puts(const char *str)
+{
+ while(*str)
+ {
+ up_putc(*str++);
+ }
+}
diff --git a/nuttx/arch/x86/src/common/up_releasepending.c b/nuttx/arch/x86/src/common/up_releasepending.c
new file mode 100755
index 000000000..f476837da
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_releasepending.c
@@ -0,0 +1,132 @@
+/****************************************************************************
+ * arch/arm/src/arm/up_releasepending.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 <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_release_pending
+ *
+ * Description:
+ * Release and ready-to-run tasks that have
+ * collected in the pending task list. This can call a
+ * context switch if a new task is placed at the head of
+ * the ready to run list.
+ *
+ ****************************************************************************/
+
+void up_release_pending(void)
+{
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+
+ slldbg("From TCB=%p\n", rtcb);
+
+ /* Merge the g_pendingtasks list into the g_readytorun task list */
+
+ /* sched_lock(); */
+ if (sched_mergepending())
+ {
+ /* The currently active task has changed! We will need to
+ * switch contexts. First check if we are operating in
+ * interrupt context:
+ */
+
+ if (current_regs)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current_regs into the OLD rtcb.
+ */
+
+ up_savestate(rtcb->xcp.regs);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+ slldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_restorestate(rtcb->xcp.regs);
+ }
+
+ /* Copy the exception context into the TCB of the task that
+ * was currently active. if up_saveusercontext returns a non-zero
+ * value, then this is really the previously running task
+ * restarting!
+ */
+
+ else if (!up_saveusercontext(rtcb->xcp.regs))
+ {
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+ slldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_fullcontextrestore(rtcb->xcp.regs);
+ }
+ }
+}
diff --git a/nuttx/arch/x86/src/common/up_reprioritizertr.c b/nuttx/arch/x86/src/common/up_reprioritizertr.c
new file mode 100755
index 000000000..5df8c26b0
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_reprioritizertr.c
@@ -0,0 +1,187 @@
+/****************************************************************************
+ * arch/arm/src/arm/up_reprioritizertr.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 <stdint.h>
+#include <stdbool.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_reprioritize_rtr
+ *
+ * Description:
+ * Called when the priority of a running or
+ * ready-to-run task changes and the reprioritization will
+ * cause a context switch. Two cases:
+ *
+ * 1) The priority of the currently running task drops and the next
+ * task in the ready to run list has priority.
+ * 2) An idle, ready to run task's priority has been raised above the
+ * the priority of the current, running task and it now has the
+ * priority.
+ *
+ * Inputs:
+ * tcb: The TCB of the task that has been reprioritized
+ * priority: The new task priority
+ *
+ ****************************************************************************/
+
+void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
+{
+ /* Verify that the caller is sane */
+
+ if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > 0
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
+ {
+ PANIC(OSERR_BADREPRIORITIZESTATE);
+ }
+ else
+ {
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+ bool switch_needed;
+
+ slldbg("TCB=%p PRI=%d\n", tcb, priority);
+
+ /* Remove the tcb task from the ready-to-run list.
+ * sched_removereadytorun will return true if we just
+ * remove the head of the ready to run list.
+ */
+
+ switch_needed = sched_removereadytorun(tcb);
+
+ /* Setup up the new task priority */
+
+ tcb->sched_priority = (uint8_t)priority;
+
+ /* Return the task to the specified blocked task list.
+ * sched_addreadytorun will return true if the task was
+ * added to the new list. We will need to perform a context
+ * switch only if the EXCLUSIVE or of the two calls is non-zero
+ * (i.e., one and only one the calls changes the head of the
+ * ready-to-run list).
+ */
+
+ switch_needed ^= sched_addreadytorun(tcb);
+
+ /* Now, perform the context switch if one is needed */
+
+ if (switch_needed)
+ {
+ /* If we are going to do a context switch, then now is the right
+ * time to add any pending tasks back into the ready-to-run list.
+ * task list now
+ */
+
+ if (g_pendingtasks.head)
+ {
+ sched_mergepending();
+ }
+
+ /* Are we in an interrupt handler? */
+
+ if (current_regs)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current_regs into the OLD rtcb.
+ */
+
+ up_savestate(rtcb->xcp.regs);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+ slldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_restorestate(rtcb->xcp.regs);
+ }
+
+ /* Copy the exception context into the TCB at the (old) head of the
+ * g_readytorun Task list. if up_saveusercontext returns a non-zero
+ * value, then this is really the previously running task restarting!
+ */
+
+ else if (!up_saveusercontext(rtcb->xcp.regs))
+ {
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+ slldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_fullcontextrestore(rtcb->xcp.regs);
+ }
+ }
+ }
+}
diff --git a/nuttx/arch/x86/src/common/up_udelay.c b/nuttx/arch/x86/src/common/up_udelay.c
new file mode 100644
index 000000000..92d3b7c16
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_udelay.c
@@ -0,0 +1,129 @@
+/****************************************************************************
+ * arch/x86/src/common/up_udelay.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 <sys/types.h>
+#include <nuttx/arch.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define CONFIG_BOARD_LOOPSPER100USEC ((CONFIG_BOARD_LOOPSPERMSEC+5)/10)
+#define CONFIG_BOARD_LOOPSPER10USEC ((CONFIG_BOARD_LOOPSPERMSEC+50)/100)
+#define CONFIG_BOARD_LOOPSPERUSEC ((CONFIG_BOARD_LOOPSPERMSEC+500)/1000)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_udelay
+ *
+ * Description:
+ * Delay inline for the requested number of microseconds. NOTE: Because
+ * of all of the setup, several microseconds will be lost before the actual
+ * timing looop begins. Thus, the delay will always be a few microseconds
+ * longer than requested.
+ *
+ * *** NOT multi-tasking friendly ***
+ *
+ * ASSUMPTIONS:
+ * The setting CONFIG_BOARD_LOOPSPERMSEC has been calibrated
+ *
+ ****************************************************************************/
+
+void up_udelay(useconds_t microseconds)
+{
+ volatile int i;
+
+ /* We'll do this a little at a time because we expect that the
+ * CONFIG_BOARD_LOOPSPERUSEC is very inaccurate during to truncation in
+ * the divisions of its calculation. We'll use the largest values that
+ * we can in order to prevent significant error buildup in the loops.
+ */
+
+ while (microseconds > 1000)
+ {
+ for (i = 0; i < CONFIG_BOARD_LOOPSPERMSEC; i++)
+ {
+ }
+ microseconds -= 1000;
+ }
+
+ while (microseconds > 100)
+ {
+ for (i = 0; i < CONFIG_BOARD_LOOPSPER100USEC; i++)
+ {
+ }
+ microseconds -= 100;
+ }
+
+ while (microseconds > 10)
+ {
+ for (i = 0; i < CONFIG_BOARD_LOOPSPER10USEC; i++)
+ {
+ }
+ microseconds -= 10;
+ }
+
+ while (microseconds > 0)
+ {
+ for (i = 0; i < CONFIG_BOARD_LOOPSPERUSEC; i++)
+ {
+ }
+ microseconds--;
+ }
+}
diff --git a/nuttx/arch/x86/src/common/up_unblocktask.c b/nuttx/arch/x86/src/common/up_unblocktask.c
new file mode 100755
index 000000000..7dd263f1a
--- /dev/null
+++ b/nuttx/arch/x86/src/common/up_unblocktask.c
@@ -0,0 +1,158 @@
+/****************************************************************************
+ * arch/x86/src/common/up_unblocktask.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 <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "clock_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_unblock_task
+ *
+ * Description:
+ * A task is currently in an inactive task list but has been prepped to
+ * execute. Move the TCB to the ready-to-run list, restore its context,
+ * and start execution.
+ *
+ * Inputs:
+ * tcb: Refers to the tcb to be unblocked. This tcb is in one of the
+ * waiting tasks lists. It must be moved to the ready-to-run list and,
+ * if it is the highest priority ready to run taks, executed.
+ *
+ ****************************************************************************/
+
+void up_unblock_task(_TCB *tcb)
+{
+ /* Verify that the context switch can be performed */
+
+ if ((tcb->task_state < FIRST_BLOCKED_STATE) ||
+ (tcb->task_state > LAST_BLOCKED_STATE))
+ {
+ PANIC(OSERR_BADUNBLOCKSTATE);
+ }
+ else
+ {
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+
+ /* Remove the task from the blocked task list */
+
+ sched_removeblocked(tcb);
+
+ /* Reset its timeslice. This is only meaningful for round
+ * robin tasks but it doesn't here to do it for everything
+ */
+
+#if CONFIG_RR_INTERVAL > 0
+ tcb->timeslice = CONFIG_RR_INTERVAL / MSEC_PER_TICK;
+#endif
+
+ /* Add the task in the correct location in the prioritized
+ * g_readytorun task list
+ */
+
+ if (sched_addreadytorun(tcb))
+ {
+ /* The currently active task has changed! We need to do
+ * a context switch to the new task.
+ *
+ * Are we in an interrupt handler?
+ */
+
+ if (current_regs)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current_regs into the OLD rtcb.
+ */
+
+ up_savestate(rtcb->xcp.regs);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+
+ /* Then switch contexts */
+
+ up_restorestate(rtcb->xcp.regs);
+ }
+
+ /* We are not in an interrupt handler. Copy the user C context
+ * into the TCB of the task that was previously active. if
+ * up_saveusercontext returns a non-zero value, then this is really the
+ * previously running task restarting!
+ */
+
+ else if (!up_saveusercontext(rtcb->xcp.regs))
+ {
+ /* Restore the exception context of the new task that is ready to
+ * run (probably tcb). This is the new rtcb at the head of the
+ * g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+
+ /* Then switch contexts */
+
+ up_fullcontextrestore(rtcb->xcp.regs);
+ }
+ }
+ }
+}
diff --git a/nuttx/arch/x86/src/i486/i486_utils.S b/nuttx/arch/x86/src/i486/i486_utils.S
new file mode 100644
index 000000000..ee89c0c68
--- /dev/null
+++ b/nuttx/arch/x86/src/i486/i486_utils.S
@@ -0,0 +1,96 @@
+/****************************************************************************
+ * arch/x86/src/i486/i486_utils.S
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Based on Bran's kernel development tutorials. Rewritten for JamesM's
+ * kernel development tutorials.
+ *
+ * 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>
+
+ .file "i486_utils.S"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+ #define KSEG 0x10
+
+/****************************************************************************
+ * Globals
+ ****************************************************************************/
+
+ .globl gdt_flush
+ .globl idt_flush
+
+/****************************************************************************
+ * .text
+ ****************************************************************************/
+
+ .text
+
+/****************************************************************************
+ * Name: gdt_flush
+ ****************************************************************************/
+
+ .type gdt_flush, @function
+gdt_flush:
+ movl %eax, 4(%esp) /* Get the pointer to the GDT, passed as a parameter */
+ lgdt (%eax) /* Load the new GDT pointer */
+
+ mov $KSEG, %ax /* KSEG is the offset in the GDT to our data segment */
+ mov %ax, %ds /* Load all data segment selectors */
+ mov %ax, %es
+ mov %ax, %fs
+ mov %ax, %gs
+ mov %ax, %ss
+ jmp $0x08, $.Lgflush /* 0x08 is the offset to our code segment: Far jump! */
+.Lgflush:
+ ret
+ .size gdt_flush, . - gdt_flush
+
+/****************************************************************************
+ * Name: idt_flush
+ ****************************************************************************/
+
+ .type idt_flush, @function
+idt_flush:
+ movl %eax, 4(%esp) /* Get the pointer to the IDT, passed as a parameter */
+ lidt (%eax) /* Load the IDT pointer */
+ ret
+ .size idt_flush, . - idt_flush
+ .end
diff --git a/nuttx/arch/x86/src/i486/up_createstack.c b/nuttx/arch/x86/src/i486/up_createstack.c
new file mode 100644
index 000000000..842872d31
--- /dev/null
+++ b/nuttx/arch/x86/src/i486/up_createstack.c
@@ -0,0 +1,135 @@
+/****************************************************************************
+ * arch/x86/src/i486/up_createstack.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 <sys/types.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_create_stack
+ *
+ * Description:
+ * Allocate a stack for a new thread and setup up stack-related information
+ * in the TCB.
+ *
+ * The following TCB fields must be initialized:
+ * adj_stack_size: Stack size after adjustment for hardware, processor,
+ * etc. This value is retained only for debug purposes.
+ * stack_alloc_ptr: Pointer to allocated stack
+ * adj_stack_ptr: Adjusted stack_alloc_ptr for HW. The initial value of
+ * the stack pointer.
+ *
+ * Inputs:
+ * tcb: The TCB of new task
+ * stack_size: The requested stack size. At least this much must be
+ * allocated.
+ *
+ ****************************************************************************/
+
+int up_create_stack(_TCB *tcb, size_t stack_size)
+{
+ if (tcb->stack_alloc_ptr && tcb->adj_stack_size != stack_size)
+ {
+ sched_free(tcb->stack_alloc_ptr);
+ tcb->stack_alloc_ptr = NULL;
+ }
+
+ if (!tcb->stack_alloc_ptr)
+ {
+#ifdef CONFIG_DEBUG
+ tcb->stack_alloc_ptr = (uint32_t*)zalloc(stack_size);
+#else
+ tcb->stack_alloc_ptr = (uint32_t*)malloc(stack_size);
+#endif
+ }
+
+ if (tcb->stack_alloc_ptr)
+ {
+ size_t top_of_stack;
+ size_t size_of_stack;
+
+ /* The i486 uses a push-down stack: the stack grows toward lower
+ * addresses in memory. The stack pointer register, points to the
+ * lowest, valid work address (the "top" of the stack). Items on
+ * the stack are referenced as positive word offsets from sp.
+ */
+
+ top_of_stack = (uint32_t)tcb->stack_alloc_ptr + stack_size - 4;
+
+ /* The i486 stack must be aligned at word (4 byte) boundaries. If
+ * necessary top_of_stack must be rounded down to the next boundary
+ */
+
+ top_of_stack &= ~3;
+ size_of_stack = top_of_stack - (uint32_t)tcb->stack_alloc_ptr + 4;
+
+ /* Save the adjusted stack values in the _TCB */
+
+ tcb->adj_stack_ptr = (uint32_t*)top_of_stack;
+ tcb->adj_stack_size = size_of_stack;
+
+ up_ledon(LED_STACKCREATED);
+ return OK;
+ }
+
+ return ERROR;
+}
diff --git a/nuttx/arch/x86/src/i486/up_initialstate.c b/nuttx/arch/x86/src/i486/up_initialstate.c
new file mode 100644
index 000000000..c1bb422da
--- /dev/null
+++ b/nuttx/arch/x86/src/i486/up_initialstate.c
@@ -0,0 +1,126 @@
+/****************************************************************************
+ * arch/x86/src/i486/up_initialstate.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 <stdint.h>
+#include <string.h>
+
+#include <nuttx/arch.h>
+#include <arch/arch.h>
+
+#include "up_internal.h"
+#include "up_arch.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_initial_state
+ *
+ * Description:
+ * A new thread is being started and a new TCB has been created. This
+ * function is called to initialize the processor specific portions of the
+ * new TCB.
+ *
+ * This function must setup the intial architecture registers and/or stack
+ * so that execution will begin at tcb->start on the next context switch.
+ *
+ ****************************************************************************/
+
+void up_initial_state(_TCB *tcb)
+{
+ struct xcptcontext *xcp = &tcb->xcp;
+
+ /* Initialize the initial exception register context structure */
+
+ memset(xcp, 0, sizeof(struct xcptcontext));
+
+ /* 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;
+
+ /* Save the task entry point */
+
+ xcp->regs[REG_EIP] = (uint32_t)tcb->start;
+
+ /* Set up the segment registers... assume the same segment as the caller.
+ * That is not a good assumption in the long run.
+ */
+
+ xcp->regs[REG_DS] = up_getds();
+ xcp->regs[REG_CS] = up_getcs();
+ xcp->regs[REG_SS] = up_getss();
+
+ /* Set supervisor- or user-mode, depending on how NuttX is configured and
+ * what kind of thread is being started. Disable FIQs in any event
+ *
+ * If the kernel build is not selected, then all threads run in
+ * supervisor-mode.
+ */
+
+#ifdef CONFIG_NUTTX_KERNEL
+# error "Missing logic for the CONFIG_NUTTX_KERNEL build"
+#endif
+
+ /* Enable or disable interrupts, based on user configuration. If the IF
+ * bit is set, maskable interrupts will be enabled.
+ */
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+ xcp->regs[REG_EFLAGS] = X86_FLAGS_IF;
+#endif
+}
+
diff --git a/nuttx/arch/x86/src/i486/up_irq.c b/nuttx/arch/x86/src/i486/up_irq.c
new file mode 100755
index 000000000..01da4962e
--- /dev/null
+++ b/nuttx/arch/x86/src/i486/up_irq.c
@@ -0,0 +1,376 @@
+/****************************************************************************
+ * arch/x86/src/i486/up_irq.c
+ * arch/x86/src/chip/up_irq.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 <stdint.h>
+#include <string.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <arch/irq.h>
+#include <arch/io.h>
+
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+#include "qemu_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static void idt_outb(uint8_t val, uint16_t addr) __attribute__((noinline));
+static void up_remappic(void);
+static void up_idtentry(unsigned int index, uint32_t base, uint16_t sel,
+ uint8_t flags);
+static inline void up_idtinit(void);
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+volatile uint32_t *current_regs;
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct idt_entry_s idt_entries[256];
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name idt_outb
+ *
+ * Description:
+ * A slightly slower version of outb
+ *
+ ****************************************************************************/
+
+static void idt_outb(uint8_t val, uint16_t addr)
+{
+ outb(val, addr);
+}
+
+/****************************************************************************
+ * Name up_remappic
+ *
+ * Description:
+ * Remap the PIC. The Programmable Interrupt Controller (PIC) is used to
+ * combine several sources of interrupt onto one or more CPU lines, while
+ * allowing priority levels to be assigned to its interrupt outputs. When
+ * the device has multiple interrupt outputs to assert, it will assert them
+ * in the order of their relative priority.
+ *
+ ****************************************************************************/
+
+static void up_remappic(void)
+{
+ /* Mask interrupts from PIC */
+
+ idt_outb(PIC1_IMR_ALL, PIC1_IMR);
+ idt_outb(PIC2_IMR_ALL, PIC2_IMR);
+
+ /* If the PIC has been reset, it must be initialized with 2 to 4 Initialization
+ * Command Words (ICW) before it will accept and process Interrupt Requests. The
+ * following outlines the four possible Initialization Command Words.
+ */
+
+ /* Remap the irq table for primary:
+ *
+ * ICW1 - We will be sending ICW4
+ * ICW2 - Address
+ * ICW3 */
+
+ idt_outb(PIC_ICW1_ICW4|PIC_ICW1_ICW1, PIC1_ICW1);
+ idt_outb(0x20, PIC1_ICW2);
+ idt_outb(PIC1_ICW3_IRQ2, PIC1_ICW3);
+ idt_outb(PIC_ICW4_808xMODE, PIC1_ICW4);
+
+ /* Remap irq for slave */
+
+ idt_outb(PIC_ICW1_ICW4|PIC_ICW1_ICW1, PIC2_ICW1);
+ idt_outb(0x28, PIC2_ICW2);
+ idt_outb(PIC_ICW3_SID2, PIC2_ICW3);
+ idt_outb(PIC_ICW4_808xMODE, PIC2_ICW4);
+
+ /* Mask interrupts from PIC */
+
+ idt_outb(PIC1_IMR_ALL, PIC1_IMR);
+ idt_outb(PIC2_IMR_ALL, PIC2_IMR);
+}
+
+/****************************************************************************
+ * Name up_idtentry
+ *
+ * Description:
+ * Initialize one IDT entry.
+ *
+ ****************************************************************************/
+
+static void up_idtentry(unsigned int index, uint32_t base, uint16_t sel,
+ uint8_t flags)
+{
+ struct idt_entry_s *entry = &idt_entries[index];
+
+ entry->lobase = base & 0xffff;
+ entry->hibase = (base >> 16) & 0xffff;
+
+ entry->sel = sel;
+ entry->zero = 0;
+
+ /* We must uncomment the OR below when we get to using user-mode. It sets the
+ * interrupt gate's privilege level to 3.
+ */
+
+ entry->flags = flags /* | 0x60 */;
+}
+
+/****************************************************************************
+ * Name up_idtinit
+ *
+ * Description:
+ * Initialize the IDT. The Interrupt Descriptor Table (IDT) is a data
+ * structure used by the x86 architecture to implement an interrupt vector
+ * table. The IDT is used by the processor to determine the correct
+ * response to interrupts and exceptions.
+ *
+ ****************************************************************************/
+
+static inline void up_idtinit(void)
+{
+ struct idt_ptr_s idt_ptr;
+
+ idt_ptr.limit = sizeof(struct idt_entry_s) * 256 - 1;
+ idt_ptr.base = (uint32_t)&idt_entries;
+
+ memset(&idt_entries, 0, sizeof(struct idt_entry_s)*256);
+
+ /* Re-map the PIC */
+
+ up_remappic();
+
+ /* Set each ISR/IRQ to the appropriate vector with selector=8 and with
+ * 32-bit interrupt gate. Interrupt gate (vs. trap gate) will leave
+ * interrupts enabled when the IRS/IRQ handler is entered.
+ */
+
+ up_idtentry(ISR0, (uint32_t)vector_isr0 , 0x08, 0x8e);
+ up_idtentry(ISR1, (uint32_t)vector_isr1 , 0x08, 0x8e);
+ up_idtentry(ISR2, (uint32_t)vector_isr2 , 0x08, 0x8e);
+ up_idtentry(ISR3, (uint32_t)vector_isr3 , 0x08, 0x8e);
+ up_idtentry(ISR4, (uint32_t)vector_isr4 , 0x08, 0x8e);
+ up_idtentry(ISR5, (uint32_t)vector_isr5 , 0x08, 0x8e);
+ up_idtentry(ISR6, (uint32_t)vector_isr6 , 0x08, 0x8e);
+ up_idtentry(ISR7, (uint32_t)vector_isr7 , 0x08, 0x8e);
+ up_idtentry(ISR8, (uint32_t)vector_isr8 , 0x08, 0x8e);
+ up_idtentry(ISR9, (uint32_t)vector_isr9 , 0x08, 0x8e);
+ up_idtentry(ISR10, (uint32_t)vector_isr10, 0x08, 0x8e);
+ up_idtentry(ISR11, (uint32_t)vector_isr11, 0x08, 0x8e);
+ up_idtentry(ISR12, (uint32_t)vector_isr12, 0x08, 0x8e);
+ up_idtentry(ISR13, (uint32_t)vector_isr13, 0x08, 0x8e);
+ up_idtentry(ISR14, (uint32_t)vector_isr14, 0x08, 0x8e);
+ up_idtentry(ISR15, (uint32_t)vector_isr15, 0x08, 0x8e);
+ up_idtentry(ISR16, (uint32_t)vector_isr16, 0x08, 0x8e);
+ up_idtentry(ISR17, (uint32_t)vector_isr17, 0x08, 0x8e);
+ up_idtentry(ISR18, (uint32_t)vector_isr18, 0x08, 0x8e);
+ up_idtentry(ISR19, (uint32_t)vector_isr19, 0x08, 0x8e);
+ up_idtentry(ISR20, (uint32_t)vector_isr20, 0x08, 0x8e);
+ up_idtentry(ISR21, (uint32_t)vector_isr21, 0x08, 0x8e);
+ up_idtentry(ISR22, (uint32_t)vector_isr22, 0x08, 0x8e);
+ up_idtentry(ISR23, (uint32_t)vector_isr23, 0x08, 0x8e);
+ up_idtentry(ISR24, (uint32_t)vector_isr24, 0x08, 0x8e);
+ up_idtentry(ISR25, (uint32_t)vector_isr25, 0x08, 0x8e);
+ up_idtentry(ISR26, (uint32_t)vector_isr26, 0x08, 0x8e);
+ up_idtentry(ISR27, (uint32_t)vector_isr27, 0x08, 0x8e);
+ up_idtentry(ISR28, (uint32_t)vector_isr28, 0x08, 0x8e);
+ up_idtentry(ISR29, (uint32_t)vector_isr29, 0x08, 0x8e);
+ up_idtentry(ISR30, (uint32_t)vector_isr30, 0x08, 0x8e);
+ up_idtentry(ISR31, (uint32_t)vector_isr31, 0x08, 0x8e);
+
+ up_idtentry(IRQ0, (uint32_t)vector_irq0, 0x08, 0x8e);
+ up_idtentry(IRQ1, (uint32_t)vector_irq1, 0x08, 0x8e);
+ up_idtentry(IRQ2, (uint32_t)vector_irq2, 0x08, 0x8e);
+ up_idtentry(IRQ3, (uint32_t)vector_irq3, 0x08, 0x8e);
+ up_idtentry(IRQ4, (uint32_t)vector_irq4, 0x08, 0x8e);
+ up_idtentry(IRQ5, (uint32_t)vector_irq5, 0x08, 0x8e);
+ up_idtentry(IRQ6, (uint32_t)vector_irq6, 0x08, 0x8e);
+ up_idtentry(IRQ7, (uint32_t)vector_irq7, 0x08, 0x8e);
+ up_idtentry(IRQ8, (uint32_t)vector_irq8, 0x08, 0x8e);
+ up_idtentry(IRQ9, (uint32_t)vector_irq9, 0x08, 0x8e);
+ up_idtentry(IRQ10, (uint32_t)vector_irq10, 0x08, 0x8e);
+ up_idtentry(IRQ11, (uint32_t)vector_irq11, 0x08, 0x8e);
+ up_idtentry(IRQ12, (uint32_t)vector_irq12, 0x08, 0x8e);
+ up_idtentry(IRQ13, (uint32_t)vector_irq13, 0x08, 0x8e);
+ up_idtentry(IRQ14, (uint32_t)vector_irq14, 0x08, 0x8e);
+ up_idtentry(IRQ15, (uint32_t)vector_irq15, 0x08, 0x8e);
+
+ /* Then program the IDT */
+
+ idt_flush((uint32_t)&idt_ptr);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_irqinitialize
+ ****************************************************************************/
+
+void up_irqinitialize(void)
+{
+ /* currents_regs is non-NULL only while processing an interrupt */
+
+ current_regs = NULL;
+
+ /* Initialize the IDT */
+
+ up_idtinit();
+
+ /* And finally, enable interrupts */
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+ irqrestore(X86_FLAGS_IF);
+#endif
+}
+
+/****************************************************************************
+ * Name: up_disable_irq
+ *
+ * Description:
+ * Disable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_disable_irq(int irq)
+{
+ unsigned int regaddr;
+ uint8_t regbit;
+
+ if (irq >= IRQ0)
+ {
+ /* Map the IRQ IMR regiser to a PIC and a bit number */
+
+ if (irq <= IRQ7)
+ {
+ regaddr = PIC1_IMR;
+ regbit = (1 << (irq - IRQ0));
+ }
+ else if (irq <= IRQ15)
+ {
+ regaddr = PIC2_IMR;
+ regbit = (1 << (irq - IRQ8));
+ }
+ else
+ {
+ return;
+ }
+
+ /* Disable (mask) the interrupt */
+
+ modifyreg8(regaddr, 0, regbit);
+ }
+}
+
+/****************************************************************************
+ * Name: up_enable_irq
+ *
+ * Description:
+ * Enable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_enable_irq(int irq)
+{
+ unsigned int regaddr;
+ uint8_t regbit;
+
+ if (irq >= IRQ0)
+ {
+ /* Map the IRQ IMR regiser to a PIC and a bit number */
+
+ if (irq <= IRQ7)
+ {
+ regaddr = PIC1_IMR;
+ regbit = (1 << (irq - IRQ0));
+ }
+ else if (irq <= IRQ15)
+ {
+ regaddr = PIC2_IMR;
+ regbit = (1 << (irq - IRQ8));
+ }
+ else
+ {
+ return;
+ }
+
+ /* Enable (unmask) the interrupt */
+
+ modifyreg8(regaddr, regbit, 0);
+ }
+}
+
+/****************************************************************************
+ * Name: up_prioritize_irq
+ *
+ * Description:
+ * Set the priority of an IRQ.
+ *
+ * Since this API is not supported on all architectures, it should be
+ * avoided in common implementations where possible.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_IRQPRIO
+int up_prioritize_irq(int irq, int priority)
+{
+#warning "Missing Logic"
+ return OK;
+}
+#endif
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..5a5da0e70
--- /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 <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 <nuttx/irq.h>
+
+#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/i486/up_releasestack.c b/nuttx/arch/x86/src/i486/up_releasestack.c
new file mode 100644
index 000000000..ac93688d6
--- /dev/null
+++ b/nuttx/arch/x86/src/i486/up_releasestack.c
@@ -0,0 +1,79 @@
+/****************************************************************************
+ * arch/x86/src/common/up_releasestack.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 <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_release_stack
+ *
+ * Description:
+ * A task has been stopped. Free all stack related resources retained in
+ * the defunct TCB.
+ *
+ ****************************************************************************/
+
+void up_release_stack(_TCB *dtcb)
+{
+ if (dtcb->stack_alloc_ptr)
+ {
+ sched_free(dtcb->stack_alloc_ptr);
+ dtcb->stack_alloc_ptr = NULL;
+ }
+
+ dtcb->adj_stack_size = 0;
+}
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..1d35c62a9
--- /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, (uint32_t*)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/i486/up_schedulesigaction.c b/nuttx/arch/x86/src/i486/up_schedulesigaction.c
new file mode 100644
index 000000000..7d91bb3e3
--- /dev/null
+++ b/nuttx/arch/x86/src/i486/up_schedulesigaction.c
@@ -0,0 +1,198 @@
+/****************************************************************************
+ * arch/x86/src/i486/up_schedulesigaction.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 <stdint.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#ifndef CONFIG_DISABLE_SIGNALS
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_schedule_sigaction
+ *
+ * Description:
+ * This function is called by the OS when one or more signal handling
+ * actions have been queued for execution. The architecture specific code
+ * must configure things so that the 'sigdeliver' callback is executed on
+ * the thread specified by 'tcb' as soon as possible.
+ *
+ * This function may be called from interrupt handling logic.
+ *
+ * This operation should not cause the task to be unblocked nor should it
+ * cause any immediate execution of sigdeliver. Typically, a few cases need
+ * to be considered:
+ *
+ * (1) This function may be called from an interrupt handler. During
+ * interrupt processing, all xcptcontext structures should be valid for
+ * all tasks. That structure should be modified to invoke sigdeliver()
+ * either on return from (this) interrupt or on some subsequent context
+ * switch to the recipient task.
+ * (2) If not in an interrupt handler and the tcb is NOT the currently
+ * executing task, then again just modify the saved xcptcontext
+ * structure for the recipient task so it will invoke sigdeliver when
+ * that task is later resumed.
+ * (3) If not in an interrupt handler and the tcb IS the currently
+ * executing task -- just call the signal handler now.
+ *
+ ****************************************************************************/
+
+void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
+{
+ /* Refuse to handle nested signal actions */
+
+ sdbg("tcb=0x%p sigdeliver=0x%p\n", tcb, sigdeliver);
+
+ if (!tcb->xcp.sigdeliver)
+ {
+ irqstate_t flags;
+
+ /* Make sure that interrupts are disabled */
+
+ flags = irqsave();
+
+ /* First, handle some special cases when the signal is being delivered
+ * to the currently executing task.
+ */
+
+ sdbg("rtcb=0x%p current_regs=0x%p\n", g_readytorun.head, current_regs);
+
+ if (tcb == (_TCB*)g_readytorun.head)
+ {
+ /* CASE 1: We are not in an interrupt handler and a task is
+ * signalling itself for some reason.
+ */
+
+ if (!current_regs)
+ {
+ /* In this case just deliver the signal now. */
+
+ sigdeliver(tcb);
+ }
+
+ /* CASE 2: We are in an interrupt handler AND the interrupted task
+ * is the same as the one that must receive the signal, then we will
+ * have to modify the return state as well as the state in the TCB.
+ *
+ * Hmmm... there looks like a latent bug here: The following logic
+ * would fail in the strange case where we are in an interrupt
+ * handler, the thread is signalling itself, but a context switch to
+ * another task has occurred so that current_regs does not refer to
+ * the thread at g_readytorun.head!
+ */
+
+ else
+ {
+ /* Save the return lr and cpsr and one scratch register. These
+ * will be restored by the signal trampoline after the signals
+ * have been delivered.
+ */
+
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_eip = current_regs[REG_EIP];
+ tcb->xcp.saved_eflags = current_regs[REG_EFLAGS];
+
+ /* Then set up to vector to the trampoline with interrupts
+ * disabled
+ */
+
+ current_regs[REG_EIP] = (uint32_t)up_sigdeliver;
+ current_regs[REG_EFLAGS] = 0;
+
+ /* And make sure that the saved context in the TCB
+ * is the same as the interrupt return context.
+ */
+
+ up_savestate(tcb->xcp.regs);
+ }
+ }
+
+ /* Otherwise, we are (1) signaling a task is not running
+ * from an interrupt handler or (2) we are not in an
+ * interrupt handler and the running task is signalling
+ * some non-running task.
+ */
+
+ else
+ {
+ /* Save the return lr and cpsr and one scratch register
+ * These will be restored by the signal trampoline after
+ * the signals have been delivered.
+ */
+
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_eip = tcb->xcp.regs[REG_EIP];
+ tcb->xcp.saved_eflags = tcb->xcp.regs[REG_EFLAGS];
+
+ /* Then set up to vector to the trampoline with interrupts
+ * disabled
+ */
+
+ tcb->xcp.regs[REG_EIP] = (uint32_t)up_sigdeliver;
+ tcb->xcp.regs[REG_EFLAGS] = 0;
+ }
+
+ irqrestore(flags);
+ }
+}
+
+#endif /* !CONFIG_DISABLE_SIGNALS */
diff --git a/nuttx/arch/x86/src/i486/up_sigdeliver.c b/nuttx/arch/x86/src/i486/up_sigdeliver.c
new file mode 100644
index 000000000..8dbf46698
--- /dev/null
+++ b/nuttx/arch/x86/src/i486/up_sigdeliver.c
@@ -0,0 +1,139 @@
+/****************************************************************************
+ * arch/x86/src/i486/up_sigdeliver.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 <stdint.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#ifndef CONFIG_DISABLE_SIGNALS
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_sigdeliver
+ *
+ * Description:
+ * This is the a signal handling trampoline. When a signal action was
+ * posted. The task context was mucked with and forced to branch to this
+ * location with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void up_sigdeliver(void)
+{
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+ uint32_t regs[XCPTCONTEXT_REGS];
+ sig_deliver_t sigdeliver;
+
+ /* Save the errno. This must be preserved throughout the signal handling
+ * so that the user code final gets the correct errno value (probably
+ * EINTR).
+ */
+
+ int saved_errno = rtcb->pterrno;
+
+ up_ledon(LED_SIGNAL);
+
+ sdbg("rtcb=%p sigdeliver=%p sigpendactionq.head=%p\n",
+ rtcb, rtcb->xcp.sigdeliver, rtcb->sigpendactionq.head);
+ ASSERT(rtcb->xcp.sigdeliver != NULL);
+
+ /* Save the real return state on the stack. */
+
+ up_copystate(regs, rtcb->xcp.regs);
+ regs[REG_EIP] = rtcb->xcp.saved_eip;
+ regs[REG_EFLAGS] = rtcb->xcp.saved_eflags;
+
+ /* Get a local copy of the sigdeliver function pointer. we do this so that
+ * we can nullify the sigdeliver function pointer in the TCB and accept
+ * more signal deliveries while processing the current pending signals.
+ */
+
+ sigdeliver = rtcb->xcp.sigdeliver;
+ rtcb->xcp.sigdeliver = NULL;
+
+ /* Then restore the task interrupt state */
+
+ irqrestore(regs[REG_EFLAGS]);
+
+ /* Deliver the signals */
+
+ sigdeliver(rtcb);
+
+ /* Output any debug messages BEFORE restoring errno (because they may
+ * alter errno), then disable interrupts again and restore the original
+ * errno that is needed by the user logic (it is probably EINTR).
+ */
+
+ sdbg("Resuming\n");
+ (void)irqsave();
+ rtcb->pterrno = saved_errno;
+
+ /* Then restore the correct state for this thread of execution. */
+
+ up_ledoff(LED_SIGNAL);
+ up_fullcontextrestore(regs);
+}
+
+#endif /* !CONFIG_DISABLE_SIGNALS */
+
diff --git a/nuttx/arch/x86/src/i486/up_syscall6.S b/nuttx/arch/x86/src/i486/up_syscall6.S
new file mode 100755
index 000000000..9c6f879e3
--- /dev/null
+++ b/nuttx/arch/x86/src/i486/up_syscall6.S
@@ -0,0 +1,97 @@
+/****************************************************************************
+ * arch/x86/src/i486/up_syscall6.S
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Based on Bran's kernel development tutorials. Rewritten for JamesM's
+ * kernel development tutorials.
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+ .file "up_syscall6.S"
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Globals
+ ****************************************************************************/
+
+/****************************************************************************
+ * .text
+ ****************************************************************************/
+
+ .text
+
+/****************************************************************************
+ * Name: sys_call6
+ *
+ * C Prototype:
+ * uintptr_t sys_call6(unsigned int nbr, uintptr_t parm1,
+ * uintptr_t parm2, uintptr_t parm3,
+ * uintptr_t parm4, uintptr_t parm5,
+ * uintptr_t parm6);
+ *
+ ****************************************************************************/
+
+ .global sys_call6
+ .type sys_call6, %function
+
+sys_call6:
+ pushl %ebp /* Save ebx, esi, edi, and ebp */
+ pushl %edi
+ pushl %esi
+ pushl %ebx
+
+ movl 44(%esp),%ebp /* Save parm6 in ebp */
+ movl 40(%esp),%edi /* Save parm5 in edi */
+ movl 36(%esp),%esi /* Save parm4 in esi */
+ movl 32(%esp),%edx /* Save parm3 in edx */
+ movl 28(%esp),%ecx /* Save parm2 in ecx */
+ movl 24(%esp),%ebx /* Save parm1 in ebx */
+ movl 20(%esp),%eax /* Save syscall number in eax */
+ int $0x80 /* Execute the trap */
+ /* Return value is in %eax */
+ popl %ebx /* Restore ebx, esi, edi, and ebp */
+ popl %esi
+ popl %edi
+ popl %ebp
+ ret /* And return with result in %eax */
+
+ .size sys_call6,.-sys_call6
+ .end
diff --git a/nuttx/arch/x86/src/i486/up_usestack.c b/nuttx/arch/x86/src/i486/up_usestack.c
new file mode 100644
index 000000000..fb8ded0e1
--- /dev/null
+++ b/nuttx/arch/x86/src/i486/up_usestack.c
@@ -0,0 +1,119 @@
+/****************************************************************************
+ * arch/x86/src/common/up_usestack.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 <sys/types.h>
+#include <stdint.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_use_stack
+ *
+ * Description:
+ * Setup up stack-related information in the TCB using pre-allocated stack
+ * memory
+ *
+ * The following TCB fields must be initialized:
+ * adj_stack_size: Stack size after adjustment for hardware, processor,
+ * etc. This value is retained only for debug purposes.
+ * stack_alloc_ptr: Pointer to allocated stack
+ * adj_stack_ptr: Adjusted stack_alloc_ptr for HW. The initial value of
+ * the stack pointer.
+ *
+ * Inputs:
+ * tcb: The TCB of new task
+ * stack_size: The allocated stack size.
+ *
+ ****************************************************************************/
+
+int up_use_stack(_TCB *tcb, void *stack, size_t stack_size)
+{
+ size_t top_of_stack;
+ size_t size_of_stack;
+
+ if (tcb->stack_alloc_ptr)
+ {
+ sched_free(tcb->stack_alloc_ptr);
+ }
+
+ /* Save the stack allocation */
+
+ tcb->stack_alloc_ptr = stack;
+
+ /* The i486 uses a push-down stack: the stack grows toward loweraddresses in
+ * memory. The stack pointer register, points to the lowest, valid work
+ * address (the "top" of the stack). Items on the stack are referenced as
+ * positive word offsets from sp.
+ */
+
+ top_of_stack = (uint32_t)tcb->stack_alloc_ptr + stack_size - 4;
+
+ /* The i486 stack must be aligned at word (4 byte) boundaries. If necessary
+ * top_of_stack must be rounded down to the next boundary
+ */
+
+ top_of_stack &= ~3;
+ size_of_stack = top_of_stack - (uint32_t)tcb->stack_alloc_ptr + 4;
+
+ /* Save the adjusted stack values in the _TCB */
+
+ tcb->adj_stack_ptr = (uint32_t*)top_of_stack;
+ tcb->adj_stack_size = size_of_stack;
+
+ return OK;
+}
diff --git a/nuttx/arch/x86/src/qemu/Make.defs b/nuttx/arch/x86/src/qemu/Make.defs
new file mode 100755
index 000000000..f4a57128c
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/Make.defs
@@ -0,0 +1,57 @@
+############################################################################
+# arch/x86/src/qemu/Make.defs
+#
+# 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.
+#
+############################################################################
+
+# The start-up, "head", file
+
+HEAD_ASRC = qemu_head.S
+
+# Common x86 and i486 files
+
+CMN_ASRCS = i486_utils.S up_syscall6.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_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_savestate.c up_sigdeliver.c up_schedulesigaction.c up_unblocktask.c \
+ up_usestack.c
+
+# Required QEMU files
+
+CHIP_ASRCS = qemu_saveusercontext.S qemu_fullcontextrestore.S qemu_vectors.S
+CHIP_CSRCS = qemu_handlers.c qemu_idle.c qemu_lowputc.c qemu_lowsetup.c \
+ qemu_serial.c qemu_timerisr.c
+
+# Configuration-dependent QEMU files
diff --git a/nuttx/arch/x86/src/qemu/chip.h b/nuttx/arch/x86/src/qemu/chip.h
new file mode 100755
index 000000000..0cbf26cb3
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/chip.h
@@ -0,0 +1,74 @@
+/************************************************************************************
+ * arch/x86/src/qemu/chip.h
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_X86_SRC_QEMU_QEMU_CHIP_H
+#define __ARCH_X86_SRC_QEMU_QEMU_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Get customizations for each supported QEMU emulation */
+
+#ifdef CONFIG_ARCH_CHIP_QEMU
+#else
+# error "Unsupported STM32 chip"
+#endif
+
+/* Include only the memory map. Other chip hardware files should then include this
+ * file for the proper setup
+ */
+
+#include "qemu_memorymap.h"
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_X86_SRC_QEMU_QEMU_CHIP_H */
diff --git a/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S b/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S
new file mode 100644
index 000000000..ded55a147
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S
@@ -0,0 +1,181 @@
+/**************************************************************************
+ * arch/x86/src/qemu/qemu_fullcontextrestore.S
+ *
+ * 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.
+ *
+ **************************************************************************/
+
+/**************************************************************************
+ * Conditional Compilation Options
+ **************************************************************************/
+
+/**************************************************************************
+ * Included Files
+ **************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/irq.h>
+#include "up_internal.h"
+
+ .file "qemu_fullcontextrestore.S"
+
+/**************************************************************************
+ * Pre-processor Definitions
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/****************************************************************************
+ * Macros
+ ****************************************************************************/
+
+/* Trace macros, use like trace 'i' to print char to serial port. */
+
+ .macro chout, addr, ch
+#ifdef CONFIG_DEBUG
+ mov $\addr, %dx
+ mov $\ch, %al
+ out %al, %dx
+#endif
+ .endm
+
+ .macro trace, ch
+#ifdef CONFIG_DEBUG
+ push %eax
+ push %edx
+ chout 0x3f8, \ch
+ pop %edx
+ pop %eax
+#endif
+ .endm
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+ .text
+
+/**************************************************************************
+ * Name: up_fullcontextrestore
+ *
+ * Full C prototype:
+ * void up_fullcontextrestore(uint32_t *regs) __attribute__ ((noreturn));
+ *
+ **************************************************************************/
+
+ .globl up_fullcontextrestore
+ .type up_fullcontextrestore, @function
+up_fullcontextrestore:
+ /* Fetch the pointer to the register save array in EAX. */
+
+ movl 4(%esp), %eax
+
+ /* Disable interrupts now (the correct EFLAGS will be restored before we
+ * return
+ */
+
+ cli
+
+ /* 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.
+ *
+ *
+ * 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
+ push %ebx
+ movl (4*REG_EIP)(%eax), %ebx
+ push %ebx
+
+ /* Save the value of EAX on the stack too */
+
+ movl (4*REG_EAX)(%eax), %ebx
+ push %ebx
+
+ /* Now restore the remaining registers */
+
+ movl (4*REG_ESI)(%eax), %esi
+ movl (4*REG_EDI)(%eax), %edi
+ movl (4*REG_EBP)(%eax), %ebp
+ movl (4*REG_EBX)(%eax), %ebx
+ movl (4*REG_EDX)(%eax), %edx
+ movl (4*REG_ECX)(%eax), %ecx
+
+ /* Restore the data segment register. I think there is an issue that will
+ * need to be address here at some time: If the register save area is in
+ * one data segment and the stack is in another, then the above would not
+ * work (and, conversely, if they are in the same data segment, the
+ * following is unnecessary and redundant).
+ */
+
+ mov (4*REG_DS)(%eax), %ds
+
+ /* Restore the correct value of EAX and then return */
+
+ popl %eax
+ iret
+ .size up_fullcontextrestore, . - up_fullcontextrestore
+ .end
diff --git a/nuttx/arch/x86/src/qemu/qemu_handlers.c b/nuttx/arch/x86/src/qemu/qemu_handlers.c
new file mode 100644
index 000000000..a85370f76
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_handlers.c
@@ -0,0 +1,204 @@
+/****************************************************************************
+ * arch/x86/src/qemu/qemu_handlers.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 <nuttx/arch.h>
+#include <arch/io.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static void idt_outb(uint8_t val, uint16_t addr) __attribute__((noinline));
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name idt_outb
+ *
+ * Description:
+ * A slightly slower version of outb
+ *
+ ****************************************************************************/
+
+static void idt_outb(uint8_t val, uint16_t addr)
+{
+ outb(val, addr);
+}
+
+/****************************************************************************
+ * Name: common_handler
+ *
+ * Description:
+ * Common logic for the ISR/IRQ handlers
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+static uint32_t *common_handler(int irq, uint32_t *regs)
+{
+ uint32_t *savestate;
+
+ up_ledon(LED_INIRQ);
+
+ /* Nested interrupts are not supported in this implementation. If you want
+ * implemented nested interrupts, you would have to (1) change the way that
+ * current regs is handled and (2) the design associated with
+ * CONFIG_ARCH_INTERRUPTSTACK.
+ */
+
+ /* Current regs non-zero indicates that we are processing an interrupt;
+ * current_regs is also used to manage interrupt level context switches.
+ */
+
+ savestate = (uint32_t*)current_regs;
+ current_regs = regs;
+
+ /* Deliver the IRQ */
+
+ irq_dispatch(irq, regs);
+
+ /* If a context switch occurred while processing the interrupt then
+ * current_regs may have change value. If we return any value different
+ * from the input regs, then the lower level will know that a context
+ * switch occurred during interrupt processing.
+ */
+
+ regs = (uint32_t*)current_regs;
+
+ /* Restore the previous value of current_regs. NULL would indicate that
+ * we are no longer in an interrupt handler. It will be non-NULL if we
+ * are returning from a nested interrupt.
+ */
+
+ current_regs = savestate;
+ return regs;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: isr_handler
+ *
+ * Description:
+ * This gets called from ISR vector handling logic in qemu_vectors.S
+ *
+ ****************************************************************************/
+
+uint32_t *isr_handler(uint32_t *regs)
+{
+#ifdef CONFIG_SUPPRESS_INTERRUPTS
+ up_ledon(LED_INIRQ);
+ PANIC(OSERR_ERREXCEPTION); /* Doesn't return */
+ return regs; /* To keep the compiler happy */
+#else
+ uint32_t *ret;
+
+ /* Dispatch the interrupt */
+
+ up_ledon(LED_INIRQ);
+ ret = common_handler((int)regs[REG_IRQNO], regs);
+ up_ledoff(LED_INIRQ);
+ return ret;
+#endif
+}
+
+/****************************************************************************
+ * Name: isr_handler
+ *
+ * Description:
+ * This gets called from IRQ vector handling logic in qemu_vectors.S
+ *
+ ****************************************************************************/
+
+uint32_t *irq_handler(uint32_t *regs)
+{
+#ifdef CONFIG_SUPPRESS_INTERRUPTS
+ up_ledon(LED_INIRQ);
+ PANIC(OSERR_ERREXCEPTION); /* Doesn't return */
+ return regs; /* To keep the compiler happy */
+#else
+ uint32_t *ret;
+ int irq;
+
+ up_ledon(LED_INIRQ);
+
+ /* Get the IRQ number */
+
+ irq = (int)regs[REG_IRQNO];
+
+ /* Send an EOI (end of interrupt) signal to the PICs if this interrupt
+ * involved the slave.
+ */
+
+ if (irq >= IRQ8)
+ {
+ /* Send reset signal to slave */
+
+ idt_outb(PIC_OCW2_EOI_NONSPEC, PIC2_OCW2);
+ }
+
+ /* Send reset signal to master */
+
+ idt_outb(PIC_OCW2_EOI_NONSPEC, PIC1_OCW2);
+
+ /* Dispatch the interrupt */
+
+ ret = common_handler(irq, regs);
+ up_ledoff(LED_INIRQ);
+ return ret;
+#endif
+}
+
diff --git a/nuttx/arch/x86/src/qemu/qemu_head.S b/nuttx/arch/x86/src/qemu/qemu_head.S
new file mode 100755
index 000000000..9933d91ff
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_head.S
@@ -0,0 +1,161 @@
+/****************************************************************************
+ * arch/x86/src/qemu/qemu_head.S
+ *
+ * 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>
+
+ .file "qemu_head.S"
+
+/****************************************************************************
+ * Pre-processor definitions
+ ****************************************************************************/
+
+/* Memory Map: _sbss is the start of the BSS region (see ld.script) _ebss is
+ * the end of the BSS regsion (see ld.script). The idle task stack starts at
+ * the end of BSS and is of size CONFIG_IDLETHREAD_STACKSIZE. The IDLE thread
+ * is the thread that the system boots on and, eventually, becomes the idle,
+ * do nothing task that runs only when there is nothing else to run. The
+ * heap continues from there until the end of memory. See g_heapbase below.
+ */
+
+#define STACKBASE ((_ebss + 0x1f) & 0xffffffe0)
+#define IDLE_STACK (STACKBASE+CONFIG_IDLETHREAD_STACKSIZE)
+#define HEAP_BASE (STACKBASE+CONFIG_IDLETHREAD_STACKSIZE)
+
+/****************************************************************************
+ * Macros
+ ****************************************************************************/
+
+/* Trace macros, use like trace 'i' to print char to serial port. */
+
+ .macro trace, ch
+#ifdef CONFIG_DEBUG
+ mov $0x3f8, %dx
+ mov $\ch, %al
+ out %al, %dx
+#endif
+ .endm
+
+/****************************************************************************
+ * Global Symbols
+ ****************************************************************************/
+
+ .global __start /* Making entry point visible to linker */
+ .global os_start /* os_start is defined elsewhere */
+ .global up_lowsetup /* up_lowsetup is defined elsewhere */
+ .global g_heapbase /* The start of the heap */
+
+/****************************************************************************
+ * .text
+ ****************************************************************************/
+/****************************************************************************
+ * Multiboot Header
+ ****************************************************************************/
+
+ /* Setting up the Multiboot header - see GRUB docs for details */
+
+ .set ALIGN, 1<<0 /* Align loaded modules on page boundaries */
+ .set MEMINFO, 1<<1 /* Provide memory map */
+ .set FLAGS, ALIGN | MEMINFO /* This is the Multiboot 'flag' field */
+ .set MAGIC, 0x1badb002 /* 'magic number' lets bootloader find the header */
+ .set CHECKSUM, -(MAGIC + FLAGS) /* Checksum required */
+
+ .text
+ .align 4
+ .long MAGIC
+ .long FLAGS
+ .long CHECKSUM
+
+/****************************************************************************
+ * Name: Start
+ ****************************************************************************/
+
+ .type __start, @function
+__start:
+ /* Set up the stack */
+
+ mov $(idle_stack + CONFIG_IDLETHREAD_STACKSIZE), %esp
+
+ /* Multiboot setup */
+
+ push %eax /* Multiboot magic number */
+ push %ebx /* Multiboot data structure */
+
+ /* Initialize and start NuttX */
+
+ call up_lowsetup /* Low-level, pre-OS initialization */
+ call os_start /* Start NuttX */
+
+ /* NuttX will not return */
+
+ cli
+hang:
+ hlt /* Halt machine should NuttX return */
+ jmp hang
+ .size __start, . - __start
+
+/****************************************************************************
+ * .bss
+ ****************************************************************************/
+
+/* The stack for the IDLE task thread is declared in .bss. NuttX boots and
+ * initializes on the IDLE thread, then at the completion of OS startup, this
+ * thread becomes the thread that executes when there is nothing else to
+ * do in the system (see up_idle()).
+ */
+
+ .type idle_stack, @object
+ .comm idle_stack, CONFIG_IDLETHREAD_STACKSIZE, 32
+ .size idle_stack, . - idle_stack
+
+/****************************************************************************
+ * .rodata
+ ****************************************************************************/
+
+ .section .rodata, "a"
+
+/* HEAP BASE: _sbss is the start of the BSS region (see ld.script) _ebss is
+ * the end of the BSS region (see ld.script). The heap continues from there
+ * until the end of memory.
+ */
+
+ .type g_heapbase, @object
+g_heapbase:
+ .long _ebss
+ .size g_heapbase, . - g_heapbase
+ .end
diff --git a/nuttx/arch/x86/src/qemu/qemu_idle.c b/nuttx/arch/x86/src/qemu/qemu_idle.c
new file mode 100644
index 000000000..42145105b
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_idle.c
@@ -0,0 +1,88 @@
+/****************************************************************************
+ * arch/x86/src/qemu/qemu_idle.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 <nuttx/arch.h>
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_idle
+ *
+ * Description:
+ * up_idle() is the logic that will be executed when their is no other
+ * ready-to-run task. This is processor idle time and will continue until
+ * some interrupt occurs to cause a context switch from the idle task.
+ *
+ * Processing in this state may be processor-specific. e.g., this is where
+ * power management operations might be performed.
+ *
+ ****************************************************************************/
+
+void up_idle(void)
+{
+#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS)
+ /* If the system is idle and there are no timer interrupts, then process
+ * "fake" timer interrupts. Hopefully, something will wake up.
+ */
+
+ sched_process_timer();
+#else
+
+ /* Sleep until an interrupt occurs to save power */
+
+#endif
+}
+
diff --git a/nuttx/arch/x86/src/qemu/qemu_internal.h b/nuttx/arch/x86/src/qemu/qemu_internal.h
new file mode 100755
index 000000000..c8bd5cd95
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_internal.h
@@ -0,0 +1,448 @@
+/************************************************************************************
+ * arch/x86/src/qemu/qemu_internal.h
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_X86_SRC_QEMU_QEMU_INTERNAL_H
+#define __ARCH_X86_SRC_QEMU_QEMU_INTERNAL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+
+#include "up_internal.h"
+#include "chip.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Configuration ********************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: i486_clockconfig
+ *
+ * Description:
+ * Called to initialize the LPC17XX. This does whatever setup is needed to put the
+ * MCU in a usable state. This includes the initialization of clocking using the
+ * settings in board.h.
+ *
+ ************************************************************************************/
+
+EXTERN void i486_clockconfig(void);
+
+/************************************************************************************
+ * Name: i486_lowsetup
+ *
+ * Description:
+ * Called at the very beginning of _start. Performs low level initialization
+ * including setup of the console UART. This UART done early so that the serial
+ * console is available for debugging very early in the boot sequence.
+ *
+ ************************************************************************************/
+
+EXTERN void i486_lowsetup(void);
+
+/************************************************************************************
+ * Name: i486_gpioirqinitialize
+ *
+ * Description:
+ * Initialize logic to support a second level of interrupt decoding for GPIO pins.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_GPIO_IRQ
+EXTERN void i486_gpioirqinitialize(void);
+#else
+# define i486_gpioirqinitialize()
+#endif
+
+/************************************************************************************
+ * Name: i486_configgpio
+ *
+ * Description:
+ * Configure a GPIO pin based on bit-encoded description of the pin.
+ *
+ ************************************************************************************/
+
+EXTERN int i486_configgpio(uint16_t cfgset);
+
+/************************************************************************************
+ * Name: i486_gpiowrite
+ *
+ * Description:
+ * Write one or zero to the selected GPIO pin
+ *
+ ************************************************************************************/
+
+EXTERN void i486_gpiowrite(uint16_t pinset, bool value);
+
+/************************************************************************************
+ * Name: i486_gpioread
+ *
+ * Description:
+ * Read one or zero from the selected GPIO pin
+ *
+ ************************************************************************************/
+
+EXTERN bool i486_gpioread(uint16_t pinset);
+
+/************************************************************************************
+ * Name: i486_gpioirqenable
+ *
+ * Description:
+ * Enable the interrupt for specified GPIO IRQ
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_GPIO_IRQ
+EXTERN void i486_gpioirqenable(int irq);
+#else
+# define i486_gpioirqenable(irq)
+#endif
+
+/************************************************************************************
+ * Name: i486_gpioirqdisable
+ *
+ * Description:
+ * Disable the interrupt for specified GPIO IRQ
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_GPIO_IRQ
+EXTERN void i486_gpioirqdisable(int irq);
+#else
+# define i486_gpioirqdisable(irq)
+#endif
+
+/************************************************************************************
+ * Function: i486_dumpgpio
+ *
+ * Description:
+ * Dump all GPIO registers associated with the base address of the provided pinset.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_DEBUG_GPIO
+EXTERN int i486_dumpgpio(uint16_t pinset, const char *msg);
+#else
+# define i486_dumpgpio(p,m)
+#endif
+
+/************************************************************************************
+ * Name: i486_spi/ssp0/ssp1select, i486_spi/ssp0/ssp1status, and
+ * i486_spi/ssp0/ssp1cmddata
+ *
+ * Description:
+ * These external functions must be provided by board-specific logic. They are
+ * implementations of the select, status, and cmddata methods of the SPI interface
+ * defined by struct spi_ops_s (see include/nuttx/spi.h). All other methods
+ * including up_spiinitialize()) are provided by common LPC17xx logic. To use
+ * this common SPI logic on your board:
+ *
+ * 1. Provide logic in i486_boardinitialize() to configure SPI/SSP chip select
+ * pins.
+ * 2. Provide i486_spi/ssp0/ssp1select() and i486_spi/ssp0/ssp1status() functions
+ * in your board-specific logic. These functions will perform chip selection
+ * and status operations using GPIOs in the way your board is configured.
+ * 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
+ * i486_spi/ssp0/ssp1cmddata() functions in your board-specific logic. These
+ * functions will perform cmd/data selection operations using GPIOs in the way
+ * your board is configured.
+ * 3. Add a call to up_spiinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by up_spiinitialize() may then be used to bind the
+ * SPI driver to higher level logic (e.g., calling
+ * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
+ * the SPI MMC/SD driver).
+ *
+ ************************************************************************************/
+
+struct spi_dev_s;
+enum spi_dev_e;
+
+#ifdef CONFIG_I486_SPI
+EXTERN void i486_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
+EXTERN uint8_t i486_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+#ifdef CONFIG_SPI_CMDDATA
+EXTERN int i486_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
+#endif
+#endif
+
+/****************************************************************************
+ * Name: ssp_flush
+ *
+ * Description:
+ * Flush and discard any words left in the RX fifo. This can be called
+ * from ssp0/1select after a device is deselected (if you worry about such
+ * things).
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+struct spi_dev_s;
+#ifdef CONFIG_I486_SPI
+EXTERN void spi_flush(FAR struct spi_dev_s *dev);
+#endif
+#if defined(CONFIG_I486_SSP0) || defined(CONFIG_I486_SSP1)
+EXTERN void ssp_flush(FAR struct spi_dev_s *dev);
+#endif
+
+/****************************************************************************
+ * Name: i486_dmainitialize
+ *
+ * Description:
+ * Initialize the GPDMA subsystem.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_I486_GPDMA
+EXTERN void i486_dmainitilaize(void);
+#endif
+
+/****************************************************************************
+ * Name: i486_dmachannel
+ *
+ * Description:
+ * Allocate a DMA channel. This function sets aside a DMA channel and
+ * gives the caller exclusive access to the DMA channel.
+ *
+ * Returned Value:
+ * One success, this function returns a non-NULL, void* DMA channel
+ * handle. NULL is returned on any failure. This function can fail only
+ * if no DMA channel is available.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_I486_GPDMA
+EXTERN DMA_HANDLE i486_dmachannel(void);
+#endif
+
+/****************************************************************************
+ * Name: i486_dmafree
+ *
+ * Description:
+ * Release a DMA channel. NOTE: The 'handle' used in this argument must
+ * NEVER be used again until i486_dmachannel() is called again to re-gain
+ * a valid handle.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_I486_GPDMA
+EXTERN void i486_dmafree(DMA_HANDLE handle);
+#endif
+
+/****************************************************************************
+ * Name: i486_dmasetup
+ *
+ * Description:
+ * Configure DMA for one transfer.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_I486_GPDMA
+EXTERN int i486_dmarxsetup(DMA_HANDLE handle,
+ uint32_t control, uint32_t config,
+ uint32_t srcaddr, uint32_t destaddr,
+ size_t nbytes);
+#endif
+
+/****************************************************************************
+ * Name: i486_dmastart
+ *
+ * Description:
+ * Start the DMA transfer
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_I486_GPDMA
+EXTERN int i486_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg);
+#endif
+
+/****************************************************************************
+ * Name: i486_dmastop
+ *
+ * Description:
+ * Cancel the DMA. After i486_dmastop() is called, the DMA channel is
+ * reset and i486_dmasetup() must be called before i486_dmastart() can be
+ * called again
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_I486_GPDMA
+EXTERN void i486_dmastop(DMA_HANDLE handle);
+#endif
+
+/****************************************************************************
+ * Name: i486_dmasample
+ *
+ * Description:
+ * Sample DMA register contents
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_I486_GPDMA
+#ifdef CONFIG_DEBUG_DMA
+EXTERN void i486_dmasample(DMA_HANDLE handle, struct i486_dmaregs_s *regs);
+#else
+# define i486_dmasample(handle,regs)
+#endif
+#endif
+
+/****************************************************************************
+ * Name: i486_dmadump
+ *
+ * Description:
+ * Dump previously sampled DMA register contents
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_I486_GPDMA
+#ifdef CONFIG_DEBUG_DMA
+EXTERN void i486_dmadump(DMA_HANDLE handle, const struct i486_dmaregs_s *regs,
+ const char *msg);
+#else
+# define i486_dmadump(handle,regs,msg)
+#endif
+#endif
+
+/****************************************************************************
+ * Name: vector_*
+ *
+ * Description:
+ * These are the various ISR/IRQ vector address exported from
+ * qemu_vectors.S. These addresses need to have global scope so that they
+ * can be known to the interrupt intialization logic in qemu_irq.c.
+ *
+ ****************************************************************************/
+
+EXTERN void vector_isr0(void);
+EXTERN void vector_isr1(void);
+EXTERN void vector_isr2(void);
+EXTERN void vector_isr3(void);
+EXTERN void vector_isr4(void);
+EXTERN void vector_isr5(void);
+EXTERN void vector_isr6(void);
+EXTERN void vector_isr7(void);
+EXTERN void vector_isr8(void);
+EXTERN void vector_isr9(void);
+EXTERN void vector_isr10(void);
+EXTERN void vector_isr11(void);
+EXTERN void vector_isr12(void);
+EXTERN void vector_isr13(void);
+EXTERN void vector_isr14(void);
+EXTERN void vector_isr15(void);
+EXTERN void vector_isr16(void);
+EXTERN void vector_isr17(void);
+EXTERN void vector_isr18(void);
+EXTERN void vector_isr19(void);
+EXTERN void vector_isr20(void);
+EXTERN void vector_isr21(void);
+EXTERN void vector_isr22(void);
+EXTERN void vector_isr23(void);
+EXTERN void vector_isr24(void);
+EXTERN void vector_isr25(void);
+EXTERN void vector_isr26(void);
+EXTERN void vector_isr27(void);
+EXTERN void vector_isr28(void);
+EXTERN void vector_isr29(void);
+EXTERN void vector_isr30(void);
+EXTERN void vector_isr31(void);
+EXTERN void vector_irq0(void);
+EXTERN void vector_irq1(void);
+EXTERN void vector_irq2(void);
+EXTERN void vector_irq3(void);
+EXTERN void vector_irq4(void);
+EXTERN void vector_irq5(void);
+EXTERN void vector_irq6(void);
+EXTERN void vector_irq7(void);
+EXTERN void vector_irq8(void);
+EXTERN void vector_irq9(void);
+EXTERN void vector_irq10(void);
+EXTERN void vector_irq11(void);
+EXTERN void vector_irq12(void);
+EXTERN void vector_irq13(void);
+EXTERN void vector_irq14(void);
+EXTERN void vector_irq15(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_X86_SRC_QEMU_QEMU_INTERNAL_H */
diff --git a/nuttx/arch/x86/src/qemu/qemu_lowputc.c b/nuttx/arch/x86/src/qemu/qemu_lowputc.c
new file mode 100644
index 000000000..1fa4aa6c5
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_lowputc.c
@@ -0,0 +1,104 @@
+/****************************************************************************
+ * arch/x86/src/qemu/qemu_lowputc.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 <arch/io.h>
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+ /* COM1 port addresses */
+
+#define COM1_PORT 0x3f8 /* COM1: I/O port 0x3f8, IRQ 4 */
+#define COM2_PORT 0x2f8 /* COM2: I/O port 0x2f8, IRQ 3 */
+#define COM3_PORT 0x3e8 /* COM3: I/O port 0x3e8, IRQ 4 */
+#define COM4_PORT 0x2e8 /* COM4: I/O port 0x2e8, IRQ 3 */
+
+/* 16650 register offsets */
+
+#define COM_RBR 0 /* DLAB=0, Receiver Buffer (read) */
+#define COM_THR 0 /* DLAB=0, Transmitter Holding Register (write) */
+#define COM_DLL 0 /* DLAB=1, Divisor Latch (least significant byte) */
+#define COM_IER 1 /* DLAB=0, Interrupt Enable */
+#define COM_DLM 1 /* DLAB=1, Divisor Latch(most significant byte) */
+#define COM_IIR 2 /* Interrupt Identification (read) */
+#define COM_FCR 2 /* FIFO Control (write) */
+#define COM_LCR 3 /* Line Control */
+#define COM_MCR 4 /* MODEM Control */
+#define COM_LSR 5 /* Line Status */
+#define COM_MSR 6 /* MODEM Status */
+#define COM_SCR 7 /* Scratch */
+
+/* 16650 register bit definitions */
+
+#define LSR_THRE (1 << 5) /* Bit 5: Transmitter Holding Register Empty */
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/**************************************************************************
+ * Name: up_lowputc
+ *
+ * Description:
+ * Output one byte on the serial console
+ *
+ **************************************************************************/
+
+void up_lowputc(char ch)
+{
+ /* Wait until the Transmitter Holding Register (THR) is empty. */
+
+ while ((inb(COM1_PORT+COM_LSR) & LSR_THRE) == 0);
+
+ /* Then output the character to the THR*/
+
+ outb(ch, COM1_PORT+COM_THR);
+}
+
diff --git a/nuttx/arch/x86/src/qemu/qemu_lowsetup.c b/nuttx/arch/x86/src/qemu/qemu_lowsetup.c
new file mode 100644
index 000000000..20250c33d
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_lowsetup.c
@@ -0,0 +1,140 @@
+/****************************************************************************
+ * arch/x86/src/qemu/qemu_lowsetup.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 <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct gdt_entry_s gdt_entries[5];
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_gdtentry
+ *
+ * Description:
+ * Set the value of one GDT entry.
+ *
+ ****************************************************************************/
+
+static void up_gdtentry(struct gdt_entry_s *entry, uint32_t base,
+ uint32_t limit, uint8_t access, uint8_t gran)
+{
+ entry->lowbase = (base & 0xffff);
+ entry->midbase = (base >> 16) & 0xff;
+ entry->hibase = (base >> 24) & 0xff;
+
+ entry->lowlimit = (limit & 0xffff);
+ entry->granularity = (limit >> 16) & 0x0f;
+
+ entry->granularity |= gran & 0xf0;
+ entry->access = access;
+}
+
+/****************************************************************************
+ * Name: up_gdtinit
+ *
+ * Description:
+ * Initialize the GDT. The Global Descriptor Table or GDT is a data
+ * structure used by Intel x86-family processors starting with the 80286
+ * in order to define the characteristics of the various memory areas used
+ * during program execution, for example the base address, the size and
+ * access privileges like executability and writability. These memory areas
+ * are called segments in Intel terminology.
+ *
+ ****************************************************************************/
+
+static void up_gdtinit(void)
+{
+ struct gdt_ptr_s gdt_ptr;
+
+ up_gdtentry(&gdt_entries[0], 0, 0, 0, 0); /* Null segment */
+ up_gdtentry(&gdt_entries[1], 0, 0xffffffff, 0x9a, 0xcf); /* Code segment */
+ up_gdtentry(&gdt_entries[2], 0, 0xffffffff, 0x92, 0xcf); /* Data segment */
+ up_gdtentry(&gdt_entries[3], 0, 0xffffffff, 0xfa, 0xcf); /* User mode code segment */
+ up_gdtentry(&gdt_entries[4], 0, 0xffffffff, 0xf2, 0xcf); /* User mode data segment */
+
+ gdt_ptr.limit = (sizeof(struct gdt_entry_s) * 5) - 1;
+ gdt_ptr.base = (uint32_t)gdt_entries;
+ gdt_flush((uint32_t )&gdt_ptr);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_lowsetup
+ *
+ * Description:
+ * Called from qemu_head BEFORE starting the operating system in order
+ * perform any necessary, early initialization.
+ *
+ ****************************************************************************/
+
+void up_lowsetup(void)
+{
+ /* Initialize the Global descriptor table */
+
+ up_gdtinit();
+
+ /* Early serial driver initialization */
+
+#ifdef CONFIG_USE_EARLYSERIALINIT
+ up_earlyserialinit();
+#endif
+
+ /* Now perform board-specific initializations */
+
+ up_boardinitialize();
+}
+
diff --git a/nuttx/arch/x86/src/qemu/qemu_memorymap.h b/nuttx/arch/x86/src/qemu/qemu_memorymap.h
new file mode 100755
index 000000000..571ddd03d
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_memorymap.h
@@ -0,0 +1,67 @@
+/************************************************************************************
+ * arch/x86/src/qemu/qemu_memorymap.h
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_X86_SRC_QEMU_QEMU_MEMORYMAP_H
+#define __ARCH_X86_SRC_QEMU_QEMU_MEMORYMAP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Memory Map ***********************************************************************/
+
+/* Peripheral Base Addresses ********************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_X86_SRC_QEMU_QEMU_MEMORYMAP_H */
diff --git a/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S b/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S
new file mode 100644
index 000000000..427c3bd5d
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S
@@ -0,0 +1,182 @@
+/**************************************************************************
+ * arch/x86/src/qemu/up_saveusercontext.S
+ *
+ * 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.
+ *
+ **************************************************************************/
+
+/**************************************************************************
+ * Conditional Compilation Options
+ **************************************************************************/
+
+/**************************************************************************
+ * Included Files
+ **************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/irq.h>
+#include "up_internal.h"
+
+ .file "qemu_saveusercontext.S"
+
+/**************************************************************************
+ * Pre-processor Definitions
+ **************************************************************************/
+
+/****************************************************************************
+ * Macros
+ ****************************************************************************/
+
+/* Trace macros, use like trace 'i' to print char to serial port. */
+
+ .macro chout, addr, ch
+#ifdef CONFIG_DEBUG
+ mov $\addr, %dx
+ mov $\ch, %al
+ out %al, %dx
+#endif
+ .endm
+
+ .macro trace, ch
+#ifdef CONFIG_DEBUG
+ push %eax
+ push %edx
+ chout 0x3f8, \ch
+ pop %edx
+ pop %eax
+#endif
+ .endm
+
+/**************************************************************************
+ * .text
+ **************************************************************************/
+
+ .text
+
+/**************************************************************************
+ * Name: up_saveusercontext
+ *
+ * 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
+ *
+ **************************************************************************/
+
+ .globl up_saveusercontext
+ .type up_saveusercontext, @function
+up_saveusercontext:
+ /* 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, (4*REG_EBX)(%eax)
+ movl %esi, (4*REG_ESI)(%eax)
+ movl %edi, (4*REG_EDI)(%eax)
+
+ /* Save the segment registers */
+
+ mov %ss, (4*REG_SS)(%eax)
+ mov %cs, (4*REG_CS)(%eax)
+ mov %ds, (4*REG_DS)(%eax)
+
+ /* 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
+ movl %ecx, (4*REG_SP)(%eax)
+
+ /* Fetch the PC from the stack and save it in the save block */
+
+ movl 0(%esp), %ecx
+ movl %ecx, (4*REG_EIP)(%eax)
+
+ /* Save the framepointer */
+
+ movl %ebp, (4*REG_EBP)(%eax)
+
+ /* Save EAX=1. This will be the "apparent" return value from this
+ * function when context is switch back to this thread. The non-zero
+ * return value is the indication that we have been resumed.
+ */
+
+ movl $1, (4*REG_EAX)(%eax)
+
+ /* Get and save the interrupt state */
+
+ pushf
+ pop %ecx
+ movl %ecx, (4*REG_EFLAGS)(%eax)
+
+ /* And return 0 -- The zero return value is the indication that that
+ * this is the original, "true" return from the function.
+ *
+ * 'ret' will remove the EIP from the top of the stack.
+ */
+
+ xorl %eax, %eax
+ ret
+ .size up_saveusercontext, . - up_saveusercontext
+ .end
diff --git a/nuttx/arch/x86/src/qemu/qemu_serial.c b/nuttx/arch/x86/src/qemu/qemu_serial.c
new file mode 100644
index 000000000..527ca0c05
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_serial.c
@@ -0,0 +1,116 @@
+/****************************************************************************
+ * arch/x86/src/qemu/qemu_serial.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 <nuttx/arch.h>
+#include <nuttx/uart_16550.h>
+
+#include <arch/io.h>
+
+#include "up_internal.h"
+
+/* This is a "stub" file to suppport up_putc if no real serial driver is
+ * configured. Normally, drivers/serial/uart_16550.c provides the serial
+ * driver for this platform.
+ */
+
+#ifdef CONFIG_USE_SERIALDRIVER
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uart_getreg(), uart_putreg()
+ *
+ * Description:
+ * These functions must be provided by the processor-specific code in order
+ * to correctly access 16550 registers
+ *
+ ****************************************************************************/
+
+uart_datawidth_t uart_getreg(uart_addrwidth_t base, unsigned int offset)
+{
+ return inb(base + offset);
+}
+
+void uart_putreg(uart_addrwidth_t base, unsigned int offset, uart_datawidth_t value)
+{
+ outb(value, base + offset);
+}
+
+#else /* CONFIG_USE_SERIALDRIVER */
+
+/****************************************************************************
+ * Name: up_putc
+ *
+ * Description:
+ * Provide priority, low-level access to support OS debug writes
+ *
+ ****************************************************************************/
+
+int up_putc(int ch)
+{
+ /* Check for LF */
+
+ if (ch == '\n')
+ {
+ /* Add CR */
+
+ up_lowputc('\r');
+ }
+
+ up_lowputc(ch);
+ return ch;
+}
+
+#endif /* CONFIG_USE_SERIALDRIVER */
diff --git a/nuttx/arch/x86/src/qemu/qemu_timerisr.c b/nuttx/arch/x86/src/qemu/qemu_timerisr.c
new file mode 100755
index 000000000..531b7d09d
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_timerisr.c
@@ -0,0 +1,148 @@
+/****************************************************************************
+ * arch/x86/src/qemu/qemu_timerisr.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Based on Bran's kernel development tutorials. Rewritten for JamesM's
+ * kernel development tutorials.
+ *
+ * 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 <stdint.h>
+#include <time.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <arch/irq.h>
+#include <arch/io.h>
+#include <arch/board/board.h>
+
+#include "clock_internal.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "chip.h"
+#include "qemu_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Programmable interval timer (PIT)
+ *
+ * Fpit = Fin / divisor
+ * divisor = Fin / divisor
+ *
+ * Where:
+ *
+ * Fpit = The desired interrupt frequency.
+ * Fin = PIT input frequency (PIT_CLOCK provided in board.h)
+ *
+ * The desired timer interrupt frequency is provided by the definition CLK_TCK
+ * (see include/time.h). CLK_TCK defines the desired number of system clock
+ * ticks per second. That value is a user configurable setting that defaults
+ * to 100 (100 ticks per second = 10 MS interval).
+ */
+
+#define PIT_DIVISOR ((uint32_t)PIT_CLOCK/(uint32_t)CLK_TCK)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: up_timerisr
+ *
+ * Description:
+ * The timer ISR will perform a variety of services for various portions
+ * of the systems.
+ *
+ ****************************************************************************/
+
+static int up_timerisr(int irq, uint32_t *regs)
+{
+ /* Process timer interrupt */
+
+ sched_process_timer();
+ return 0;
+}
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: up_timerinit
+ *
+ * Description:
+ * This function is called during start-up to initialize
+ * the timer interrupt.
+ *
+ ****************************************************************************/
+
+void up_timerinit(void)
+{
+ /* uint32_t to avoid compile time overflow errors */
+
+ uint32_t divisor = PIT_DIVISOR;
+ DEBUGASSERT(divisor <= 0xffff);
+
+ /* Attach to the timer interrupt handler */
+
+ (void)irq_attach(IRQ0, (xcpt_t)up_timerisr);
+
+ /* Send the command byte to configure counter 0 */
+
+ outb(PIT_OCW_MODE_SQUARE|PIT_OCW_RL_DATA|PIT_OCW_COUNTER_0, PIT_REG_COMMAND);
+
+ /* Set the PIT input frequency divisor */
+
+ outb((uint8_t)(divisor & 0xff), PIT_REG_COUNTER0);
+ outb((uint8_t)((divisor >> 8) & 0xff), PIT_REG_COUNTER0);
+
+ /* And enable IRQ0 */
+
+ up_enable_irq(IRQ0);
+}
diff --git a/nuttx/arch/x86/src/qemu/qemu_vectors.S b/nuttx/arch/x86/src/qemu/qemu_vectors.S
new file mode 100755
index 000000000..d6e17e57b
--- /dev/null
+++ b/nuttx/arch/x86/src/qemu/qemu_vectors.S
@@ -0,0 +1,271 @@
+/****************************************************************************
+ * arch/x86/src/qemu/qemu_head.S
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Based on Bran's kernel development tutorials. Rewritten for JamesM's
+ * kernel development tutorials.
+ *
+ * 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 <arch/irq.h>
+
+ .file "qemu_vectors.S"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define KSEG 0x10
+
+/****************************************************************************
+ * .text
+ ****************************************************************************/
+
+ .text
+
+/****************************************************************************
+ * Globals
+ ****************************************************************************/
+
+ .globl irq_handler
+ .globl isr_handler
+
+/****************************************************************************
+ * Macros
+ ****************************************************************************/
+
+/* Trace macros, use like trace 'i' to print char to serial port. */
+
+ .macro trace, ch
+ mov $0x3f8, %dx
+ mov $\ch, %al
+ out %al, %dx
+ .endm
+
+/* This macro creates a stub for an ISR which does NOT pass it's own
+ * error code (adds a dummy errcode byte).
+ */
+
+ .macro ISR_NOERRCODE, intno
+ .globl vector_isr\intno
+vector_isr\intno:
+ cli /* Disable interrupts firstly. */
+ push $0 /* Push a dummy error code. */
+ push $\intno /* Push the interrupt number. */
+ jmp isr_common /* Go to the common ISR handler code. */
+ .endm
+
+/* This macro creates a stub for an ISR which passes it's own
+ * error code.
+ */
+
+ .macro ISR_ERRCODE, intno
+ .globl vector_isr\intno
+vector_isr\intno:
+ cli /* Disable interrupts firstly. */
+ push $\intno /* Push the interrupt number. */
+ jmp isr_common /* Go to the common ISR handler code. */
+ .endm
+
+/* This macro creates a stub for an IRQ - the first parameter is
+ * the IRQ number, the second is the ISR number it is remapped to.
+ */
+
+ .macro IRQ, irqno, intno
+ .globl vector_irq\irqno
+vector_irq\irqno:
+ cli /* Disable interrupts firstly. */
+ push $0 /* Push a dummy error code. */
+ push $\intno /* Push the interrupt number. */
+ jmp irq_common /* Go to the common IRQ handler code. */
+ .endm
+
+/****************************************************************************
+ * IDT Vectors
+ ****************************************************************************/
+/* The following will be the vector addresses programmed into the IDT */
+
+ ISR_NOERRCODE ISR0
+ ISR_NOERRCODE ISR1
+ ISR_NOERRCODE ISR2
+ ISR_NOERRCODE ISR3
+ ISR_NOERRCODE ISR4
+ ISR_NOERRCODE ISR5
+ ISR_NOERRCODE ISR6
+ ISR_NOERRCODE ISR7
+ ISR_ERRCODE ISR8
+ ISR_NOERRCODE ISR9
+ ISR_ERRCODE ISR10
+ ISR_ERRCODE ISR11
+ ISR_ERRCODE ISR12
+ ISR_ERRCODE ISR13
+ ISR_ERRCODE ISR14
+ ISR_NOERRCODE ISR15
+ ISR_NOERRCODE ISR16
+ ISR_NOERRCODE ISR17
+ ISR_NOERRCODE ISR18
+ ISR_NOERRCODE ISR19
+ ISR_NOERRCODE ISR20
+ ISR_NOERRCODE ISR21
+ ISR_NOERRCODE ISR22
+ ISR_NOERRCODE ISR23
+ ISR_NOERRCODE ISR24
+ ISR_NOERRCODE ISR25
+ ISR_NOERRCODE ISR26
+ ISR_NOERRCODE ISR27
+ ISR_NOERRCODE ISR28
+ ISR_NOERRCODE ISR29
+ ISR_NOERRCODE ISR30
+ ISR_NOERRCODE ISR31
+ IRQ 0, IRQ0
+ IRQ 1, IRQ1
+ IRQ 2, IRQ2
+ IRQ 3, IRQ3
+ IRQ 4, IRQ4
+ IRQ 5, IRQ5
+ IRQ 6, IRQ6
+ IRQ 7, IRQ7
+ IRQ 8, IRQ8
+ IRQ 9, IRQ9
+ IRQ 10, IRQ10
+ IRQ 11, IRQ11
+ IRQ 12, IRQ12
+ IRQ 13, IRQ13
+ IRQ 14, IRQ14
+ IRQ 15, IRQ15
+
+/****************************************************************************
+ * Name: isr_common
+ *
+ * Description:
+ * This is the common ISR logic. It saves the processor state, sets up for
+ * kernel mode segments, calls the C-level fault handler, and finally
+ * restores the stack frame.
+ *
+ ****************************************************************************/
+
+ .type isr_common, @function
+isr_common:
+/* trace 'S' */
+ pusha /* Pushes edi,esi,ebp,esp,ebx,edx,ecx,eax */
+
+ mov %ds, %ax /* Lower 16-bits of eax = ds. */
+ pushl %eax /* Save the data segment descriptor */
+
+ mov $KSEG, %ax /* Load the kernel data segment descriptor */
+ mov %ax, %ds
+ mov %ax, %es
+ mov %ax, %fs
+ mov %ax, %gs
+
+ /* 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.
+ */
+
+ mov %esp, %eax
+ push %eax
+ call isr_handler
+ jmp .Lreturn
+ .size isr_common, . - isr_common
+
+/****************************************************************************
+ * Name: irq_common
+ *
+ * Description:
+ * This is the common IRQ logic. It saves the processor state, sets up for
+ * kernel mode segments, calls the C-level fault handler, and finally
+ * restores the stack frame.
+ *
+ ****************************************************************************/
+
+ .type irq_common, @function
+irq_common:
+/* trace 'R' */
+ pusha /* Pushes edi,esi,ebp,esp,ebx,edx,ecx,eax */
+
+ mov %ds, %ax /* Lower 16-bits of eax = ds. */
+ push %eax /* Save the data segment descriptor */
+
+ mov $KSEG, %ax /* Load the kernel data segment descriptor */
+ mov %ax, %ds
+ mov %ax, %es
+ mov %ax, %fs
+ mov %ax, %gs
+
+ /* 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 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 up_fullcontextrestore
+
+.Lnoswitch:
+ pop %ebx /* Reload the original data segment descriptor */
+ mov %bx, %ds
+ mov %bx, %es
+ mov %bx, %fs
+ mov %bx, %gs
+
+ popa /* Pops edi,esi,ebp... */
+ add $8, %esp /* Cleans up the pushed error code and pushed ISR number */
+ iret /* Pops 3-5 things at once: CS, EIP, EFLAGS (and maybe SS and ESP) */
+ .size irq_common, . - irq_common
+ .end