From 55d4f54ef204271e27703b5e7a89d58c13c2b294 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 4 Mar 2011 22:25:03 +0000 Subject: First cut at x86 build environment git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3336 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/x86/src/Makefile | 143 ++++++++ nuttx/arch/x86/src/README.txt | 31 ++ nuttx/arch/x86/src/common/up_allocateheap.c | 82 +++++ nuttx/arch/x86/src/common/up_arch.h | 90 +++++ nuttx/arch/x86/src/common/up_exit.c | 174 ++++++++++ nuttx/arch/x86/src/common/up_initialize.c | 168 ++++++++++ nuttx/arch/x86/src/common/up_internal.h | 258 ++++++++++++++ nuttx/arch/x86/src/common/up_interruptcontext.c | 72 ++++ nuttx/arch/x86/src/common/up_lowputs.c | 74 ++++ nuttx/arch/x86/src/common/up_mdelay.c | 90 +++++ nuttx/arch/x86/src/common/up_modifyreg16.c | 85 +++++ nuttx/arch/x86/src/common/up_modifyreg32.c | 85 +++++ nuttx/arch/x86/src/common/up_modifyreg8.c | 85 +++++ nuttx/arch/x86/src/common/up_puts.c | 75 +++++ nuttx/arch/x86/src/common/up_udelay.c | 129 +++++++ nuttx/arch/x86/src/i486/up_createstack.c | 135 ++++++++ nuttx/arch/x86/src/i486/up_releasestack.c | 79 +++++ nuttx/arch/x86/src/i486/up_usestack.c | 119 +++++++ nuttx/arch/x86/src/qemu/Make.defs | 52 +++ nuttx/arch/x86/src/qemu/chip.h | 74 ++++ nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S | 122 +++++++ nuttx/arch/x86/src/qemu/qemu_head.S | 126 +++++++ nuttx/arch/x86/src/qemu/qemu_idle.c | 88 +++++ nuttx/arch/x86/src/qemu/qemu_internal.h | 389 ++++++++++++++++++++++ nuttx/arch/x86/src/qemu/qemu_memorymap.h | 67 ++++ nuttx/arch/x86/src/qemu/qemu_saveusercontext.S | 130 ++++++++ 26 files changed, 3022 insertions(+) create mode 100644 nuttx/arch/x86/src/Makefile create mode 100755 nuttx/arch/x86/src/README.txt create mode 100644 nuttx/arch/x86/src/common/up_allocateheap.c create mode 100644 nuttx/arch/x86/src/common/up_arch.h create mode 100644 nuttx/arch/x86/src/common/up_exit.c create mode 100644 nuttx/arch/x86/src/common/up_initialize.c create mode 100644 nuttx/arch/x86/src/common/up_internal.h create mode 100644 nuttx/arch/x86/src/common/up_interruptcontext.c create mode 100644 nuttx/arch/x86/src/common/up_lowputs.c create mode 100644 nuttx/arch/x86/src/common/up_mdelay.c create mode 100644 nuttx/arch/x86/src/common/up_modifyreg16.c create mode 100644 nuttx/arch/x86/src/common/up_modifyreg32.c create mode 100644 nuttx/arch/x86/src/common/up_modifyreg8.c create mode 100644 nuttx/arch/x86/src/common/up_puts.c create mode 100644 nuttx/arch/x86/src/common/up_udelay.c create mode 100644 nuttx/arch/x86/src/i486/up_createstack.c create mode 100644 nuttx/arch/x86/src/i486/up_releasestack.c create mode 100644 nuttx/arch/x86/src/i486/up_usestack.c create mode 100755 nuttx/arch/x86/src/qemu/Make.defs create mode 100755 nuttx/arch/x86/src/qemu/chip.h create mode 100644 nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S create mode 100755 nuttx/arch/x86/src/qemu/qemu_head.S create mode 100644 nuttx/arch/x86/src/qemu/qemu_idle.c create mode 100755 nuttx/arch/x86/src/qemu/qemu_internal.h create mode 100755 nuttx/arch/x86/src/qemu/qemu_memorymap.h create mode 100644 nuttx/arch/x86/src/qemu/qemu_saveusercontext.S (limited to 'nuttx/arch/x86/src') diff --git a/nuttx/arch/x86/src/Makefile b/nuttx/arch/x86/src/Makefile new file mode 100644 index 000000000..9281828bb --- /dev/null +++ b/nuttx/arch/x86/src/Makefile @@ -0,0 +1,143 @@ +############################################################################ +# arch/x86/src/Makefile +# +# Copyright (C) 2010 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +-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_AOBJ = $(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) -print-libgcc-file-name}" + +VPATH = chip:common:$(ARCH_SUBDIR) + +all: $(HEAD_OBJ) libarch$(LIBEXT) + +$(AOBJS) $(HEAD_AOBJ): %$(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) + +nuttx: $(HEAD_AOBJ) board/libboard$(LIBEXT) + @echo "LD: nuttx" + @$(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_AOBJ) $(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 + +.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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "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 + * + * 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 +#ifndef __ASSEMBLY__ +# include +#endif +#include + +/**************************************************************************** + * 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_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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "os_internal.h" +#include "up_internal.h" + +#ifdef CONFIG_DUMP_ON_EXIT +#include +#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..9ce9523ed --- /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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include +#include + +#include "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 stm32_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..9730c3372 --- /dev/null +++ b/nuttx/arch/x86/src/common/up_internal.h @@ -0,0 +1,258 @@ +/**************************************************************************** + * arch/x86/src/common/up_internal.h + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef __ARCH_X86_SRC_COMMON_UP_INTERNAL_H +#define __ARCH_X86_SRC_COMMON_UP_INTERNAL_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#ifndef __ASSEMBLY__ +# include +#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_savestate(regs) up_copystate(regs, current_regs) +#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 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_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 int up_timerisr(int irq, uint32_t *regs); +extern void up_lowputc(char ch); +extern void up_puts(const char *str); +extern void up_lowputs(const char *str); + +extern void up_doirq(int irq, uint32_t *regs); +#ifdef CONFIG_PAGING +extern void up_pginitialize(void); +extern uint32_t *up_va2pte(uintptr_t vaddr); +extern void up_dataabort(uint32_t *regs, uint32_t far, uint32_t fsr); +#else /* CONFIG_PAGING */ +# define up_pginitialize() +extern void up_dataabort(uint32_t *regs); +#endif /* CONFIG_PAGING */ +extern void up_prefetchabort(uint32_t *regs); +extern void up_syscall(uint32_t *regs); +extern void up_undefinedinsn(uint32_t *regs); + +/* Defined in up_vectors.S */ + +extern void up_vectorundefinsn(void); +extern void up_vectorswi(void); +extern void up_vectorprefetch(void); +extern void up_vectordata(void); +extern void up_vectoraddrexcptn(void); +extern void up_vectorirq(void); +extern void up_vectorfiq(void); + +/* 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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * 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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include "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_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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * 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/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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "up_arch.h" +#include "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_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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "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_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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include "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..5e88c117e --- /dev/null +++ b/nuttx/arch/x86/src/qemu/Make.defs @@ -0,0 +1,52 @@ +############################################################################ +# arch/x86/src/qemu/Make.defs +# +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# The start-up, "head", file + +HEAD_ASRC = qemu_head.S + +# Common x86 and i486 files + +CMN_ASRCS = +CMN_CSRCS = up_createstack.c up_mdelay.c up_udelay.c up_exit.c up_initialize.c \ + up_interruptcontext.c up_modifyreg8.c up_modifyreg16.c \ + up_modifyreg32.c up_releasestack.c up_usestack.c + +# Required QEMU files + +CHIP_ASRCS = qemu_saveusercontext.S qemu_fullcontextrestore.S +CHIP_CSRCS = qemu_idle.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 + * + * 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 + +/************************************************************************************ + * 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..b70ab0984 --- /dev/null +++ b/nuttx/arch/x86/src/qemu/qemu_fullcontextrestore.S @@ -0,0 +1,122 @@ +/************************************************************************** + * arch/x86/src/qemu/qemu_fullcontextrestore.S + * + * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **************************************************************************/ + +/************************************************************************** + * Conditional Compilation Options + **************************************************************************/ + +/************************************************************************** + * Included Files + **************************************************************************/ + +#include +#include +#include "up_internal.h" + +/************************************************************************** + * Private Definitions + **************************************************************************/ + +#ifdef __CYGWIN__ +# define SYMBOL(s) _##s +#else +# define SYMBOL(s) s +#endif + +/************************************************************************** + * Private Types + **************************************************************************/ + +/************************************************************************** + * Private Function Prototypes + **************************************************************************/ + +/************************************************************************** + * Global Variables + **************************************************************************/ + +/************************************************************************** + * Private Variables + **************************************************************************/ + +/************************************************************************** + * Private Functions + **************************************************************************/ + +/************************************************************************** + * Public Functions + **************************************************************************/ + +/************************************************************************** + * Name: up_fullcontextrestore + * + * Full C prototype: + * void up_fullcontextrestore(uint32_t *regs) __attribute__ ((noreturn)); + * + **************************************************************************/ + +#ifdef CONFIG_X86_NASM +# warning "No Nasm support" +#else + .text + .globl SYMBOL(up_fullcontextrestore) +#ifndef __CYGWIN__ + .type SYMBOL(up_fullcontextrestore), @function +#endif +SYMBOL(up_fullcontextrestore): + movl 4(%esp), %ecx /* U_pthread_jmpbuf in %ecx. */ + movl 8(%esp), %eax /* Second argument is return value. */ + + /* Save the return address now. */ + + movl (JB_PC)(%ecx), %edx + + /* Restore registers. */ + + movl (JB_EBX)(%ecx), %ebx + movl (JB_ESI)(%ecx), %esi + movl (JB_EDI)(%ecx), %edi + movl (JB_EBP)(%ecx), %ebp + movl (JB_SP)(%ecx), %esp + + /* Jump to saved PC. */ + + jmp *%edx +#ifndef __CYGWIN__ + .size SYMBOL(up_fullcontextrestore), . - SYMBOL(up_fullcontextrestore) +#endif + .end +#endif /* CONFIG_X86_NASM */ + 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..a1c816827 --- /dev/null +++ b/nuttx/arch/x86/src/qemu/qemu_head.S @@ -0,0 +1,126 @@ +/**************************************************************************** + * arch/x86/src/qemu/qemu_head.S + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * .text + ****************************************************************************/ + +#ifdef CONFIG_X86_NASM +global loader /* Making entry point visible to linker */ +extern os_start /* os_start is defined elsewhere */ +extern up_lowsetup /* up_lowsetup is defined elsewhere */ + +/* Setting up the Multiboot header - see GRUB docs for details */ + +MODULEALIGN equ 1<<0 /* Align loaded modules on page boundaries */ +MEMINFO equ 1<<1 /* Provide memory map */ +FLAGS equ MODULEALIGN | MEMINFO /* This is the Multiboot 'flag' field */ +MAGIC equ 0x1BADB002 /* 'magic number' lets bootloader find the header */ +CHECKSUM equ -(MAGIC + FLAGS) /* Checksum required */ + +section .text +align 4 +MultiBootHeader: + dd MAGIC + dd FLAGS + dd CHECKSUM + +/* Reserve initial kernel stack space */ + +STACKSIZE equ 0x4000 /* That's 16k */ + +loader: + mov esp, stack+STACKSIZE /* Set up the stack */ + push eax /* Pass Multiboot magic number */ + push ebx /* Pass Multiboot info structure */ + + call up_lowsetup /* Low-level, pre-OS initialization */ + call os_start /* Start NuttX */ + + cli +hang: + hlt /* Halt machine should NuttX return */ + jmp hang + +section .bss +align 4 +stack: + resb STACKSIZE /* Reserve 16k stack on a doubleword boundary */ + +#else /* GAS */ + + .global loader /* Making entry point visible to linker */ + .global os_start /* os_start is defined elsewhere */ + .global up_lowsetup /* up_lowsetup is defined elsewhere */ + +/* 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 */ + + .align 4 + .long MAGIC + .long FLAGS + .long CHECKSUM + +/* Reserve initial kernel stack space */ + + .set STACKSIZE, 0x4000 /* That is, 16k */ + .comm stack, STACKSIZE, 32 /* Reserve 16k stack on a quadword boundary */ + +loader: + mov $(stack + STACKSIZE), %esp /* Set up the stack */ + push %eax /* Multiboot magic number */ + push %ebx /* Multiboot data structure */ + + call up_lowsetup /* Low-level, pre-OS initialization */ + call os_start /* Start NuttX */ + + cli +hang: + hlt /* Halt machine should NuttX return */ + jmp hang +#endif + .end +#endif \ No newline at end of file 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 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include "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..601f84b77 --- /dev/null +++ b/nuttx/arch/x86/src/qemu/qemu_internal.h @@ -0,0 +1,389 @@ +/************************************************************************************ + * arch/x86/src/qemu/qemu_internal.h + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __ARCH_X86_SRC_QEMU_QEMU_INTERNAL_H +#define __ARCH_X86_SRC_QEMU_QEMU_INTERNAL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include +#include +#include + +#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 + +#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_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 + * + * 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 + +#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..1d72bd643 --- /dev/null +++ b/nuttx/arch/x86/src/qemu/qemu_saveusercontext.S @@ -0,0 +1,130 @@ +/************************************************************************** + * arch/x86/src/qemu/up_saveusercontext.S + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **************************************************************************/ + +/************************************************************************** + * Conditional Compilation Options + **************************************************************************/ + +/************************************************************************** + * Included Files + **************************************************************************/ + +#include +#include +#include "up_internal.h" + +/************************************************************************** + * Private Definitions + **************************************************************************/ + +#ifdef __CYGWIN__ +# define SYMBOL(s) _##s +#else +# define SYMBOL(s) s +#endif + +/************************************************************************** + * Private Types + **************************************************************************/ + +/************************************************************************** + * Private Function Prototypes + **************************************************************************/ + +/************************************************************************** + * Global Variables + **************************************************************************/ + +/************************************************************************** + * Private Variables + **************************************************************************/ + +/************************************************************************** + * Private Functions + **************************************************************************/ + +/************************************************************************** + * Public Functions + **************************************************************************/ + +/************************************************************************** + * Name: up_saveusercontext + * + * Full C prototype: + * int up_saveusercontext(uint32_t *regs); + * + **************************************************************************/ + +#ifdef CONFIG_X86_NASM +# warning "No Nasm support" +#else + .text + .globl SYMBOL(up_saveusercontext) +#ifndef __CYGWIN__ + .type SYMBOL(up_saveusercontext), @function +#endif +SYMBOL(up_saveusercontext): + + /* %ebx, %esi, %edi, and %ebp must be preserved. + * save %ebx, $esi, and %edi now... */ + + movl 4(%esp), %eax + movl %ebx, (REG_EBX)(%eax) + movl %esi, (REG_ESI)(%eax) + movl %edi, (REG_EDI)(%eax) + + /* Save the value of SP as will be after we return */ + + leal 4(%esp), %ecx + movl %ecx, (REG_SP)(%eax) + + /* Save the return PC */ + + movl 0(%esp), %ecx + movl %ecx, (REG_PC)(%eax) + + /* Save the framepointer */ + + movl %ebp, (REG_EBP)(%eax) + + /* And return 0 */ + + xorl %eax, %eax + ret +#ifndef __CYGWIN__ + .size SYMBOL(up_saveusercontext), . - SYMBOL(up_saveusercontext) +#endif + .end +#endif -- cgit v1.2.3