summaryrefslogtreecommitdiff
path: root/nuttx/arch/pjrc-8051/src
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-03-02 21:29:08 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-03-02 21:29:08 +0000
commit5288ccf79e6d13f27c18a3fd9765804e8c722968 (patch)
treefe74d5a325fd4e1e6a94f115e94e9925591e3b8c /nuttx/arch/pjrc-8051/src
parent36727bb989aaf6110386f75262bd6a5f6dbec809 (diff)
downloadpx4-nuttx-5288ccf79e6d13f27c18a3fd9765804e8c722968.tar.gz
px4-nuttx-5288ccf79e6d13f27c18a3fd9765804e8c722968.tar.bz2
px4-nuttx-5288ccf79e6d13f27c18a3fd9765804e8c722968.zip
Import 8051 support
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@30 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/pjrc-8051/src')
-rw-r--r--nuttx/arch/pjrc-8051/src/Makefile134
-rw-r--r--nuttx/arch/pjrc-8051/src/up_allocateheap.c79
-rw-r--r--nuttx/arch/pjrc-8051/src/up_assert.c80
-rw-r--r--nuttx/arch/pjrc-8051/src/up_blocktask.c171
-rw-r--r--nuttx/arch/pjrc-8051/src/up_exit.c111
-rw-r--r--nuttx/arch/pjrc-8051/src/up_head.S229
-rw-r--r--nuttx/arch/pjrc-8051/src/up_idle.c79
-rw-r--r--nuttx/arch/pjrc-8051/src/up_initialize.c98
-rw-r--r--nuttx/arch/pjrc-8051/src/up_initialstate.c108
-rw-r--r--nuttx/arch/pjrc-8051/src/up_internal.h125
-rw-r--r--nuttx/arch/pjrc-8051/src/up_interruptcontext.c68
-rw-r--r--nuttx/arch/pjrc-8051/src/up_irq.c157
-rw-r--r--nuttx/arch/pjrc-8051/src/up_putc.c78
-rw-r--r--nuttx/arch/pjrc-8051/src/up_releasepending.c134
-rw-r--r--nuttx/arch/pjrc-8051/src/up_reprioritizertr.c181
-rw-r--r--nuttx/arch/pjrc-8051/src/up_restorecontext.c156
-rw-r--r--nuttx/arch/pjrc-8051/src/up_savecontext.c167
-rw-r--r--nuttx/arch/pjrc-8051/src/up_unblocktask.c164
18 files changed, 2319 insertions, 0 deletions
diff --git a/nuttx/arch/pjrc-8051/src/Makefile b/nuttx/arch/pjrc-8051/src/Makefile
new file mode 100644
index 000000000..5adb30284
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/Makefile
@@ -0,0 +1,134 @@
+############################################################
+# Makefile
+#
+# Copyright (C) 2007 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name Gregory Nutt 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
+
+MKDEP = $(TOPDIR)/tools/mkdeps.sh
+CFLAGS += -I$(TOPDIR)/sched
+ASFLAGS = -x -j -g -l -s -p
+CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) -D__ASSEMBLY__
+
+SSRCS =
+ASRCS = $(SSRCS:.S=$(ASMEXT))
+AOBJS = $(ASRCS:$(ASMEXT)=$(OBJEXT))
+CSRCS = up_initialize.c up_idle.c up_interruptcontext.c \
+ up_initialstate.c up_unblocktask.c up_blocktask.c \
+ up_releasepending.c up_reprioritizertr.c \
+ up_exit.c up_assert.c up_allocateheap.c \
+ up_irq.c up_savecontext.c up_restorecontext.c up_putc.c
+COBJS = $(CSRCS:.c=$(OBJEXT))
+SRCS = $(SSRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+SDCCLIBDIR = /usr/local/share/sdcc/lib/large
+SDCCPATH = -L$(SDCCLIBDIR)
+SDCCLIBS = -llibfloat.lib -llibint.lib -lliblong.lib -llibmysdcc.lib -lmcs51.lib
+
+LINKSSRCS = up_head.S
+LINKASRCS = $(LINKSSRCS:.S=$(ASMEXT))
+LINKOBJS = $(LINKASRCS:$(ASMEXT)=$(OBJEXT))
+LINKLIBS =
+LDPATHES = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
+LDLIBS = $(addprefix -l,$(notdir $(LINKLIBS)))
+
+LDFLAGS = --model-large --nostdlib \
+ --data-loc 0x30 --iram-size 0x100 \
+ --code-loc 0x2040 --code-size 0x5fc0 \
+ --xram-loc 0x0100 --xram-size 0x1f00
+
+HEAP_START = ${shell cat pass1.mem | grep "EXTERNAL RAM" | sed -e "s/[ ][ ]*/ /g" | cut -d' ' -f5}
+
+DEPSRCS = $(SRCS) $(LINKSSRCS)
+
+all: up_head$(OBJEXT) libarch$(LIBEXT)
+
+$(ASRCS) $(LINKASRCS): %$(ASMEXT): %.S
+ $(CPP) -P $(CPPFLAGS) -D__ASSEMBLY__ -DUP_HEAP_START=0x0100 -DUP_HEAP_END=0x2000 $< -o $@
+
+$(AOBJS) $(LINKOBJS): $(ASRCS) $(LINKASRCS)
+ $(AS) $(ASFLAGS) $<
+
+$(COBJS): %$(OBJEXT): %.c
+ $(CC) -c $(CFLAGS) -DUP_HEAP_START=0x0100 -DUP_HEAP_END=0x2000 $< -o $@
+
+# Combine all objects in this directory into a library
+
+libarch$(LIBEXT): $(OBJS)
+ ( for obj in $(OBJS) ; do \
+ $(AR) $@ $${obj} || \
+ { echo "$(AR) $@ $${obj} FAILED!" ; exit 1 ; } ; \
+ done ; )
+
+# This is a kludge to work around some conflicting symbols in libsdcc.lib
+
+$(SDCCLIBDIR)/libmysdcc.lib: $(SDCCLIBDIR)/libsdcc.lib
+ @cat $(SDCCLIBDIR)/libsdcc.lib | \
+ grep -v calloc | grep -v malloc | grep -v realloc | \
+ grep -v free | grep -v vprintf | grep -v _strncpy | \
+ grep -v _strchr | grep -v _strlen | grep -v _strcmp | \
+ grep -v _strcpy | grep -v _memcmp | grep -v _memcpy | \
+ grep -v _memset \
+ > libmysdcc.lib
+ @sudo mv -f libmysdcc.lib $(SDCCLIBDIR)/libmysdcc.lib
+
+# This target builds the final executable
+
+pass1$(EXEEXT): $(SDCCLIBDIR)/libmysdcc.lib $(LINKOBJS)
+ $(CC) $(LDFLAGS) $(LDPATHES) $(SDCCPATH) $(LINKOBJS) $(LDLIBS) $(SDCCLIBS) -o pass1.ihx
+
+nuttx$(EXEEXT): pass1$(EXEEXT)
+ $(CC) -c $(CFLAGS) -DUP_HEAP_START=$(HEAP_START) -DUP_HEAP_END=0x2000 \
+ up_allocateheap.c -o up_allocateheap$(OBJEXT)
+ @rm -f pass1.*
+ $(CC) $(LDFLAGS) $(LDPATHES) $(SDCCPATH) $(LINKOBJS) $(LDLIBS) $(SDCCLIBS) -o nuttx.ihx
+ packihx nuttx.ihx > $(TOPDIR)/nuttx$(EXEEXT)
+ @cp -f nuttx.map $(TOPDIR)/.
+
+# Build dependencies
+
+.depend: Makefile $(DEPSRCS)
+ $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ touch $@
+
+depend: .depend
+
+clean:
+ rm -f libarch$(LIBEXT) *.asm *.rel *.lst *.rst *.sym *.adb *.lnk *.map *.mem *.ihx *.hex *~
+ if [ ! -z "$(OBJEXT)" ]; then rm -f *$(OBJEXT); fi
+
+distclean: clean
+ rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/arch/pjrc-8051/src/up_allocateheap.c b/nuttx/arch/pjrc-8051/src/up_allocateheap.c
new file mode 100644
index 000000000..6a874ed2a
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_allocateheap.c
@@ -0,0 +1,79 @@
+/************************************************************
+ * up_allocateheap.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include "os_internal.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)
+{
+ *heap_start = (FAR void*)UP_HEAP_START;
+ *heap_size = UP_HEAP_END - UP_HEAP_START;
+}
diff --git a/nuttx/arch/pjrc-8051/src/up_assert.c b/nuttx/arch/pjrc-8051/src/up_assert.c
new file mode 100644
index 000000000..b9ac5db43
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_assert.c
@@ -0,0 +1,80 @@
+/************************************************************
+ * up_assert.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <stdlib.h>
+#include <assert.h>
+#include <debug.h>
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_assert
+ ************************************************************/
+
+void up_assert(void)
+{
+ dbg("Assertion failed\n");
+ exit(EXIT_FAILURE);
+}
+
+/************************************************************
+ * Name: up_assert_code
+ ************************************************************/
+
+void up_assert_code(int errorcode)
+{
+ dbg("Assertion failed with error code: %d\n", errcode);
+ exit(errorcode);
+}
diff --git a/nuttx/arch/pjrc-8051/src/up_blocktask.c b/nuttx/arch/pjrc-8051/src/up_blocktask.c
new file mode 100644
index 000000000..4a15a817a
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_blocktask.c
@@ -0,0 +1,171 @@
+/************************************************************
+ * up_blocktask.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include "os_internal.h"
+#include "up_internal.h"
+
+/************************************************************
+ * Private Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Funtions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_block_task
+ *
+ * Description:
+ * The currently executing task at the head of
+ * the ready to run list must be stopped. Save its context
+ * and move it to the inactive list specified by task_state.
+ *
+ * Inputs:
+ * tcb: Refers to a task in the ready-to-run list (normally
+ * the task at the the head of the list). It most be
+ * stopped, its context saved and moved into one of the
+ * waiting task lists. It it was the task at the head
+ * of the ready-to-run list, then a context to the new
+ * ready to run task must be performed.
+ * task_state: Specifies which waiting task list should be
+ * hold the blocked task TCB.
+ *
+ ************************************************************/
+
+void up_block_task(FAR _TCB *tcb, tstate_t task_state)
+{
+ /* Verify that the context switch can be performed */
+
+ if ((tcb->task_state < FIRST_READY_TO_RUN_STATE) ||
+ (tcb->task_state > LAST_READY_TO_RUN_STATE))
+ {
+ PANIC(OSERR_BADBLOCKSTATE);
+ }
+ else
+ {
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ boolean switch_needed;
+
+ dbg("Blocking TCB=%p\n", tcb);
+
+ /* Remove the tcb task from the ready-to-run list. If we
+ * are blocking the task at the head of the task list (the
+ * most likely case), then a context switch to the next
+ * ready-to-run task is needed. In this case, it should
+ * also be true that rtcb == tcb.
+ */
+
+ switch_needed = sched_removereadytorun(tcb);
+
+ /* Add the task to the specified blocked task list */
+
+ sched_addblocked(tcb, (tstate_t)task_state);
+
+ /* If there are any pending tasks, then add them to the g_readytorun
+ * task list now
+ */
+
+ if (g_pendingtasks.head)
+ {
+ switch_needed |= sched_mergepending();
+ }
+
+ /* Now, perform the context switch if one is needed */
+
+ if (switch_needed)
+ {
+ /* Are we in an interrupt handler? */
+
+ if (g_ininterrupt)
+ {
+#if 0
+# warning REVISIT
+ /* Yes, then we have to do things differently.
+ * Just copy the current registers into the OLD rtcb.
+ */
+
+ up_copystate(&tcb->xcp, current_regs);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+ dbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_copystate(current_regs, &tcb->xcp);
+#endif
+ }
+
+ /* Copy the user C context into the TCB at the (old) head of the
+ * g_readytorun Task list. if up_savecontext returns a non-zero
+ * value, then this is really the previously running task restarting!
+ */
+
+ else if (!up_savecontext(&rtcb->xcp))
+ {
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ dbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_restorecontext(&rtcb->xcp);
+ }
+ }
+ }
+}
diff --git a/nuttx/arch/pjrc-8051/src/up_exit.c b/nuttx/arch/pjrc-8051/src/up_exit.c
new file mode 100644
index 000000000..5a98496a6
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_exit.c
@@ -0,0 +1,111 @@
+/************************************************************
+ * up_exit.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include "os_internal.h"
+#include "up_internal.h"
+
+/************************************************************
+ * Private Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Funtions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: _exit
+ *
+ * Description:
+ * This function causes the currently executing task to cease
+ * to exist. This is a special case of task_delete().
+ *
+ ************************************************************/
+
+void _exit(int status)
+{
+ FAR _TCB* tcb = (FAR _TCB*)g_readytorun.head;
+
+ dbg("TCB=%p exitting\n", tcb);
+
+ /* Remove the tcb task from the ready-to-run list. We can
+ * ignore the return value because we know that a context
+ * switch is needed.
+ */
+
+ (void)sched_removereadytorun(tcb);
+
+ /* Move the TCB to the specified blocked task list and delete it */
+
+ sched_addblocked(tcb, TSTATE_TASK_INACTIVE);
+ task_delete(tcb->pid);
+
+ /* If there are any pending tasks, then add them to the g_readytorun
+ * task list now
+ */
+
+ if (g_pendingtasks.head)
+ {
+ (void)sched_mergepending();
+ }
+
+ /* Now, perform the context switch to the new ready-to-run task at the
+ * head of the list.
+ */
+
+ tcb = (FAR _TCB*)g_readytorun.head;
+ dbg("New Active Task TCB=%p\n", tcb);
+
+ /* Then switch contexts */
+
+ up_restorecontext(&tcb->xcp);
+}
+
diff --git a/nuttx/arch/pjrc-8051/src/up_head.S b/nuttx/arch/pjrc-8051/src/up_head.S
new file mode 100644
index 000000000..ff2f3a5c9
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_head.S
@@ -0,0 +1,229 @@
+/************************************************************
+ * up_head.S
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/irq.h>
+#include "up_internal.h"
+
+ .module up_head
+ .optsdcc -mmcs51 --model-large
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+ .area REG_BANK_0 (REL,OVR,DATA)
+ .ds 8
+
+/************************************************************
+ * Public Data
+ ************************************************************/
+
+ .globl _g_ininterrupt
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+ .globl _irq_dispatch
+
+/************************************************************
+ * Program entry points
+ ************************************************************/
+
+/* Program entry is through PROGRAM_BASE. This is just a
+ * branch to our start up logic.
+ */
+
+ .area CODE1 (ABS)
+ .org PROGRAM_BASE
+ ljmp start
+
+/* These are indirect interrupt vectors. Logic in PAULMON2,
+ * captures the interrupt vectors (near address 0x0000) and
+ * re-routes them through the following entry points.
+ *
+ * Each of these saves acc and ie then passes the IRQ number
+ * to higher level logic in a
+ */
+
+ .org PM2_VECTOR_EXTINT0
+ push acc
+ push ie
+ mov a, #EXT_INT0_IRQ
+ ljmp _up_interrupt
+
+ .org PM2_VECTOR_TIMER0
+ push acc
+ push ie
+ mov a, #TIMER0_IRQ
+ ljmp _up_interrupt
+
+ .org PM2_VECTOR_EXTINT1
+ push acc
+ push ie
+ mov a, #EXT_INT1_IRQ
+ ljmp _up_interrupt
+
+ .org PM2_VECTOR_TIMER1
+ push acc
+ push ie
+ mov a, #TIMER1_IRQ
+ ljmp _up_interrupt
+
+ .org PM2_VECTOR_UART
+ push acc
+ push ie
+ mov a, #UART_IRQ
+ ljmp _up_interrupt
+
+ .org PM2_VECTOR_TIMER2
+ push acc
+ push ie
+ mov a, #TIMER2_IRQ
+ ljmp _up_interrupt
+
+/************************************************************
+ * Name: start
+ *
+ * Description:
+ * This is the initial entry point into NuttX
+ *
+ ************************************************************/
+
+start:
+ mov sp, #(STACK_BASE-1)
+ ljmp _os_start
+
+/************************************************************
+ * Name: up_interrupt
+ *
+ * Description:
+ * All interrupts vector to this point with:
+ *
+ * (1) acc and ie on the stack and
+ * (2) the IRQ number in the accumulator
+ *
+ ************************************************************/
+
+_up_interrupt:
+ ar2 = 0x02
+ ar3 = 0x03
+ ar4 = 0x04
+ ar5 = 0x05
+ ar6 = 0x06
+ ar7 = 0x07
+ ar0 = 0x00
+ ar1 = 0x01
+
+ /* Push ACC and IE. Then disable interrupts */
+
+ push acc
+ push ie
+ clr ea
+
+ /* Now push the remaining registers with interrupt disabled */
+
+ push dpl
+ push dph
+ push b
+ push ar2
+ push ar3
+ push ar4
+ push ar5
+ push ar6
+ push ar7
+ push ar0
+ push ar1
+ push psw
+ clr psw
+ push _bp
+
+ /* Now call void irq_dispatch(int irq, FAR void *context)
+ *
+ * First, create the first argument as (int)irqno
+ */
+
+ mov dpl, a
+ clr dph
+
+ /* Create the second argument (void *context) on the stack */
+
+ push sp
+ clr a
+ push acc
+
+ /* Then dispatch the IRQ */
+
+ lcall _irq_dispatch
+
+ /* Clean up the stack */
+
+ dec sp
+ dec sp
+
+ /* Then return from the interrupt */
+
+ pop _bp
+ pop psw
+ pop ar1
+ pop ar0
+ pop ar7
+ pop ar6
+ pop ar5
+ pop ar4
+ pop ar3
+ pop ar2
+ pop b
+ pop dph
+ pop dpl
+
+ /* Restore the interrupt state per the stored IE value */
+
+ pop acc
+ jb acc.7, 00001$
+ clr ie.7
+ sjmp 00002$
+ 00001$:
+ setb ie.7
+ 00002$:
+
+ /* Finally pop off the ACC, which was the first register saved. */
+
+ pop acc
+ reti
diff --git a/nuttx/arch/pjrc-8051/src/up_idle.c b/nuttx/arch/pjrc-8051/src/up_idle.c
new file mode 100644
index 000000000..fcc89ed9b
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_idle.c
@@ -0,0 +1,79 @@
+/************************************************************
+ * up_idle.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/arch.h>
+#include "up_internal.h"
+
+/************************************************************
+ * Private 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)
+{
+}
+
diff --git a/nuttx/arch/pjrc-8051/src/up_initialize.c b/nuttx/arch/pjrc-8051/src/up_initialize.c
new file mode 100644
index 000000000..20d2e8122
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_initialize.c
@@ -0,0 +1,98 @@
+/************************************************************
+ * up_initialize.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/arch.h>
+#include <nuttx/fs.h>
+#include "up_internal.h"
+
+/************************************************************
+ * Private Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/* TRUE if processing an interrupt */
+
+boolean g_ininterrupt;
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * 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 init process has been started and before the
+ * libraries have been initialized. OS services and driver
+ * services are available.
+ *
+ ************************************************************/
+
+void up_initialize(void)
+{
+ /* Initialize global variables */
+
+ g_ininterrupt = FALSE;
+
+ /* Initialize the interrupt subsystem */
+
+ /* Initialize the system timer interrupt */
+
+ /* Initialize the serial console support */
+}
+
diff --git a/nuttx/arch/pjrc-8051/src/up_initialstate.c b/nuttx/arch/pjrc-8051/src/up_initialstate.c
new file mode 100644
index 000000000..930f16873
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_initialstate.c
@@ -0,0 +1,108 @@
+/************************************************************
+ * up_initialstate.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include "up_internal.h"
+
+/************************************************************
+ * Private Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_initial_state
+ *
+ * Description:
+ * A new thread is being started and a new TCB
+ * has been created. This function is called to initialize
+ * the processor specific portions of the new TCB.
+ *
+ * This function must setup the intial architecture registers
+ * and/or stack so that execution will begin at tcb->start
+ * on the next context switch.
+ *
+ ************************************************************/
+
+void up_initial_state(FAR _TCB *tcb)
+{
+ FAR ubyte *frame = tcb->xcp.stack;
+
+ /* This is the form of initial stack frame
+ *
+ * This initial stack frame will be configured to hold.
+ * (1) The 16-bit return address of either:
+ *
+ * void task_start(void);
+ * void pthread_start(void)
+ *
+ * The return address is stored at the top of stack.
+ * so that the RETI instruction will work:
+ *
+ * PC15-8 <- ((SP))
+ * (SP) <- (SP) -1
+ * PC7-0 <- ((SP))
+ * (SP) <- (SP) -1
+ */
+
+ frame[FRAME_RETLS] = (((uint16)tcb->start) & 0xff);
+ frame[FRAME_RETMS] = (((uint16)tcb->start) >> 8);
+
+ /* Then the context save area which can be indexed with
+ * the following definitions (relative to the beginning of
+ * the initial frame.
+ */
+
+ frame[FRAME_IE] = 0x80;
+ frame[FRAME_PSW] = 0;
+
+ tcb->xcp.nbytes = FRAME_SIZE;
+}
diff --git a/nuttx/arch/pjrc-8051/src/up_internal.h b/nuttx/arch/pjrc-8051/src/up_internal.h
new file mode 100644
index 000000000..27a83585f
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_internal.h
@@ -0,0 +1,125 @@
+/**************************************************************************
+ * up_internal.h
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt 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_UP_INTERNAL_H
+#define __ARCH_UP_INTERNAL_H
+
+/**************************************************************************
+ * Included Files
+ **************************************************************************/
+
+/**************************************************************************
+ * Public Definitions
+ **************************************************************************/
+
+/* Memory Map
+ *
+ * BEGIN END DESCRIPTION
+ * 0x0000 0x1fff CODE: ROM containg PAULMON2
+ * DATA: RAM for program variables
+ * 0x2000 0x7fff COMMON: RAM for program code or
+ * variables
+ * 0x8000 0xf7ff COMMON: FLASH for program code
+ * 0xf800 0xfeff COMMON: Peripherals
+ * 0xff00 0xffff COMMON: unused
+ *
+ * Program code may be loaded at the RAM location 0x2000-0x7fff
+ * for testing. If loaded into the FLASH location at
+ * 0x8000-0xf7ff, PAULMON2 will automatically write the program
+ * into flash. The program is configured in the RAM-based test
+ * configuration:
+ */
+
+#define RAM_BLOCK_START IRAM_SIZE
+#define RAM_BLOCK_END 0x1fff
+
+#define PROGRAM_BASE 0x2000
+#define PROGRAM_END 0x7fff
+
+#define FLASH_BASE 0x8000
+#define FLASH_END 0xf7ff
+
+/* Well-known entry points to access PAULMON2's built-in functions */
+
+#define PM2_ENTRY_PHEX1 0x002e
+#define PM2_ENTRY_COUT 0x0030
+#define PM2_ENTRY_CIN 0x0032
+#define PM2_ENTRY_PHEX 0x0034
+#define PM2_ENTRY_PHEX16 0x0036
+#define PM2_ENTRY_PSTR 0x0038
+#define PM2_ENTRY_ESC 0x003e
+#define PM2_ENTRY_UPPER 0x0040
+#define PM2_ENTRY_PINT8U 0x004D
+#define PM2_ENTRY_PINT8 0x0050
+#define PM2_ENTRY_PINT16U 0x0053
+#define PM2_ENTRY_NEWLINE 0x0048
+#define PM2_ENTRY_PRGM 0x0059
+#define PM2_ENTRY_ERBLOCK 0x0067
+
+#define PM2_VECTOR_BASE PROGRAM_BASE
+#define PM2_VECTOR_EXTINT0 (PM2_VECTOR_BASE + 3)
+#define PM2_VECTOR_TIMER0 (PM2_VECTOR_BASE + 11)
+#define PM2_VECTOR_EXTINT1 (PM2_VECTOR_BASE + 19)
+#define PM2_VECTOR_TIMER1 (PM2_VECTOR_BASE + 27)
+#define PM2_VECTOR_UART (PM2_VECTOR_BASE + 35)
+#define PM2_VECTOR_TIMER2 (PM2_VECTOR_BASE + 43)
+
+/**************************************************************************
+ * Public Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Public Variables
+ **************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* TRUE if processing an interrupt */
+
+extern boolean g_ininterrupt;
+
+#endif /* __ASSEMBLY */
+
+/**************************************************************************
+ * Public Function Prototypes
+ **************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+extern ubyte up_savecontext(FAR struct xcptcontext *context);
+extern void up_restorecontext(FAR struct xcptcontext *context);
+
+#endif /* __ASSEMBLY */
+#endif /* __ARCH_UP_INTERNAL_H */
diff --git a/nuttx/arch/pjrc-8051/src/up_interruptcontext.c b/nuttx/arch/pjrc-8051/src/up_interruptcontext.c
new file mode 100644
index 000000000..2743ed7b0
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_interruptcontext.c
@@ -0,0 +1,68 @@
+/************************************************************
+ * up_interruptcontext.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+#include "up_internal.h"
+
+/************************************************************
+ * Private Types
+ ************************************************************/
+
+/************************************************************
+ * Private Function Prototypes
+ ************************************************************/
+
+/************************************************************
+ * Global Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_interrupt_context
+ *
+ * Description: Return TRUE is we are currently executing in
+ * the interrupt handler context.
+ ************************************************************/
+
+boolean up_interrupt_context(void)
+{
+ return g_ininterrupt;
+}
diff --git a/nuttx/arch/pjrc-8051/src/up_irq.c b/nuttx/arch/pjrc-8051/src/up_irq.c
new file mode 100644
index 000000000..c524fe3e7
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_irq.c
@@ -0,0 +1,157 @@
+/************************************************************
+ * up_irq.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/irq.h>
+#include "up_internal.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Public Data
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: irq_initialize
+ ************************************************************/
+
+void up_irqinitialize(void)
+{
+}
+
+/************************************************************
+ * Name: irqsave
+ *
+ * Description:
+ * Disable all IRQs
+ *
+ ************************************************************/
+
+irqstate_t irqsave(void) _naked
+{
+ _asm
+ mov ie, dpl
+ clr ea
+ ret
+ _endasm;
+}
+
+/************************************************************
+ * Name: irqrestore
+ *
+ * Description:
+ * Restore a previous interrupt state
+ *
+ ************************************************************/
+
+void irqrestore(irqstate_t flags) __naked
+{
+ flags; /* Avoid compiler warning about unused argument */
+ _asm
+ mov ie, dpl
+ ret
+ _endasm;
+}
+
+/************************************************************
+ * Name: up_disable_irq
+ *
+ * Description:
+ * Disable the IRQ specified by 'irq'
+ *
+ ************************************************************/
+
+static void _up_disable_irq(ubyte iebit) __naked
+{
+ _asm
+ mov a, ie
+ orl a, dpl
+ mov ie, a
+ ret
+ _endasm;
+}
+
+void up_disable_irq(int irq)
+{
+ if ((unsigned)irq < NR_IRQS)
+ {
+ _up_disable_irq(1 << irq);
+ }
+}
+
+/************************************************************
+ * Name: up_enable_irq
+ *
+ * Description:
+ * Enable the IRQ specified by 'irq'
+ *
+ ************************************************************/
+
+static void _up_enable_irq(ubyte iebit) __naked
+{
+ _asm
+ mov a, ie
+ anl a, dpl
+ mov ie, a
+ ret
+ _endasm;
+}
+
+void up_enable_irq(int irq)
+{
+ if ((unsigned)irq < NR_IRQS)
+ {
+ _up_enable_irq(~(1 << irq));
+ }
+}
diff --git a/nuttx/arch/pjrc-8051/src/up_putc.c b/nuttx/arch/pjrc-8051/src/up_putc.c
new file mode 100644
index 000000000..d2e486829
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_putc.c
@@ -0,0 +1,78 @@
+/************************************************************
+ * up_putc.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/arch.h>
+#include "up_internal.h"
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+static void _up_putc(int ch) __naked
+{
+#if 0
+ ch; /* To avoid unreferenced argument warning */
+ _asm
+ mov a, dpl
+ ljmp PM2_ENTRY_COUT
+ _endasm;
+#else
+ ch;
+ _asm
+ mov a, dpl
+cout: jnb ti, cout
+ clr ti
+ mov sbuf, a
+ ret
+ _endasm;
+#endif
+}
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+int up_putc(int ch)
+{
+ _up_putc(ch);
+ return ch;
+}
+
diff --git a/nuttx/arch/pjrc-8051/src/up_releasepending.c b/nuttx/arch/pjrc-8051/src/up_releasepending.c
new file mode 100644
index 000000000..99c20ec23
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_releasepending.c
@@ -0,0 +1,134 @@
+/************************************************************
+ * up_releasepending.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include "os_internal.h"
+#include "up_internal.h"
+
+/************************************************************
+ * Private Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Funtions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_release_pending
+ *
+ * Description:
+ * Release and ready-to-run tasks that have
+ * collected in the pending task list. This can call a
+ * context switch if a new task is placed at the head of
+ * the ready to run list.
+ *
+ ************************************************************/
+
+void up_release_pending(void)
+{
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+
+ dbg("From TCB=%p\n", rtcb);
+
+ /* Merge the g_pendingtasks list into the g_readytorun task list */
+
+ /* sched_lock(); */
+ if (sched_mergepending())
+ {
+ /* The currently active task has changed! We will need to
+ * switch contexts. First check if we are operating in
+ * interrupt context:
+ */
+
+ if (g_ininterrupt)
+ {
+#if 0
+# warning REVISIT
+ /* Yes, then we have to do things differently.
+ * Just copy the current registers into the OLD rtcb.
+ */
+
+ up_copystate(&tcb->xcp, current_regs);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+ dbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_copystate(current_regs, &tcb->xcp);
+#endif
+ }
+
+ /* Copy the exception context into the TCB of the task that
+ * was currently active. if up_savecontext returns a non-zero
+ * value, then this is really the previously running task
+ * restarting!
+ */
+
+ else if (!up_savecontext(&rtcb->xcp))
+ {
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ dbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_restorecontext(&rtcb->xcp);
+ }
+ }
+}
diff --git a/nuttx/arch/pjrc-8051/src/up_reprioritizertr.c b/nuttx/arch/pjrc-8051/src/up_reprioritizertr.c
new file mode 100644
index 000000000..dbb9db3c4
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_reprioritizertr.c
@@ -0,0 +1,181 @@
+/************************************************************
+ * up_reprioritizertr.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include "os_internal.h"
+#include "up_internal.h"
+
+/************************************************************
+ * Private Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Funtions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_reprioritize_rtr
+ *
+ * Description:
+ * Called when the priority of a running or
+ * ready-to-run task changes and the reprioritization will
+ * cause a context switch. Two cases:
+ *
+ * 1) The priority of the currently running task drops and the next
+ * task in the ready to run list has priority.
+ * 2) An idle, ready to run task's priority has been raised above the
+ * the priority of the current, running task and it now has the
+ * priority.
+ *
+ * Inputs:
+ * tcb: The TCB of the task that has been reprioritized
+ * priority: The new task priority
+ *
+ ************************************************************/
+
+void up_reprioritize_rtr(FAR _TCB *tcb, ubyte priority)
+{
+ /* Verify that the caller is sane */
+
+ if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
+ tcb->task_state > LAST_READY_TO_RUN_STATE ||
+ priority < SCHED_PRIORITY_MIN ||
+ priority > SCHED_PRIORITY_MAX)
+ {
+ PANIC(OSERR_BADREPRIORITIZESTATE);
+ }
+ else
+ {
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ boolean switch_needed;
+
+ dbg("TCB=%p PRI=%d\n", tcb, priority);
+
+ /* Remove the tcb task from the ready-to-run list.
+ * sched_removereadytorun will return TRUE if we just
+ * remove the head of the ready to run list.
+ */
+
+ switch_needed = sched_removereadytorun(tcb);
+
+ /* Setup up the new task priority */
+
+ tcb->sched_priority = (ubyte)priority;
+
+ /* Return the task to the specified blocked task list.
+ * sched_addreadytorun will return TRUE if the task was
+ * added to the new list. We will need to perform a context
+ * switch only if the EXCLUSIVE or of the two calls is non-zero
+ * (i.e., one and only one the calls changes the head of the
+ * ready-to-run list).
+ */
+
+ switch_needed ^= sched_addreadytorun(tcb);
+
+ /* Now, perform the context switch if one is needed */
+
+ if (switch_needed)
+ {
+ /* If we are going to do a context switch, then now is the right
+ * time to add any pending tasks back into the ready-to-run list.
+ * task list now
+ */
+
+ if (g_pendingtasks.head)
+ {
+ sched_mergepending();
+ }
+
+ /* Are we in an interrupt handler? */
+
+ if (g_ininterrupt)
+ {
+#if 0
+# warning REVISIT
+ /* Yes, then we have to do things differently.
+ * Just copy the current registers into the OLD rtcb.
+ */
+
+ up_copystate(&tcb->xcp, current_regs);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+ dbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_copystate(current_regs, &tcb->xcp);
+#endif
+ }
+ /* Copy the exception context into the TCB at the (old) head of the
+ * g_readytorun Task list. if up_savecontext returns a non-zero
+ * value, then this is really the previously running task restarting!
+ */
+
+ if (!up_savecontext(&rtcb->xcp))
+ {
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ dbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_restorecontext(&rtcb->xcp);
+ }
+ }
+ }
+}
diff --git a/nuttx/arch/pjrc-8051/src/up_restorecontext.c b/nuttx/arch/pjrc-8051/src/up_restorecontext.c
new file mode 100644
index 000000000..d1d095d91
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_restorecontext.c
@@ -0,0 +1,156 @@
+/**************************************************************************
+ * up_restorecontext.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ **************************************************************************/
+
+/**************************************************************************
+ * Included Files
+ **************************************************************************/
+
+#include <nuttx/irq.h>
+#include "up_internal.h"
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Function Prototypes
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_popcontext
+ *
+ * Description:
+ * Pop the current execution context from the stack and return to the
+ * execution context. Similar operations are executed from the interrupt
+ * state restore
+ *
+ * Inputs:
+ * None
+ *
+ * Return:
+ * This function does not return
+ *
+ **************************************************************************/
+
+static void up_popcontext(ubyte newsp) __naked
+
+{
+ _asm
+ pop _bp
+ pop psw
+ pop ar1
+ pop ar0
+ pop ar7
+ pop ar6
+ pop ar5
+ pop ar4
+ pop ar3
+ pop ar2
+ pop b
+ pop dph
+ pop dpl
+
+ /* Restore the interrupt state per the stored IE value */
+
+ pop acc
+ jb acc.7,00001$
+ clr ie.7
+ sjmp 00002$
+ 00001$:
+ setb ie.7
+ 00002$:
+
+ pop acc
+ ret
+ _endasm;
+}
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_restorecontext
+ *
+ * Description:
+ * Restore the stack specified in the context structure and return to
+ * that context
+ *
+ * Inputs:
+ * context - Holds the stack content of the context to return to
+ *
+ * Return:
+ * This function does not return.
+ *
+ **************************************************************************/
+
+void up_restorecontext(FAR struct xcptcontext *context)
+{
+ int nbytes = context->nbytes;
+ FAR ubyte *src = context->stack;
+ FAR ubyte *dest = (FAR ubyte*)STACK_BASE;
+
+ /* Interrupts should be disabled for the following. up_popcontext() will
+ * set the new interrupt state correctly.
+ */
+
+ (void)irqsave();
+
+ while (nbytes--)
+ {
+ *src++ = *dest++;
+ }
+
+ /* Then return to the restored context */
+
+ up_popcontext(context->nbytes + (STACK_BASE-1));
+}
+
diff --git a/nuttx/arch/pjrc-8051/src/up_savecontext.c b/nuttx/arch/pjrc-8051/src/up_savecontext.c
new file mode 100644
index 000000000..1405fce4d
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_savecontext.c
@@ -0,0 +1,167 @@
+/**************************************************************************
+ * up_savecontext.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt 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 <sys/types.h>
+#include <nuttx/irq.h>
+#include "up_internal.h"
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Function Prototypes
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_pushcontext
+ *
+ * Description:
+ * Push the current execution context onto the before the stack. Similar
+ * operations are executed from the interrupt state save.
+ *
+ * Inputs:
+ * None
+ *
+ * Return:
+ * Returns the stack pointer (always non-zero). However, when
+ * up_popcontext() executes, it will appear as a return from this
+ * function with return value == 0
+ *
+ **************************************************************************/
+
+static ubyte up_pushcontext(void) __naked
+{
+ /* Push the current execution context onto the stack. */
+
+ _asm
+ push acc
+ push ie
+ mov dptr, #0 /* Save return value (dpl) = 0 */
+ push dpl
+ push dph
+ push b
+ push ar2
+ push ar3
+ push ar4
+ push ar5
+ push ar6
+ push ar7
+ push ar0
+ push ar1
+ push psw
+ clr psw
+ push _bp
+
+ /* And return the current stack pointer value in dpl */
+
+ mov dpl, sp
+ ret
+ _endasm;
+}
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_savecontext
+ *
+ * Description:
+ * Push the current execution context onto the stack, then save the
+ * entire stack contents in the provided context structure.
+ *
+ * Inputs:
+ * context - the context structure in which to save the stack info
+ *
+ * Return
+ * 0 = Normal state save return
+ * 1 = This is the matching return from up_restorecontext()
+ *
+ **************************************************************************/
+
+ubyte up_savecontext(FAR struct xcptcontext *context)
+{
+ irqstate_t flags = irqsave();
+ ubyte sp = up_pushcontext();
+ if (sp)
+ {
+ /* Now copy the current stack frame (including the saved execution
+ * context) from internal RAM to XRAM.
+ */
+
+ ubyte nbytes = sp - (STACK_BASE-1);
+ FAR ubyte *src = (FAR ubyte*)STACK_BASE;
+ FAR ubyte *dest = context->stack;
+
+ /* Then copy the stack info into the context structure */
+
+ context->nbytes = nbytes;
+ while (nbytes--)
+ {
+ *dest++ = *src++;
+ }
+
+ /* Return zero so that the return behavior is similar to setjmp */
+
+ irqrestore(flags);
+ return 0;
+ }
+
+ /* Return one so that the return behavior is similar to setjmp */
+
+ irqrestore(flags);
+ return 1;
+}
diff --git a/nuttx/arch/pjrc-8051/src/up_unblocktask.c b/nuttx/arch/pjrc-8051/src/up_unblocktask.c
new file mode 100644
index 000000000..1c9494f36
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_unblocktask.c
@@ -0,0 +1,164 @@
+/************************************************************
+ * up_unblocktask.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include "os_internal.h"
+#include "up_internal.h"
+
+/************************************************************
+ * Private Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+/************************************************************
+ * Private Funtions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_unblock_task
+ *
+ * Description:
+ * A task is currently in an inactive task list
+ * but has been prepped to execute. Move the TCB to the
+ * ready-to-run list, restore its context, and start execution.
+ *
+ * Inputs:
+ * tcb: Refers to the tcb to be unblocked. This tcb is
+ * in one of the waiting tasks lists. It must be moved to
+ * the ready-to-run list and, if it is the highest priority
+ * ready to run taks, executed.
+ *
+ ************************************************************/
+
+void up_unblock_task(FAR _TCB *tcb)
+{
+ /* Verify that the context switch can be performed */
+
+ if ((tcb->task_state < FIRST_BLOCKED_STATE) ||
+ (tcb->task_state > LAST_BLOCKED_STATE))
+ {
+ PANIC(OSERR_BADUNBLOCKSTATE);
+ }
+ else
+ {
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+
+ dbg("Unblocking TCB=%p\n", tcb);
+
+ /* Remove the task from the blocked task list */
+
+ sched_removeblocked(tcb);
+
+ /* Reset its timeslice. This is only meaningful for round
+ * robin tasks but it doesn't here to do it for everything
+ */
+
+#if CONFIG_RR_INTERVAL > 0
+ tcb->timeslice = CONFIG_RR_INTERVAL;
+#endif
+
+ /* Add the task in the correct location in the prioritized
+ * g_readytorun task list
+ */
+
+ if (sched_addreadytorun(tcb))
+ {
+ /* The currently active task has changed! We need to do
+ * a context switch to the new task.
+ *
+ * Are we in an interrupt handler?
+ */
+
+ if (g_ininterrupt)
+ {
+#if 0
+# warning REVISIT
+ /* Yes, then we have to do things differently.
+ * Just copy the current registers into the OLD rtcb.
+ */
+
+ up_copystate(&tcb->xcp, current_regs);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (_TCB*)g_readytorun.head;
+ dbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_copystate(current_regs, &tcb->xcp);
+#endif
+ }
+
+ /* We are not in an interrupt andler. Copy the user C context
+ * into the TCB of the task that was previously active. if
+ * up_savecontext returns a non-zero value, then this is really the
+ * previously running task restarting!
+ */
+
+ else if (!up_savecontext(&rtcb->xcp))
+ {
+ /* Restore the exception context of the new task that is ready to
+ * run (probably tcb). This is the new rtcb at the head of the
+ * g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ dbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ up_restorecontext(&rtcb->xcp);
+ }
+ }
+ }
+}