summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-11 18:19:09 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-11 18:19:09 +0000
commit3b0eb489665d4d8422d34309a13b20fcf65f637a (patch)
tree865e706cf0ed1dbe84005bee16774f4f97055b4b
parentddfaa63ee4ff54b4f875b33cc62823fe73419164 (diff)
downloadpx4-nuttx-3b0eb489665d4d8422d34309a13b20fcf65f637a.tar.gz
px4-nuttx-3b0eb489665d4d8422d34309a13b20fcf65f637a.tar.bz2
px4-nuttx-3b0eb489665d4d8422d34309a13b20fcf65f637a.zip
untest z16f code
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@553 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/common/up_arch.h2
-rw-r--r--nuttx/arch/z16/include/z16f/irq.h67
-rw-r--r--nuttx/arch/z16/src/common/up_allocateheap.c98
-rw-r--r--nuttx/arch/z16/src/common/up_assert.c156
-rw-r--r--nuttx/arch/z16/src/common/up_blocktask.c173
-rw-r--r--nuttx/arch/z16/src/common/up_copystate.c78
-rw-r--r--nuttx/arch/z16/src/common/up_createstack.c128
-rw-r--r--nuttx/arch/z16/src/common/up_doirq.c104
-rw-r--r--nuttx/arch/z16/src/common/up_exit.c204
-rw-r--r--nuttx/arch/z16/src/common/up_idle.c107
-rw-r--r--nuttx/arch/z16/src/common/up_initialize.c169
-rw-r--r--nuttx/arch/z16/src/common/up_initialstate.c92
-rw-r--r--nuttx/arch/z16/src/common/up_internal.h15
-rw-r--r--nuttx/arch/z16/src/common/up_interruptcontext.c68
-rw-r--r--nuttx/arch/z16/src/common/up_mdelay.c94
-rw-r--r--nuttx/arch/z16/src/common/up_registerdump.c91
-rw-r--r--nuttx/arch/z16/src/common/up_releasepending.c137
-rw-r--r--nuttx/arch/z16/src/common/up_releasestack.c78
-rw-r--r--nuttx/arch/z16/src/common/up_reprioritizertr.c185
-rw-r--r--nuttx/arch/z16/src/common/up_schedulesigaction.c198
-rw-r--r--nuttx/arch/z16/src/common/up_sigdeliver.c143
-rw-r--r--nuttx/arch/z16/src/common/up_stackdump.c109
-rw-r--r--nuttx/arch/z16/src/common/up_udelay.c132
-rw-r--r--nuttx/arch/z16/src/common/up_unblocktask.c168
-rw-r--r--nuttx/arch/z16/src/common/up_usestack.c118
-rw-r--r--nuttx/arch/z16/src/z16f/Make.defs10
-rw-r--r--nuttx/arch/z16/src/z16f/chip.h224
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_clkinit.c245
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_irq.c197
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_timerisr.c135
-rw-r--r--nuttx/arch/z80/src/common/up_releasestack.c4
-rw-r--r--nuttx/arch/z80/src/common/up_udelay.c4
-rw-r--r--nuttx/arch/z80/src/common/up_usestack.c4
-rw-r--r--nuttx/configs/z16f2800100zcog/src/Makefile2
-rw-r--r--nuttx/configs/z16f2800100zcog/src/z16f_lowinit.c81
35 files changed, 3747 insertions, 73 deletions
diff --git a/nuttx/arch/arm/src/common/up_arch.h b/nuttx/arch/arm/src/common/up_arch.h
index 071e60d67..eb4770686 100644
--- a/nuttx/arch/arm/src/common/up_arch.h
+++ b/nuttx/arch/arm/src/common/up_arch.h
@@ -84,7 +84,7 @@ static inline void putreg16(uint16 val, unsigned int addr)
/* Most DM320 registers are 16-bits wide */
-#define getreg(a) getreg16(1)
+#define getreg(a) getreg16(a)
#define putreg(v,a) putreg16(v,a)
#endif
diff --git a/nuttx/arch/z16/include/z16f/irq.h b/nuttx/arch/z16/include/z16f/irq.h
index bcea8806c..e2ffd58b8 100644
--- a/nuttx/arch/z16/include/z16f/irq.h
+++ b/nuttx/arch/z16/include/z16f/irq.h
@@ -50,36 +50,47 @@
****************************************************************************/
/* Interrupt Vectors */
-
-#define Z16F_IRQ_RESET ( 0) /* Vector: 0x04 Reset */
-#define Z16F_IRQ_SYSEXC ( 1) /* Vector: 0x08 Sysexec */
-#define Z16F_IRQ_TIMER2 ( 2) /* Vector: 0x10 Timer 2 */
-#define Z16F_IRQ_TIMER1 ( 3) /* Vector: 0x14 Timer 1 */
-#define Z16F_IRQ_TIMER0 ( 4) /* Vector: 0x18 Timer 0 */
-#define Z16F_IRQ_UART0RX ( 5) /* Vector: 0x1C UART0 RX */
-#define Z16F_IRQ_UART0TX ( 6) /* Vector: 0x20 UART0 TX */
-#define Z16F_IRQ_I2C ( 7) /* Vector: 0x24 I2C */
-#define Z16F_IRQ_SPI ( 8) /* Vector: 0x28 SPI */
-#define Z16F_IRQ_ADC ( 9) /* Vector: 0x2C ADC */
-#define Z16F_IRQ_P7AD (10) /* Vector: 0x30 P7AD */
-#define Z16F_IRQ_P6AD (11) /* Vector: 0x34 P6AD */
-#define Z16F_IRQ_P5AD (12) /* Vector: 0x38 P5AD */
-#define Z16F_IRQ_P4AD (13) /* Vector: 0x3C P4AD */
-#define Z16F_IRQ_P3AD (14) /* Vector: 0x40 P3AD */
-#define Z16F_IRQ_P2AD (15) /* Vector: 0x44 P2AD */
-#define Z16F_IRQ_P1AD (16) /* Vector: 0x48 P1AD */
-#define Z16F_IRQ_P0AD (17) /* Vector: 0x4C P0AD */
-#define Z16F_IRQ_PWMTIMER (18) /* Vector: 0x50 PWM Timer */
-#define Z16F_IRQ_UART1RX (19) /* Vector: 0x54 UART1 RX */
-#define Z16F_IRQ_UART1TX (20) /* Vector: 0x58 UART1 TX */
-#define Z16F_IRQ_PWMFAULT (21) /* Vector: 0x5C PWM Fault */
-#define Z16F_IRQ_C3 (22) /* Vector: 0x60 C3 */
-#define Z16F_IRQ_C2 (23) /* Vector: 0x64 C2 */
-#define Z16F_IRQ_C1 (24) /* Vector: 0x68 C1 */
-#define Z16F_IRQ_C0 (25) /* Vector: 0x6C C0 */
+
+#define Z16F_IRQ_SYSEXC ( 0) /* Vector: 0x08 System Exceptions */
+
+#define Z16F_IRQ_IRQ0 ( 1) /* First of 8 IRQs controlled by IRQ0 registers */
+#define Z16F_IRQ_ADC ( 1) /* Vector: 0x2C IRQ0.0 ADC */
+#define Z16F_IRQ_SPI ( 2) /* Vector: 0x28 IRQ0.1 SPI */
+#define Z16F_IRQ_I2C ( 3) /* Vector: 0x24 IRQ0.2 I2C */
+#define Z16F_IRQ_UART0TX ( 4) /* Vector: 0x20 IRQ0.3 UART0 TX */
+#define Z16F_IRQ_UART0RX ( 5) /* Vector: 0x1C IRQ0.4 UART0 RX */
+#define Z16F_IRQ_TIMER0 ( 6) /* Vector: 0x18 IRQ0.5 Timer 0 */
+#define Z16F_IRQ_TIMER1 ( 7) /* Vector: 0x14 IRQ0.6 Timer 1 */
+#define Z16F_IRQ_TIMER2 ( 8) /* Vector: 0x10 IRQ0.7 Timer 2 */
+
+#define Z16F_IRQ_IRQ1 ( 9) /* First of 8 IRQs controlled by IRQ1 registers */
+#define Z16F_IRQ_P0AD ( 9) /* Vector: 0x4C IRQ1.0 Port A/D0, rising/falling edge */
+#define Z16F_IRQ_P1AD (10) /* Vector: 0x48 IRQ1.1 Port A/D1, rising/falling edge */
+#define Z16F_IRQ_P2AD (11) /* Vector: 0x44 IRQ1.2 Port A/D2, rising/falling edge */
+#define Z16F_IRQ_P3AD (12) /* Vector: 0x40 IRQ1.3 Port A/D3, rising/falling edge */
+#define Z16F_IRQ_P4AD (13) /* Vector: 0x3C IRQ1.4 Port A/D4, rising/falling edge */
+#define Z16F_IRQ_P5AD (14) /* Vector: 0x38 IRQ1.5 Port A/D5, rising/falling edge */
+#define Z16F_IRQ_P6AD (15) /* Vector: 0x34 IRQ1.6 Port A/D6, rising/falling edge */
+#define Z16F_IRQ_P7AD (16) /* Vector: 0x30 IRQ1.7 Port A/D7, rising/falling edge */
+
+#define Z16F_IRQ_IRQ2 (17) /* First of 8 IRQs controlled by IRQ2 registers */
+#define Z16F_IRQ_C0 (17) /* Vector: IRQ2.0 0x6C Port C0, both edges DMA3 */
+#define Z16F_IRQ_C1 (18) /* Vector: IRQ2.1 0x68 Port C1, both edges DMA3 */
+#define Z16F_IRQ_C2 (19) /* Vector: IRQ2.2 0x64 Port C2, both edges DMA3 */
+#define Z16F_IRQ_C3 (20) /* Vector: IRQ2.3 0x60 Port C3, both edges DMA3 */
+#define Z16F_IRQ_PWMFAULT (21) /* Vector: IRQ2.4 0x5C PWM Fault */
+#define Z16F_IRQ_UART1TX (22) /* Vector: IRQ2.5 0x58 UART1 TX */
+#define Z16F_IRQ_UART1RX (23) /* Vector: IRQ2.6 0x54 UART1 RX */
+#define Z16F_IRQ_PWMTIMER (24) /* Vector: IRQ2.7 0x50 PWM Timer */
#define Z16F_IRQ_SYSTIMER Z16F_IRQ_TIMER0
-#define NR_IRQS (26)
+#define NR_IRQS (25)
+
+/* These macros will map an IRQ to a register bit position */
+
+#define Z16F_IRQ0_BIT(i) (1 << ((i)-Z16F_IRQ_IRQ0))
+#define Z16F_IRQ1_BIT(i) (1 << ((i)-Z16F_IRQ_IRQ1))
+#define Z16F_IRQ2_BIT(i) (1 << ((i)-Z16F_IRQ_IRQ2))
/* IRQ Stack Frame Format
*
diff --git a/nuttx/arch/z16/src/common/up_allocateheap.c b/nuttx/arch/z16/src/common/up_allocateheap.c
new file mode 100644
index 000000000..28205ecd7
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_allocateheap.c
@@ -0,0 +1,98 @@
+/****************************************************************************
+ * common/up_allocateheap.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include <nuttx/mm.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+#include "up_mem.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_HEAP1_BASE;
+ *heap_size = UP_HEAP1_END - UP_HEAP1_BASE;
+ up_ledon(LED_HEAPALLOCATE);
+}
+
+/****************************************************************************
+ * Name: up_addregions
+ *
+ * Description:
+ * Memory may be added in non-contiguous chunks. Additional chunks are
+ * added by calling this function.
+ *
+ ****************************************************************************/
+
+#if CONFIG_MM_REGIONS > 1
+void up_addregion(void)
+{
+ mm_addregion((FAR void*)UP_HEAP2_BASE, UP_HEAP2_END - UP_HEAP2_BASE);
+}
+#endif
diff --git a/nuttx/arch/z16/src/common/up_assert.c b/nuttx/arch/z16/src/common/up_assert.c
new file mode 100644
index 000000000..d0e89fded
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_assert.c
@@ -0,0 +1,156 @@
+/****************************************************************************
+ * common/up_assert.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdlib.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+#include "up_mem.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Output debug info if stack dump is selected -- even if
+ * debug is not selected.
+ */
+
+#ifdef CONFIG_ARCH_STACKDUMP
+# undef lldbg
+# define lldbg lib_lowprintf
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: _up_assert
+ ****************************************************************************/
+
+static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+{
+ /* Are we in an interrupt handler or the idle task? */
+
+ if (up_interrupt_context() || ((FAR _TCB*)g_readytorun.head)->pid == 0)
+ {
+ (void)irqsave();
+ for(;;)
+ {
+#ifdef CONFIG_ARCH_LEDS
+ up_ledon(LED_PANIC);
+ up_mdelay(250);
+ up_ledoff(LED_PANIC);
+ up_mdelay(250);
+#endif
+ }
+ }
+ else
+ {
+ exit(errorcode);
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_assert
+ ****************************************************************************/
+
+void up_assert(const ubyte *filename, int lineno)
+{
+#if CONFIG_TASK_NAME_SIZE > 0
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+#endif
+
+ up_ledon(LED_ASSERTION);
+
+#if CONFIG_TASK_NAME_SIZE > 0
+ lldbg("Assertion failed at file:%s line: %d task: %s\n",
+ filename, lineno, rtcb->name);
+#else
+ lldbg("Assertion failed at file:%s line: %d\n",
+ filename, lineno);
+#endif
+
+ up_stackdump();
+ up_registerdump();
+ _up_assert(EXIT_FAILURE);
+}
+
+/****************************************************************************
+ * Name: up_assert_code
+ ****************************************************************************/
+
+void up_assert_code(const ubyte *filename, int lineno, int errorcode)
+{
+#if CONFIG_TASK_NAME_SIZE > 0
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+#endif
+
+ up_ledon(LED_ASSERTION);
+
+#if CONFIG_TASK_NAME_SIZE > 0
+ lldbg("Assertion failed at file:%s line: %d task: %s error code: %d\n",
+ filename, lineno, rtcb->name, errorcode);
+#else
+ lldbg("Assertion failed at file:%s line: %d error code: %d\n",
+ filename, lineno, errorcode);
+#endif
+
+ up_stackdump();
+ up_registerdump();
+ _up_assert(errorcode);
+}
diff --git a/nuttx/arch/z16/src/common/up_blocktask.c b/nuttx/arch/z16/src/common/up_blocktask.c
new file mode 100644
index 000000000..218afe080
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_blocktask.c
@@ -0,0 +1,173 @@
+/****************************************************************************
+ * common/up_blocktask.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <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_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 (IN_INTERRUPT)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current registers into the OLD rtcb.
+ */
+
+ SAVE_IRQCONTEXT(rtcb);
+
+ /* 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 setup so that the context will be performed on exit
+ * from the interrupt.
+ */
+
+ SET_IRQCONTEXT(rtcb);
+ }
+
+ /* Copy the user C context into the TCB at the (old) head of the
+ * g_readytorun Task list. if SAVE_USERCONTEXT returns a non-zero
+ * value, then this is really the previously running task restarting!
+ */
+
+ else if (!SAVE_USERCONTEXT(rtcb))
+ {
+ /* 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 */
+
+ RESTORE_USERCONTEXT(rtcb);
+ }
+ }
+ }
+}
diff --git a/nuttx/arch/z16/src/common/up_copystate.c b/nuttx/arch/z16/src/common/up_copystate.c
new file mode 100644
index 000000000..5b8d83cc0
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_copystate.c
@@ -0,0 +1,78 @@
+/****************************************************************************
+ * common/up_copystate.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <arch/irq.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_undefinedinsn
+ ****************************************************************************/
+
+/* Maybe a little faster than most memcpy's */
+
+void up_copystate(FAR chipreg_t *dest, FAR const chipreg_t *src)
+{
+ int i;
+ for (i = 0; i < XCPTCONTEXT_REGS; i++)
+ {
+ *dest++ = *src++;
+ }
+}
+
diff --git a/nuttx/arch/z16/src/common/up_createstack.c b/nuttx/arch/z16/src/common/up_createstack.c
new file mode 100644
index 000000000..7528b0af2
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_createstack.c
@@ -0,0 +1,128 @@
+/****************************************************************************
+ * common/up_createstack.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+#include "up_arch.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_create_stack
+ *
+ * Description:
+ * Allocate a stack for a new thread and setup
+ * up stack-related information in the TCB.
+ *
+ * The following TCB fields must be initialized:
+ * adj_stack_size: Stack size after adjustment for hardware,
+ * processor, etc. This value is retained only for debug
+ * purposes.
+ * stack_alloc_ptr: Pointer to allocated stack
+ * adj_stack_ptr: Adjusted stack_alloc_ptr for HW. The
+ * initial value of the stack pointer.
+ *
+ * Inputs:
+ * tcb: The TCB of new task
+ * stack_size: The requested stack size. At least this much
+ * must be allocated.
+ ****************************************************************************/
+
+STATUS 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)
+ {
+ tcb->stack_alloc_ptr = (uint32 *)kzmalloc(stack_size);
+ }
+
+ if (tcb->stack_alloc_ptr)
+ {
+ size_t top_of_stack;
+ size_t size_of_stack;
+
+ /* The Arm7Tdmi 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)tcb->stack_alloc_ptr + stack_size - 4;
+
+ /* The Arm7Tdmi 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)tcb->stack_alloc_ptr + 4;
+
+ /* Save the adjusted stack values in the _TCB */
+
+ tcb->adj_stack_ptr = (uint32*)top_of_stack;
+ tcb->adj_stack_size = size_of_stack;
+
+ up_ledon(LED_STACKCREATED);
+ return OK;
+ }
+
+ return ERROR;
+}
diff --git a/nuttx/arch/z16/src/common/up_doirq.c b/nuttx/arch/z16/src/common/up_doirq.c
new file mode 100644
index 000000000..6771006db
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_doirq.c
@@ -0,0 +1,104 @@
+/****************************************************************************
+ * common/up_doirq.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <assert.h>
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+void up_doirq(int irq, chipreg_t *regs)
+{
+ up_ledon(LED_INIRQ);
+#ifdef CONFIG_SUPPRESS_INTERRUPTS
+ PANIC(OSERR_ERREXCEPTION);
+#else
+ if ((unsigned)irq < NR_IRQS)
+ {
+ /* Current regs non-zero indicates that we are processing
+ * an interrupt; current_regs is also used to manage
+ * interrupt level context switches.
+ */
+
+ current_regs = regs;
+
+ /* Mask and acknowledge the interrupt */
+
+ up_maskack_irq(irq);
+
+ /* Deliver the IRQ */
+
+ irq_dispatch(irq, regs);
+
+ /* Indicate that we are no long in an interrupt handler */
+
+ current_regs = NULL;
+
+ /* Unmask the last interrupt (global interrupts are still
+ * disabled.
+ */
+
+ up_enable_irq(irq);
+ }
+ up_ledoff(LED_INIRQ);
+#endif
+}
diff --git a/nuttx/arch/z16/src/common/up_exit.c b/nuttx/arch/z16/src/common/up_exit.c
new file mode 100644
index 000000000..8838603bb
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_exit.c
@@ -0,0 +1,204 @@
+/****************************************************************************
+ * common/up_exit.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+#ifdef CONFIG_DUMP_ON_EXIT
+#include <nuttx/fs.h>
+#endif
+
+/****************************************************************************
+ * Private 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
+
+ dbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]);
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ if (tcb->filelist)
+ {
+ lldbg(" 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)
+ {
+ lldbg(" fd=%d refcount=%d\n",
+ i, inode->i_crefs);
+ }
+ }
+ }
+#endif
+
+#if CONFIG_NFILE_STREAMS > 0
+ if (tcb->streams)
+ {
+ lldbg(" 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
+ lldbg(" fd=%d nbytes=%d\n",
+ filep->fs_filedes,
+ filep->fs_bufpos - filep->fs_bufstart);
+#else
+ lldbg(" 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().
+ *
+ ****************************************************************************/
+
+void _exit(int status)
+{
+ FAR _TCB* tcb = (FAR _TCB*)g_readytorun.head;
+
+ /* Disable interrupts. Interrupts will remain disabled until
+ * the new task is resumed below.
+ */
+
+ (void)irqsave();
+
+ lldbg("TCB=%p exitting\n", tcb);
+
+#if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG)
+ lldbg("Other tasks:\n");
+ sched_foreach(_up_dumponexit, NULL);
+#endif
+
+ /* 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);
+
+ /* We are not in a bad stack-- the head of the ready to run task list
+ * does not correspond to the thread that is running. Disabling pre-
+ * emption on this TCB should be enough to keep things stable.
+ */
+
+ sched_lock();
+
+ /* 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 calling sched_unlock() should have no effect */
+
+ sched_unlock();
+
+ /* Now, perform the context switch to the new ready-to-run task at the
+ * head of the list.
+ */
+
+ tcb = (FAR _TCB*)g_readytorun.head;
+ lldbg("New Active Task TCB=%p\n", tcb);
+
+ /* Then switch contexts */
+
+ RESTORE_USERCONTEXT(tcb);
+}
+
diff --git a/nuttx/arch/z16/src/common/up_idle.c b/nuttx/arch/z16/src/common/up_idle.c
new file mode 100644
index 000000000..528bc5f6e
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_idle.c
@@ -0,0 +1,107 @@
+/****************************************************************************
+ * common/up_idle.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+#if defined(CONFIG_ARCH_LEDS) && defined(CONFIG_ARCH_BRINGUP)
+static ubyte g_ledtoggle = 0;
+#endif
+
+/****************************************************************************
+ * 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_ARCH_LEDS) && defined(CONFIG_ARCH_BRINGUP)
+ g_ledtoggle++;
+ if (g_ledtoggle == 0x80)
+ {
+ up_ledon(LED_IDLE);
+ }
+ else if (g_ledtoggle == 0x00)
+ {
+ up_ledoff(LED_IDLE);
+ }
+#endif
+
+#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();
+#endif
+}
+
diff --git a/nuttx/arch/z16/src/common/up_initialize.c b/nuttx/arch/z16/src/common/up_initialize.c
new file mode 100644
index 000000000..0f54beb4f
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_initialize.c
@@ -0,0 +1,169 @@
+/****************************************************************************
+ * common/up_initialize.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/fs.h>
+#include <nuttx/mm.h>
+#include <arch/board/board.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Define to enable timing loop calibration */
+
+#undef CONFIG_ARCH_CALIBRATION
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* This holds a references to the current interrupt level
+ * register storage structure. If is non-NULL only during
+ * interrupt processing.
+ */
+
+chipreg_t *current_regs;
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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 extra memory fragments to the memory manager */
+
+#if CONFIG_MM_REGIONS > 1
+ up_addregion();
+#endif
+
+ /* Initialize the interrupt subsystem */
+
+ up_irqinitialize();
+
+ /* 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 */
+
+ up_serialinit();
+
+ /* Initialize the netwok */
+
+ up_netinitialize();
+ up_ledon(LED_IRQSENABLED);
+}
diff --git a/nuttx/arch/z16/src/common/up_initialstate.c b/nuttx/arch/z16/src/common/up_initialstate.c
new file mode 100644
index 000000000..493df1fa3
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_initialstate.c
@@ -0,0 +1,92 @@
+/****************************************************************************
+ * common/up_initialstate.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <string.h>
+#include <nuttx/arch.h>
+
+#include "chip/chip.h"
+#include "up_internal.h"
+#include "up_arch.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(_TCB *tcb)
+{
+ struct xcptcontext *xcp = &tcb->xcp;
+
+ /* Initialize the initial exception register context structure */
+
+ memset(xcp, 0, sizeof(struct xcptcontext));
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+ xcp->regs[XCPT_I] = Z80_C_FLAG; /* Carry flag will enable interrupts */
+#endif
+ xcp->regs[XCPT_SP] = (chipreg_t)tcb->adj_stack_ptr;
+ xcp->regs[XCPT_PC] = (chipreg_t)tcb->start;
+}
diff --git a/nuttx/arch/z16/src/common/up_internal.h b/nuttx/arch/z16/src/common/up_internal.h
index 8d4ad35ba..28e4ed2e2 100644
--- a/nuttx/arch/z16/src/common/up_internal.h
+++ b/nuttx/arch/z16/src/common/up_internal.h
@@ -85,7 +85,7 @@ typedef void (*up_vector_t)(void);
* interrupt processing.
*/
-extern uint32 *current_regs;
+extern chipreg_t *current_regs;
#endif
/****************************************************************************
@@ -96,14 +96,13 @@ extern uint32 *current_regs;
/* Defined in files with the same name as the function */
-extern void up_copystate(FAR uint32 *dest, FAR uint32 *src);
-extern void up_decodeirq(FAR uint32 *regs);
-extern void up_doirq(int irq, FAR uint32 *regs);
-extern void up_fullcontextrestore(FAR uint32 *regs);
+extern void up_copystate(FAR chipreg_t *dest, FAR chipreg_t *src);
+extern void up_doirq(int irq, FAR chipreg_t *regs);
+extern void up_fullcontextrestore(FAR chipreg_t *regs);
extern void up_irqinitialize(void);
-extern int up_saveusercontext(FAR uint32 *regs);
+extern int up_saveusercontext(FAR chipreg_t *regs);
extern void up_sigdeliver(void);
-extern int up_timerisr(int irq, FAR uint32 *regs);
+extern int up_timerisr(int irq, FAR chipreg_t *regs);
#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC)
extern void up_lowputc(char ch);
@@ -157,7 +156,7 @@ extern void up_netinitialize(void);
/* Return the current value of the stack pointer (used in stack dump logic) */
-extern uint32 up_getsp(void);
+extern chipreg_t up_getsp(void);
/* Dump stack and registers */
diff --git a/nuttx/arch/z16/src/common/up_interruptcontext.c b/nuttx/arch/z16/src/common/up_interruptcontext.c
new file mode 100644
index 000000000..2fcfc6d36
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_interruptcontext.c
@@ -0,0 +1,68 @@
+/****************************************************************************
+ * common/up_interruptcontext.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/arch.h>
+#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 current_regs != NULL;
+}
diff --git a/nuttx/arch/z16/src/common/up_mdelay.c b/nuttx/arch/z16/src/common/up_mdelay.c
new file mode 100644
index 000000000..94ae88541
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_mdelay.c
@@ -0,0 +1,94 @@
+/****************************************************************************
+ * common/up_mdelay.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+
+#ifdef CONFIG_BOARD_LOOPSPERMSEC
+
+/****************************************************************************
+ * 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++)
+ {
+ }
+ }
+}
+#endif /* CONFIG_BOARD_LOOPSPERMSEC */
+
diff --git a/nuttx/arch/z16/src/common/up_registerdump.c b/nuttx/arch/z16/src/common/up_registerdump.c
new file mode 100644
index 000000000..0b1f33f24
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_registerdump.c
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * common/up_registerdump.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Output debug info if stack dump is selected -- even if
+ * debug is not selected.
+ */
+
+#ifdef CONFIG_ARCH_STACKDUMP
+# undef lldbg
+# define lldbg lib_lowprintf
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_registerdump
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_STACKDUMP
+static void up_registerdump(void)
+{
+ if (current_regs)
+ {
+ lldbg("AF: %04x I: %04x\n",
+ current_regs[XCPT_AF], current_regs[XCPT_I]);
+ lldbg("BC: %04x DE: %04x HL: %04x\n",
+ current_regs[XCPT_BC], current_regs[XCPT_DE], current_regs[XCPT_HL]);
+ lldbg("IX: %04x IY: %04x\n",
+ current_regs[XCPT_IX], current_regs[XCPT_IY]);
+ lldbg("SP: %04x PC: $04x\n"
+ current_regs[XCPT_SP], current_regs[XCPT_PC]);
+ }
+}
+#endif
diff --git a/nuttx/arch/z16/src/common/up_releasepending.c b/nuttx/arch/z16/src/common/up_releasepending.c
new file mode 100644
index 000000000..13586a7ba
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_releasepending.c
@@ -0,0 +1,137 @@
+/****************************************************************************
+ * common/up_releasepending.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_release_pending
+ *
+ * Description:
+ * Release and ready-to-run tasks that have
+ * collected in the pending task list. This can call a
+ * context switch if a new task is placed at the head of
+ * the ready to run list.
+ *
+ ****************************************************************************/
+
+void up_release_pending(void)
+{
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+
+ lldbg("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 (IN_INTERRUPT)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current context into the OLD rtcb.
+ */
+
+ SAVE_IRQCONTEXT(rtcb);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ lldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then setup so that the context will be performed on exit
+ * from the interrupt.
+ */
+
+ SET_IRQCONTEXT(rtcb);
+ }
+
+ /* Copy the exception context into the TCB of the task that
+ * was currently active. if SAVE_USERCONTEXT returns a non-zero
+ * value, then this is really the previously running task
+ * restarting!
+ */
+
+ else if (!SAVE_USERCONTEXT(rtcb))
+ {
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ lldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ RESTORE_USERCONTEXT(rtcb);
+ }
+ }
+}
diff --git a/nuttx/arch/z16/src/common/up_releasestack.c b/nuttx/arch/z16/src/common/up_releasestack.c
new file mode 100644
index 000000000..e6fcfb731
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_releasestack.c
@@ -0,0 +1,78 @@
+/************************************************************
+ * common/up_releasestack.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include "os_internal.h"
+#include "up_internal.h"
+
+/************************************************************
+ * Private Types
+ ************************************************************/
+
+/************************************************************
+ * Private Function Prototypes
+ ************************************************************/
+
+/************************************************************
+ * Global Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_release_stack
+ *
+ * Description:
+ * A task has been stopped. Free all stack
+ * related resources retained int 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/z16/src/common/up_reprioritizertr.c b/nuttx/arch/z16/src/common/up_reprioritizertr.c
new file mode 100644
index 000000000..5caf2d8ef
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_reprioritizertr.c
@@ -0,0 +1,185 @@
+/****************************************************************************
+ * common/up_reprioritizertr.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_reprioritize_rtr
+ *
+ * Description:
+ * Called when the priority of a running or
+ * ready-to-run task changes and the reprioritization will
+ * cause a context switch. Two cases:
+ *
+ * 1) The priority of the currently running task drops and the next
+ * task in the ready to run list has priority.
+ * 2) An idle, ready to run task's priority has been raised above the
+ * the priority of the current, running task and it now has the
+ * priority.
+ *
+ * Inputs:
+ * tcb: The TCB of the task that has been reprioritized
+ * priority: The new task priority
+ *
+ ****************************************************************************/
+
+void up_reprioritize_rtr(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;
+
+ lldbg("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 (IN_INTERRUPT)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current context into the OLD rtcb.
+ */
+
+ SAVE_IRQCONTEXT(rtcb);
+
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ lldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then setup so that the context will be performed on exit
+ * from the interrupt.
+ */
+
+ SET_IRQCONTEXT(rtcb);
+ }
+
+ /* Copy the exception context into the TCB at the (old) head of the
+ * g_readytorun Task list. if SAVE_USERCONTEXT returns a non-zero
+ * value, then this is really the previously running task restarting!
+ */
+
+ else if (!SAVE_USERCONTEXT(rtcb))
+ {
+ /* Restore the exception context of the rtcb at the (new) head
+ * of the g_readytorun task list.
+ */
+
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ lldbg("New Active Task TCB=%p\n", rtcb);
+
+ /* Then switch contexts */
+
+ RESTORE_USERCONTEXT(rtcb);
+ }
+ }
+ }
+}
diff --git a/nuttx/arch/z16/src/common/up_schedulesigaction.c b/nuttx/arch/z16/src/common/up_schedulesigaction.c
new file mode 100644
index 000000000..6d1aa00ed
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_schedulesigaction.c
@@ -0,0 +1,198 @@
+/****************************************************************************
+ * common/up_schedulesigaction.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <arch/irq.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+#ifndef CONFIG_DISABLE_SIGNALS
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_schedule_sigaction
+ *
+ * Description:
+ * This function is called by the OS when one or more
+ * signal handling actions have been queued for execution.
+ * The architecture specific code must configure things so
+ * that the 'igdeliver' callback is executed on the thread
+ * specified by 'tcb' as soon as possible.
+ *
+ * This function may be called from interrupt handling logic.
+ *
+ * This operation should not cause the task to be unblocked
+ * nor should it cause any immediate execution of sigdeliver.
+ * Typically, a few cases need to be considered:
+ *
+ * (1) This function may be called from an interrupt handler
+ * During interrupt processing, all xcptcontext structures
+ * should be valid for all tasks. That structure should
+ * be modified to invoke sigdeliver() either on return
+ * from (this) interrupt or on some subsequent context
+ * switch to the recipient task.
+ * (2) If not in an interrupt handler and the tcb is NOT
+ * the currently executing task, then again just modify
+ * the saved xcptcontext structure for the recipient
+ * task so it will invoke sigdeliver when that task is
+ * later resumed.
+ * (3) If not in an interrupt handler and the tcb IS the
+ * currently executing task -- just call the signal
+ * handler now.
+ *
+ ****************************************************************************/
+
+void up_schedule_sigaction(FAR _TCB *tcb, sig_deliver_t sigdeliver)
+{
+ /* Refuse to handle nested signal actions */
+
+ dbg("tcb=0x%p sigdeliver=0x%04x\n", tcb, (chipreg_t)sigdeliver);
+
+ if (!tcb->xcp.sigdeliver)
+ {
+ irqstate_t flags;
+
+ /* Make sure that interrupts are disabled */
+
+ flags = irqsave();
+
+ /* First, handle some special cases when the signal is
+ * being delivered to the currently executing task.
+ */
+
+ dbg("rtcb=0x%p current_regs=0x%p\n", g_readytorun.head, current_regs);
+
+ if (tcb == (FAR _TCB*)g_readytorun.head)
+ {
+ /* CASE 1: We are not in an interrupt handler and
+ * a task is signalling itself for some reason.
+ */
+
+ if (!current_regs)
+ {
+ /* In this case just deliver the signal now. */
+
+ sigdeliver(tcb);
+ }
+
+ /* CASE 2: We are in an interrupt handler AND the
+ * interrupted task is the same as the one that
+ * must receive the signal, then we will have to modify
+ * the return state as well as the state in the TCB.
+ */
+
+ else
+ {
+ /* Save the return address and interrupt state.
+ * These will be restored by the signal trampoline after
+ * the signals have been delivered.
+ */
+
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_pc = current_regs[XCPT_PC];
+ tcb->xcp.saved_i = current_regs[XCPT_I];
+
+ /* Then set up to vector to the trampoline with interrupts
+ * disabled
+ */
+
+ current_regs[XCPT_PC] = (chipreg_t)up_sigdeliver;
+ current_regs[XCPT_I] = 0;
+
+ /* And make sure that the saved context in the TCB
+ * is the same as the interrupt return context.
+ */
+
+ up_copystate(tcb->xcp.regs, current_regs);
+ }
+ }
+
+ /* Otherwise, we are (1) signaling a task is not running
+ * from an interrupt handler or (2) we are not in an
+ * interrupt handler and the running task is signalling
+ * some non-running task.
+ */
+
+ else
+ {
+ /* Save the return lr and cpsr and one scratch register
+ * These will be restored by the signal trampoline after
+ * the signals have been delivered.
+ */
+
+ tcb->xcp.sigdeliver = sigdeliver;
+ tcb->xcp.saved_pc = tcb->xcp.regs[XCPT_PC];
+ tcb->xcp.saved_i = tcb->xcp.regs[XCPT_I];
+
+ /* Then set up to vector to the trampoline with interrupts
+ * disabled
+ */
+
+ tcb->xcp.regs[XCPT_PC] = (chipreg_t)up_sigdeliver;
+ tcb->xcp.regs[XCPT_I] = 0;
+ }
+
+ irqrestore(flags);
+ }
+}
+
+#endif /* CONFIG_DISABLE_SIGNALS */
+
diff --git a/nuttx/arch/z16/src/common/up_sigdeliver.c b/nuttx/arch/z16/src/common/up_sigdeliver.c
new file mode 100644
index 000000000..9083c596f
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_sigdeliver.c
@@ -0,0 +1,143 @@
+/****************************************************************************
+ * common/up_sigdeliver.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+#ifndef CONFIG_DISABLE_SIGNALS
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_sigdeliver
+ *
+ * Description:
+ * This is the a signal handling trampoline. When a
+ * signal action was posted. The task context was mucked
+ * with and forced to branch to this location with interrupts
+ * disabled.
+ *
+ ****************************************************************************/
+
+void up_sigdeliver(void)
+{
+#ifndef CONFIG_DISABLE_SIGNALS
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+ chipreg_t regs[XCPTCONTEXT_REGS];
+ sig_deliver_t sigdeliver;
+
+ /* Save the errno. This must be preserved throughout the signal handling
+ * so that the the user code final gets the correct errno value (probably
+ * EINTR).
+ */
+
+ int saved_errno = rtcb->errno;
+
+ up_ledon(LED_SIGNAL);
+
+ dbg("rtcb=%p sigdeliver=%p sigpendactionq.head=%p\n",
+ rtcb, rtcb->xcp.sigdeliver, rtcb->sigpendactionq.head);
+ ASSERT(rtcb->xcp.sigdeliver != NULL);
+
+ /* Save the real return state on the stack. */
+
+ up_copystate(regs, rtcb->xcp.regs);
+ regs[XCPT_PC] = rtcb->xcp.saved_pc;
+ regs[XCPT_I] = rtcb->xcp.saved_i;
+
+ /* Get a local copy of the sigdeliver function pointer.
+ * we do this so that we can nullify the sigdeliver
+ * function point in the TCB and accept more signal
+ * deliveries while processing the current pending
+ * signals.
+ */
+
+ sigdeliver = rtcb->xcp.sigdeliver;
+ rtcb->xcp.sigdeliver = NULL;
+
+ /* Then restore the task interrupt state. */
+
+ irqrestore(regs[XCPT_I]);
+
+ /* Deliver the signals */
+
+ sigdeliver(rtcb);
+
+ /* Output any debug messaged BEFORE restoring errno
+ * (because they may alter errno), then restore the
+ * original errno that is needed by the user logic
+ * (it is probably EINTR).
+ */
+
+ dbg("Resuming\n");
+ rtcb->errno = saved_errno;
+
+ /* Then restore the correct state for this thread of
+ * execution.
+ */
+
+ up_ledoff(LED_SIGNAL);
+ SIGNAL_RETURN(regs);
+#endif
+}
+
+#endif /* CONFIG_DISABLE_SIGNALS */
diff --git a/nuttx/arch/z16/src/common/up_stackdump.c b/nuttx/arch/z16/src/common/up_stackdump.c
new file mode 100644
index 000000000..482f7bf1b
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_stackdump.c
@@ -0,0 +1,109 @@
+/****************************************************************************
+ * common/up_stackdump.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Output debug info if stack dump is selected -- even if
+ * debug is not selected.
+ */
+
+#ifdef CONFIG_ARCH_STACKDUMP
+# undef lldbg
+# define lldbg lib_lowprintf
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_getsp
+ ****************************************************************************/
+#warning TO BE PROVIDED
+
+/****************************************************************************
+ * Name: up_stackdump
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_STACKDUMP
+static void up_stackdump(void)
+{
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+ chipreg_t sp = up_getsp();
+ chipreg_t stack_base = (chipreg_t)rtcb->adj_stack_ptr;
+ chipreg_t stack_size = (chipreg_t)rtcb->adj_stack_size;
+
+ lldbg("stack_base: %08x\n", stack_base);
+ lldbg("stack_size: %08x\n", stack_size);
+ lldbg("sp: %08x\n", sp);
+
+ if (sp >= stack_base || sp < stack_base - stack_size)
+ {
+ lldbg("ERROR: Stack pointer is not within allocated stack\n");
+ return;
+ }
+ else
+ {
+ chipreg_t stack = sp & ~0x0f;
+
+ for (stack = sp & ~0x0f; stack < stack_base; stack += 8*sizeof(chipreg_t))
+ {
+ chipreg_t *ptr = (chipreg_t*)stack;
+ lldbg("%08x: %08x %08x %08x %08x %08x %08x %08x %08x\n",
+ stack, ptr[0], ptr[1], ptr[2], ptr[3],
+ ptr[4], ptr[5], ptr[6], ptr[7]);
+ }
+ }
+}
+#endif
diff --git a/nuttx/arch/z16/src/common/up_udelay.c b/nuttx/arch/z16/src/common/up_udelay.c
new file mode 100644
index 000000000..18b176302
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_udelay.c
@@ -0,0 +1,132 @@
+/****************************************************************************
+ * common/up_udelay.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+
+#ifdef CONFIG_BOARD_LOOPSPERMSEC
+
+/****************************************************************************
+ * 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(unsigned int 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--;
+ }
+}
+#endif /* CONFIG_BOARD_LOOPSPERMSEC */
+
diff --git a/nuttx/arch/z16/src/common/up_unblocktask.c b/nuttx/arch/z16/src/common/up_unblocktask.c
new file mode 100644
index 000000000..b67886b8c
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_unblocktask.c
@@ -0,0 +1,168 @@
+/****************************************************************************
+ * common/up_unblocktask.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "os_internal.h"
+#include "clock_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_unblock_task
+ *
+ * Description:
+ * A task is currently in an inactive task list
+ * but has been prepped to execute. Move the TCB to the
+ * ready-to-run list, restore its context, and start execution.
+ *
+ * Inputs:
+ * tcb: Refers to the tcb to be unblocked. This tcb is
+ * in one of the waiting tasks lists. It must be moved to
+ * the ready-to-run list and, if it is the highest priority
+ * ready to run taks, executed.
+ *
+ ****************************************************************************/
+
+void up_unblock_task(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 / MSEC_PER_TICK;
+#endif
+
+ /* Add the task in the correct location in the prioritized
+ * g_readytorun task list
+ */
+
+ if (sched_addreadytorun(tcb))
+ {
+ /* The currently active task has changed! We need to do
+ * a context switch to the new task.
+ *
+ * Are we in an interrupt handler?
+ */
+
+ if (IN_INTERRUPT)
+ {
+ /* Yes, then we have to do things differently.
+ * Just copy the current context into the OLD rtcb.
+ */
+
+ SAVE_IRQCONTEXT(rtcb);
+
+ /* 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 setup so that the context will be performed on exit
+ * from the interrupt.
+ */
+
+ SET_IRQCONTEXT(rtcb);
+ }
+
+ /* We are not in an interrupt handler. Copy the user C context
+ * into the TCB of the task that was previously active. if
+ * SAVE_USERCONTEXT returns a non-zero value, then this is really the
+ * previously running task restarting!
+ */
+
+ else if (!SAVE_USERCONTEXT(rtcb))
+ {
+ /* 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 */
+
+ RESTORE_USERCONTEXT(rtcb);
+ }
+ }
+ }
+}
diff --git a/nuttx/arch/z16/src/common/up_usestack.c b/nuttx/arch/z16/src/common/up_usestack.c
new file mode 100644
index 000000000..d633fa294
--- /dev/null
+++ b/nuttx/arch/z16/src/common/up_usestack.c
@@ -0,0 +1,118 @@
+/************************************************************
+ * common/up_usestack.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+#include "up_internal.h"
+
+/************************************************************
+ * Private Types
+ ************************************************************/
+
+/************************************************************
+ * Private Function Prototypes
+ ************************************************************/
+
+/************************************************************
+ * Global Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_use_stack
+ *
+ * Description:
+ * Setup up stack-related information in the TCB
+ * using pre-allocated stack memory
+ *
+ * The following TCB fields must be initialized:
+ * adj_stack_size: Stack size after adjustment for hardware,
+ * processor, etc. This value is retained only for debug
+ * purposes.
+ * stack_alloc_ptr: Pointer to allocated stack
+ * adj_stack_ptr: Adjusted stack_alloc_ptr for HW. The
+ * initial value of the stack pointer.
+ *
+ * Inputs:
+ * tcb: The TCB of new task
+ * stack_size: The allocated stack size.
+ *
+ ************************************************************/
+
+STATUS 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 Arm7Tdmi 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)tcb->stack_alloc_ptr + stack_size - 4;
+
+ /* The Arm7Tdmi 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)tcb->stack_alloc_ptr + 4;
+
+ /* Save the adjusted stack values in the _TCB */
+
+ tcb->adj_stack_size = top_of_stack;
+ tcb->adj_stack_size = size_of_stack;
+
+ return OK;
+}
diff --git a/nuttx/arch/z16/src/z16f/Make.defs b/nuttx/arch/z16/src/z16f/Make.defs
index 3549e08d2..f360ca96d 100644
--- a/nuttx/arch/z16/src/z16f/Make.defs
+++ b/nuttx/arch/z16/src/z16f/Make.defs
@@ -36,7 +36,13 @@
HEAD_SSRC = z16f_head.S
CMN_SSRCS =
-CMN_CSRCS =
+CMN_CSRCS = up_allocateheap.c up_initialize.c up_schedulesigaction.c \
+ up_assert.c up_initialstate.c up_sigdeliver.c up_blocktask.c \
+ up_interruptcontext.c up_stackdump.c up_copystate.c \
+ up_mdelay.c up_udelay.c up_createstack.c up_registerdump.c \
+ up_unblocktask.c up_doirq.c up_releasepending.c up_usestack.c \
+ up_exit.c up_releasestack.c up_idle.c up_reprioritizertr.c
CHIP_SSRCS = z16f_lowuart.S
-CHIP_CSRCS =
+CHIP_CSRCS = z16f_clkinit.c z16f_irq.c z16f_timerisr.c
+
diff --git a/nuttx/arch/z16/src/z16f/chip.h b/nuttx/arch/z16/src/z16f/chip.h
index b91e44484..64124008e 100644
--- a/nuttx/arch/z16/src/z16f/chip.h
+++ b/nuttx/arch/z16/src/z16f/chip.h
@@ -83,7 +83,35 @@
# error "Z16F chip variant not specified"
#endif
-/* Memory areas**********************************************************************
+/* Flash option settings at address 0x00000000 ************************************/
+
+#define Z16F_FLOPTION0 rom char _flash_option0 _At 0x0
+#define Z16F_FLOPTION1 rom char _flash_option1 _At 0x1
+#define Z16F_FLOPTION2 rom char _flash_option2 _At 0x2
+#define Z16F_FLOPTION3 rom char _flash_option3 _At 0x3
+
+#define Z16F_FLOPTION0_EXTRNRC _HX8(00) /* Bits 6-7: OSC_SEL */
+#define Z16F_FLOPTION0_LOWFREQ _HX8(40)
+#define Z16F_FLOPTION0_MEDFREQ _HX8(80)
+#define Z16F_FLOPTION0_MAXPWR _HX8(c0)
+#define Z16F_FLOPTION0_WDTRES _HX8(20) /* Bit 5 */
+#define Z16F_FLOPTION0_WDTA0 _HX8(10) /* Bit 4 */
+#define Z16F_FLOPTION0_VBOA0 _HX8(08) /* Bit 3 */
+#define Z16F_FLOPTION0_DBGUART _HX8(04) /* Bit 2 */
+#define Z16F_FLOPTION0_FWP _HX8(02) /* Bit 1 */
+#define Z16F_FLOPTION0_RP _HX8(01) /* Bit 0 */
+
+#define Z16F_FLOPTION1_RESVD _HX8(f8) /* Bits 3-7: reserved */
+#define Z16F_FLOPTION1_MCEN _HX8(04) /* Bit 2: Motor control pins enable */
+#define Z16F_FLOPTION1_OFFH _HX8(02) /* High side OFF */
+#define Z16F_FLOPTION1_OFFL _HX8(01) /* Low side OFF */
+
+#define Z16F_FLOPTION2_RESVD _HX8(ff) /* Bits 0-7: reserved */
+
+#define Z16F_FLOPTION3_RESVD _HX8(bf) /* Bits 0-5,7: reserved */
+#define Z16F_FLOPTION3_NORMAL _HX8(40) /* Bit 6: 1:Normal 0:Low power mode */
+
+/* Memory areas *******************************************************************
*
* Internal non-volatile memory starts at address zero. The size
* of the internal non-volatile memory is chip-dependent.
@@ -117,6 +145,77 @@
#define Z16F_IIO_BASE _HX32(ffffe000) /* Internal I/O memory and SFRs */
#define Z16F_IIO_SIZE _HX32(00001fff)
+/* Control Registers ***************************************************************/
+
+#define Z16F_CNTRL_PCOV _HX32(ffffe004) /* 32-bits: Program counter overflow */
+#define Z16F_CNTRL_SPOV _HX32(ffffe00c) /* 32-bits: Stack pointer overflow */
+#define Z16F_CNTRL_FLAGS _HX32(ffffe100) /* 8-bits: flags */
+#define Z16F_CNTRL_CPUCTL _HX32(ffffe102) /* 8-bits: CPU control */
+
+/* Flag register bits ***************************************************************/
+
+#define Z16F_CNTRL_FLAGS_C _HX8(80) /* Bit 7: Carry flag */
+#define Z16F_CNTRL_FLAGS_Z _HX8(40) /* Bit 6: Zero flag */
+#define Z16F_CNTRL_FLAGS_S _HX8(20) /* Bit 5: Sign flag */
+#define Z16F_CNTRL_FLAGS_V _HX8(10) /* Bit 4: Overflow flag */
+#define Z16F_CNTRL_FLAGS_B _HX8(08) /* Bit 3: Blank flag */
+#define Z16F_CNTRL_FLAGS_F1 _HX8(04) /* Bit 2: User flag 1 */
+#define Z16F_CNTRL_FLAGS_CIRQE _HX8(02) /* Bit 1: Chained interrupt enable */
+#define Z16F_CNTRL_FLAGS_IRQE _HX8(01) /* Bit 0: Master interrupt enable */
+
+/* CPU control register bits ********************************************************/
+
+ /* Bits 7-2: Reserved, must be zero */
+ /* Bits 1-0: DMA bandwidth control */
+#define Z16F_CNTRL_CPUCTL_BWALL _HX8(00) /* DMA can consume 100% bandwidth */
+#define Z16F_CNTRL_CPUCTL_BW11 _HX8(01) /* DMA can do 1 transaction per 1 cycle */
+#define Z16F_CNTRL_CPUCTL_BW12 _HX8(01) /* DMA can do 1 transaction per 2 cycles */
+#define Z16F_CNTRL_CPUCTL_BW13 _HX8(01) /* DMA can do 1 transaction per 3 cycles */
+
+/* Trace registers ******************************************************************/
+
+#define Z16F_TRACE_CTL _HX32(ffffe013) /* 8-bit: Trace Control */
+#define Z16F_TRACE_ADDR _HX32(ffffe014) /* 32-bit: Trace Address */
+
+/* Interrupt controller registers ***************************************************/
+
+#define Z16F_SYSEXCP _HX32(ffffe020) /* 16-bit: System Exception Status */
+#define Z16F_SYSEXCPH _HX32(ffffe020) /* 8-bit: System Exception Status High */
+#define Z16F_SYSEXCPL _HX32(ffffe021) /* 8-bit: System Exception Status Low */
+#define Z16F_LASTIRQ _HX32(ffffe023) /* 8-bit: Last IRQ Register */
+#define Z16F_IRQ0 _HX32(ffffe030) /* 8-bit: Interrupt Request 0 */
+#define Z16F_IRQ0_SET _HX32(ffffe031) /* 8-bit: Interrupt Request 0 Set */
+#define Z16F_IRQ0_EN _HX32(ffffe032) /* 16-bit: IRQ0 Enable */
+#define Z16F_IRQ0_ENH _HX32(ffffe032) /* 8-bit: IRQ0 Enable High Bit */
+#define Z16F_IRQ0_ENL _HX32(ffffe033) /* 8-bit: IRQ0 Enable Low Bit */
+#define Z16F_IRQ1 _HX32(ffffe034) /* 8-bit: Interrupt Request 1 */
+#define Z16F_IRQ1_SET _HX32(ffffe035) /* 8-bit: Interrupt Request 1 Set */
+#define Z16F_IRQ1_EN _HX32(ffffe036) /* 16-bit: IRQ1 Enable */
+#define Z16F_IRQ1_ENH _HX32(ffffe036) /* 8-bit: IRQ1 Enable High Bit */
+#define Z16F_IRQ1_ENL _HX32(ffffe037) /* 8-bit: IRQ1 Enable Low Bit */
+#define Z16F_IRQ2 _HX32(ffffe038) /* 8-bit: Interrupt Request 2 */
+#define Z16F_IRQ2_SET _HX32(ffffe039) /* 8-bit Interrupt Request 2 Set */
+#define Z16F_IRQ2_EN _HX32(ffffe03a) /* 16-bit: IRQ2 Enable */
+#define Z16F_IRQ2_ENH _HX32(ffffe03a) /* 8-bit: IRQ2 Enable High Bit */
+#define Z16F_IRQ2_ENL _HX32(ffffe03c) /* 8-bit: IRQ2 Enable Low Bit */
+
+/* Oscillator control registers *****************************************************/
+
+#define Z16F_OSC_CTL _HX32(ffffe0A0) /* 8-bit: Oscillator Control */
+#define Z16F_OSC_DIV _HX32(ffffe0A1) /* 8-bit: Oscillator Divide */
+
+/* Oscillator control register bits *************************************************/
+
+#define Z16F_OSCCTL_INTEN _HX8(80) /* Bit 7: Internal oscillator enabled */
+#define Z16F_OSCCTL_XTLEN _HX8(40) /* Bit 6: Crystal oscillator enabled */
+#define Z16F_OSCCTL_WDTEN _HX8(20) /* Bit 5: Watchdog timer enabled */
+#define Z16F_OSCCTL_POFEN _HX8(10) /* Bit 4: Failure detection enabled */
+#define Z16F_OSCCTL_WDFEN _HX8(08) /* Bit 3: WD Failuare detection enabled*/
+#define Z16F_OSCCTL_FLPEN _HX8(04) /* Bit 2: Flash low power enabled */
+#define Z16F_OSCCTL_INT56 _HX8(00) /* Bits 0-1=0: Intenal 5.6 MHz */
+#define Z16F_OSCCTL_EXTCLK _HX8(02) /* Bits 0-1=2: Extenal clock */
+#define Z16F_OSCCTL_WDT10KHZ _HX8(03) /* Bits 0-1=3: WD Timer 10 KHz*/
+
/* GPIO Port A-K ********************************************************************/
#define Z16F_GPIOA_IN _HX32(ffffe100) /* 8-bits: Port A Input Data */
@@ -249,32 +348,103 @@
#define Z16F_UART1_BRH _HX32(ffffe216) /* 8-bits: UART1 Baud Rate High Byte */
#define Z16F_UART1_BRL _HX32(ffffe217) /* 8-bits: UART1 Baud Rate Low Byte */
-/* Control Registers ***************************************************************/
-
-#define Z16F_CNTRL_PCOV _HX32(fffffe04) /* 32-bits: Program counter overflow */
-#define Z16F_CNTRL_SPOV _HX32(fffffe0c) /* 32-bits: Stack pointer overflow */
-#define Z16F_CNTRL_FLAGS _HX32(fffffe10) /* 8-bits: flags */
-#define Z16F_CNTRL_CPUCTL _HX32(fffffe12) /* 8-bits: CPU control */
-
-/* Flag register bits ***************************************************************/
+/* Timer0/1/2 registers *************************************************************/
+
+#define Z16F_TIMER0_HL _HX32(ffffe300) /* 16-bit: Timer 0 */
+#define Z16F_TIMER0_H _HX32(ffffe300) /* 8-bit: Timer 0 High Byte */
+#define Z16F_TIMER0_L _HX32(ffffe301) /* 8-bit: Timer 0 Low Byte */
+#define Z16F_TIMER0_R _HX32(ffffe302) /* 16-bit: Timer 0 Reload */
+#define Z16F_TIMER0_RH _HX32(ffffe302) /* 8-bit: Timer 0 Reload High Byte */
+#define Z16F_TIMER0_RL _HX32(ffffe303) /* 8-bit: Timer 0 Reload Low Byte */
+#define Z16F_TIMER0_PWM _HX32(ffffe304) /* 16-bit: Timer 0 PWM */
+#define Z16F_TIMER0_PWMH _HX32(ffffe304) /* 8-bit: Timer 0 PWM High Byte */
+#define Z16F_TIMER0_PWML _HX32(ffffe305) /* 8-bit: Timer 0 PWM Low Byte */
+#define Z16F_TIMER0_CTL _HX32(ffffe306) /* 16-bit: Timer 0 Control */
+#define Z16F_TIMER0_CTL0 _HX32(ffffe306) /* 8-bit: Timer 0 Control 0 */
+#define Z16F_TIMER0_CTL1 _HX32(ffffe307) /* 8-bit: Timer 0 Control 1 */
+
+#define Z16F_TIMER1_HL _HX32(ffffe310) /* 16-bit: Timer 1 */
+#define Z16F_TIMER1_H _HX32(ffffe310) /* 8-bit: Timer 1 High Byte */
+#define Z16F_TIMER1_L _HX32(ffffe311) /* 8-bit: Timer 1 Low Byte */
+#define Z16F_TIMER1_R _HX32(ffffe312) /* 16-bit: Timer 1 Reload */
+#define Z16F_TIMER1_RH _HX32(ffffe312) /* 8-bit: Timer 1 Reload High Byte */
+#define Z16F_TIMER1_RL _HX32(ffffe313) /* 8-bit: Timer 1 Reload Low Byte */
+#define Z16F_TIMER1_PWM _HX32(ffffe314) /* 16-bit: Timer 1 PWM */
+#define Z16F_TIMER1_PWMH _HX32(ffffe314) /* 8-bit: Timer 1 PWM High Byte */
+#define Z16F_TIMER1_PWML _HX32(ffffe315) /* 8-bit: Timer 1 PWM Low Byte */
+#define Z16F_TIMER1_CTL _HX32(ffffe316) /* 16-bit: Timer 1 Control */
+#define Z16F_TIMER1_CTL0 _HX32(ffffe316) /* 8-bit: Timer 1 Control 0 */
+#define Z16F_TIMER1_CTL1 _HX32(ffffe317) /* 8-bit: Timer 1 Control 1 */
+
+#define Z16F_TIMER2_HL _HX32(ffffe320) /* 16-bit: Timer 2 */
+#define Z16F_TIMER2_H _HX32(ffffe320) /* 8-bit: Timer 2 High Byte */
+#define Z16F_TIMER2_L _HX32(ffffe321) /* 8-bit: Timer 2 Low Byte */
+#define Z16F_TIMER2_R _HX32(ffffe322) /* 16-bit: Timer 2 Reload */
+#define Z16F_TIMER2_RH _HX32(ffffe322) /* 8-bit: Timer 2 Reload High Byte */
+#define Z16F_TIMER2_RL _HX32(ffffe323) /* 8-bit: Timer 2 Reload Low Byte */
+#define Z16F_TIMER2_PWM _HX32(ffffe324) /* 16-bit: Timer 2 PWM */
+#define Z16F_TIMER2_PWMH _HX32(ffffe324) /* 8-bit: Timer 2 PWM High Byte */
+#define Z16F_TIMER2_PWML _HX32(ffffe325) /* 8-bit: Timer 2 PWM Low Byte */
+#define Z16F_TIMER2_CTL _HX32(ffffe326) /* 16-bit: Timer 2 Control */
+#define Z16F_TIMER2_CTL0 _HX32(ffffe326) /* 8-bit: Timer 2 Control 0 */
+#define Z16F_TIMER2_CTL1 _HX32(ffffe327) /* 8-bit: Timer 2 Control 1 */
+
+/* Common timer0/1/2 register bit definitions ***************************************/
+
+#define Z16F_TIMERCTL0_TMODE _HX8(80) /* Bit 7: Timer mode */
+ /* Bits 5-6: Timer configuration,
+ * Interpretation depends on timer mode */
+#define Z16F_TIMERCTL0_RELOAD _HX8(00) /* Interrupt occurs on reload or capture */
+#define Z16F_TIMERCTL0_DISABLED _HX8(40) /* Disabled */
+#define Z16F_TIMERCTL0_INACTIVE _HX8(40) /* Interrrupt occurs on inactive gate edge */
+#define Z16F_TIMERCTL0_CAPTURE _HX8(40) /* Interrupt occurs on capture */
+#define Z16F_TIMERCTL0_RELOAD _HX8(60) /* Interrupt occurs on reload */
+#define Z16F_TIMERCTL0_CASCADE _HX8(10) /* Bit 4: Timer is cascaded */
+ /* Bits 1-2: PW mode */
+#define Z16F_TIMERCTL0_NODELAY _HZ8(00) /* No delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(01) /* 2 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(02) /* 4 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(03) /* 8 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(04) /* 16 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(05) /* 32 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(06) /* 64 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(07) /* 128 cycle delay */
+
+#define Z16F_TIMERCTL1_TEN _HX8(80) /* Bit 7: Timer enable */
+#define Z16F_TIMERCTL1_TPOL _HX8(40) /* Bit 6: Input output polarity */
+ /* Bits 3-5: Timer prescale value */
+#define Z16F_TIMERSCTL1_DIV1 _HX8(00) /* Divide by 1 */
+#define Z16F_TIMERSCTL1_DIV2 _HX8(08) /* Divide by 2 */
+#define Z16F_TIMERSCTL1_DIV4 _HX8(10) /* Divide by 4 */
+#define Z16F_TIMERSCTL1_DIV8 _HX8(18) /* Divide by 8 */
+#define Z16F_TIMERSCTL1_DIV16 _HX8(20) /* Divide by 16 */
+#define Z16F_TIMERSCTL1_DIV32 _HX8(28) /* Divide by 32 */
+#define Z16F_TIMERSCTL1_DIV64 _HX8(30) /* Divide by 64 */
+#define Z16F_TIMERSCTL1_DIV128 _HX8(38) /* Divide by 128 */
+ /* Bits 0-2: Timer mode + CTL0 TMODE bit*/
+#define Z16F_TIMERSCTL1_ONESHOT _HX8(00) /* One shot mode (CTL0 TMOD = 0) */
+#define Z16F_TIMERSCTL1_PWMDO _HX8(00) /* One shot mode (CTL0 TMOD = 1) */
+#define Z16F_TIMERSCTL1_CONT _HX8(01) /* Continuous mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_CAPRST _HX8(01) /* Capture restart mode (CTL0 TMOD = 1)*/
+#define Z16F_TIMERSCTL1_COUNTER _HX8(02) /* Counter mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_CMPCNTR _HX8(02) /* Comparator counter mode (CTL0 TMOD = 1)*/
+#define Z16F_TIMERSCTL1_PWMSO _HX8(03) /* PWM single output mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_TRIGOS _HX8(03) /* Triggered one shot (CTL0 TMOD = 1)*/
+#define Z16F_TIMERSCTL1_CAPTURE _HX8(04) /* Capture mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_COMPARE _HX8(05) /* Compare mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_GATED _HX8(06) /* Gated mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_CAPCMP _HX8(07) /* Capture/Compare mode (CTL0 TMOD = 0)*/
+
+/* Register access macros ***********************************************************/
-#define Z16F_CNTRL_FLAGS_C _HX8(80) /* Bit 7: Carry flag */
-#define Z16F_CNTRL_FLAGS_Z _HX8(40) /* Bit 6: Zero flag */
-#define Z16F_CNTRL_FLAGS_S _HX8(20) /* Bit 5: Sign flag */
-#define Z16F_CNTRL_FLAGS_V _HX8(10) /* Bit 4: Overflow flag */
-#define Z16F_CNTRL_FLAGS_B _HX8(08) /* Bit 3: Blank flag */
-#define Z16F_CNTRL_FLAGS_F1 _HX8(04) /* Bit 2: User flag 1 */
-#define Z16F_CNTRL_FLAGS_CIRQE _HX8(02) /* Bit 1: Chained interrupt enable */
-#define Z16F_CNTRL_FLAGS_IRQE _HX8(01) /* Bit 0: Master interrupt enable */
-
-/* CPU control register bits ********************************************************/
-
- /* Bits 7-2: Reserved, must be zero */
- /* Bits 1-0: DMA bandwidth control */
-#define Z16F_CNTRL_CPUCTL_BWALL _HX8(00) /* DMA can consume 100% bandwidth */
-#define Z16F_CNTRL_CPUCTL_BW11 _HX8(01) /* DMA can do 1 transaction per 1 cycle */
-#define Z16F_CNTRL_CPUCTL_BW12 _HX8(01) /* DMA can do 1 transaction per 2 cycles */
-#define Z16F_CNTRL_CPUCTL_BW13 _HX8(01) /* DMA can do 1 transaction per 3 cycles */
+#ifndef __ASSEMBLY__
+# define getreg8(a) (*(ubyte volatile near*)((a) & 0xffff))
+# define putreg8(v,a) (*(ubyte volatile near*)((a) & 0xffff) = (v))
+# define getreg16(a) (*(uint16 volatile near*)((a) & 0xffff))
+# define putreg16(v,a) (*(uint16 volatile near*)((a) & 0xffff) = (v))
+# define getreg32(a) (*(uint32 volatile near*)((a) & 0xffff))
+# define putreg32(v,a) (*(uint32 volatile near*)((a) & 0xffff) = (v))
+#endif /* __ASSEMBLY__ */
/************************************************************************************
* Public Function Prototypes
@@ -302,6 +472,6 @@ extern void z16f_lowuartinit(void);
#ifdef __cplusplus
}
#endif
-#endif
+#endif /* __ASSEMBLY__ */
#endif /* __Z16F_CHIP_H */
diff --git a/nuttx/arch/z16/src/z16f/z16f_clkinit.c b/nuttx/arch/z16/src/z16f/z16f_clkinit.c
new file mode 100644
index 000000000..3b8fa87e8
--- /dev/null
+++ b/nuttx/arch/z16/src/z16f/z16f_clkinit.c
@@ -0,0 +1,245 @@
+/***************************************************************************
+ * z16f/z16f_clkinit.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Based upon sample code included with the Zilog ZDS-II toolchain.
+ *
+ * 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
+ ***************************************************************************/
+
+/***************************************************************************
+ * Definitions
+ ***************************************************************************/
+
+/* System clock source value from ZDS target settings */
+
+extern _Erom unsigned long SYS_CLK_SRC;
+#define _DEFSRC ((unsigned long)&SYS_CLK_SRC)
+
+/* System clock frequency value from ZDS target settings */
+
+extern _Erom unsigned long SYS_CLK_FREQ;
+#define _DEFCLK ((unsigned long)&SYS_CLK_FREQ)
+
+/* Setup FLASH options at address 0x00000000 */
+
+Z16F_FLOPTION0 = (Z16F_FLOPTION0_MAXPWR|Z16F_FLOPTION0_WDTRES|\
+ Z16F_FLOPTION0_WDTA0|Z16F_FLOPTION0_VBOA0|\
+ Z16F_FLOPTION0_DBGUART|Z16F_FLOPTION0_FWP|
+ Z16F_FLOPTION0_RP);
+Z16F_FLOPTION1 = (Z16F_FLOPTION1_RESVD|Z16F_FLOPTION1_MCEN|\
+ Z16F_FLOPTION1_OFFH|Z16F_FLOPTION1_OFFL);
+Z16F_FLOPTION2 = Z16F_FLOPTION2_RESVD;
+Z16F_FLOPTION3 = (Z16F_FLOPTION3_RESVD|Z16F_FLOPTION3_NORMAL);
+
+/***************************************************************************
+ * Private Functions
+ ***************************************************************************/
+
+#ifndef CONFIG_DEBUG
+/***************************************************************************
+ * System clock initialization--DEBUG. Code Using Frequency Input from
+ * ZDS IDE.
+ *
+ * The sysclk_init function below uses the flexibility of the ZDS debug
+ * environment to allow the user to experiment with different clock frequency
+ * settings to help determine the frequency requirements of his Project. The
+ * function allows the selection of internal 5.56 MHz, the 10 KHz Watch Dog
+ * timer or an external clock Source. ZNEO supports clock frequency division
+ * with the Clock Division Register. The clock division Register will divide
+ * by (a minimum of) 2 or more. An assumed clock value of 5.5 MHz internal or
+ * an external clock of 20 MHz was used as the crystal frequency to match the
+ * Demo Target. The User can enter a new frequency in the OTHER clock dialog
+ * Target Setting. The clock frequency is passed with the variable _DEFFREQ
+ * and the clock source is _DEFSRC.
+ *
+ * NOTE: The UART output is designed to work with 5.56 MHz internal and 20 MHz
+ * External clock frequencies at the Default Baud rate of 57.6K Baud.
+ * Entering different clock frequencies may cause the UART to stop transmitting
+ * unless the user makes changes to the UART routines.
+ *
+ * Function Not Recommended for Release Code.
+ *
+ ***************************************************************************/
+
+static void z16f_sysclkinit(void)
+{
+ /* _DEFSRC (SCKSEL Bits 1,0) is passed to program view the .linkcmd file */
+
+ int count;
+ int temp_oscdiv;
+
+ if ((getreg8(Z16F_OSC_CTL) & 0x03) != _DEFSRC)
+ {
+ if (_DEFSRC == 0)
+ {
+ /* Enable 5.6 MHz clock RESET DEFAULT*/
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xa0, Z16F_OSC_CTL);
+
+ /* Wait for oscillator to stabilize */
+
+ for (count = 0; count < 10000; count++);
+
+ /* Select 5.6 MHz clock */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xa0 | _DEFSRC, Z16F_OSC_CTL);
+ }
+
+ if (_DEFSRC == 1)
+ {
+ /* enable (reserved) clock */
+ }
+
+ if (_DEFSRC == 2 )
+ {
+ /* Enable external oscillator */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xe0, Z16F_OSC_CTL);
+
+ /* Wait for oscillator to stabilize */
+
+ for (count = 0; count < 10000; count++);
+
+ /* select external oscillator */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xe0 | _DEFSRC, Z16F_OSC_CTL);
+ }
+
+ if (_DEFSRC == 3)
+ {
+ /* Enable watchdog timer clock */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xb0, Z16F_OSC_CTL);
+
+ /* Wait for oscillator to stabilize */
+
+ for (count = 0; count < 10000; count++);
+
+ /* Select watch dog timer clock */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xb0 | _DEFSRC, Z16F_OSC_CTL);
+ }
+ }
+
+ /* Check SysClock Frequency.
+ * divide the clock if the user has selected the OTHER option for frequency.
+ */
+
+ if (((_DEFSRC == 0) && (_DEFCLK < 3000000ul)) ||
+ ((_DEFSRC == 2) && (_DEFCLK <= 10000000ul)))
+ {
+ if ( _DEFSRC ==0 )
+ {
+ temp_oscdiv = ( 5526000ul / (_DEFCLK +1) );
+ /* Example @ 32 KHz: 0xAC (172 decimal)*/
+ }
+ else
+ {
+ temp_oscdiv = (( 20000000ul / (_DEFCLK +1) ) + 1 );
+ }
+
+ /* Unlock and Set the Oscillator Division Register (Z16F_OSC_DIV) */
+
+ putreg8(0xE7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(temp_oscdiv, Z16F_OSC_DIV);
+ }
+
+ /* Wait for oscillator to stabilize */
+
+ for (count = 0; count < 10000; count++);
+}
+
+#else
+/***************************************************************************
+ * System Clock Initialization Recommended for Release Code
+ *
+ * The z16f_sysclkinit function below allows the user to switch from
+ * Internal to External Clock source and should be used for clock frequency
+ * switching to the External Clock. Note the delay to allow the clock to
+ * stabilize.
+ ***************************************************************************/
+
+static void z16f_sysclkinit(void)
+{
+ /*
+ * _DEFSRC (SCKSEL Bits 1,0) is passed to program from Target Settings Dialog.
+ * I.E. extern _Erom unsigned long SYS_CLK_SRC;
+ */
+ int count;
+
+ if ((getreg8(Z16F_OSC_CTL) & 0x03) != _DEFSRC)
+ {
+ /* enable external oscillator */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xe0, Z16F_OSC_CTL);
+
+ /* wait for oscillator to stabilize */
+ for (count = 0; count < 10000; count++);
+
+ /* select external oscillator */
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xe0 | _DEFSRC, Z16F_OSC_CTL);
+ }
+}
+#endif /* CONFIG_DEBUG */
+
+/***************************************************************************
+ * Public Functions
+ ***************************************************************************/
+/***************************************************************************
+ * Name: z16f_clkinit
+ ***************************************************************************/
+void z16f_clkinit(void)
+{
+ z16f_sysclkinit();
+}
+
diff --git a/nuttx/arch/z16/src/z16f/z16f_irq.c b/nuttx/arch/z16/src/z16f/z16f_irq.c
new file mode 100644
index 000000000..f5335af15
--- /dev/null
+++ b/nuttx/arch/z16/src/z16f/z16f_irq.c
@@ -0,0 +1,197 @@
+/****************************************************************************
+ * z16f/z16f_irq.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <nuttx/irq.h>
+
+#include "chip/chip.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_irqinitialize
+ ****************************************************************************/
+
+void up_irqinitialize(void)
+{
+ /* Clear and disable all interrupts. Set all to priority 0. */
+
+ putreg8(0xff, Z16F_IRQ0);
+ putreg8(0xff, Z16F_IRQ1);
+ putreg8(0xff, Z16F_IRQ2);
+
+ putreg16(0x0000, Z16F_IRQ0_EN);
+ putreg16(0x0000, Z16F_IRQ1_EN);
+ putreg16(0x0000, Z16F_IRQ2_EN);
+
+ /* currents_regs is non-NULL only while processing an interrupt */
+
+ current_regs = NULL;
+
+ /* And finally, enable interrupts */
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+ EI();
+#endif
+}
+
+/****************************************************************************
+ * Name: up_disable_irq
+ *
+ * Description:
+ * Disable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_disable_irq(int irq)
+{
+ /* System exceptions cannot be disabled */
+
+ if (irq >= Z16F_IRQ_IRQ0)
+ {
+ /* Disable the interrupt by clearing the corresponding bit in the
+ * appropriate IRQ enable register.
+ */
+
+ if (irq < Z16F_IRQ_IRQ1)
+ {
+ putreg8((getreg8(Z16F_IRQ0_ENH) & ~Z16_IRQ0_BIT(irq)), Z16F_IRQ0_ENH);
+ }
+ else if (irq < Z16F_IRQ_IRQ2)
+ {
+ putreg8((getreg8(Z16F_IRQ1_ENH) & ~Z16_IRQ1_BIT(irq)), Z16F_IRQ1_ENH);
+ }
+ else if (irq < NR_IRQS)
+ {
+ putreg8((getreg8(Z16F_IRQ2_ENH) & ~Z16_IRQ2_BIT(irq)), Z16F_IRQ2_ENH);
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: up_enable_irq
+ *
+ * Description:
+ * Enable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_enable_irq(int irq)
+{
+ /* System exceptions cannot be disabled */
+
+ if (irq >= Z16F_IRQ_IRQ0)
+ {
+ /* Enable the interrupt by setting the corresponding bit in the
+ * appropriate IRQ enable register.
+ */
+
+ if (irq < Z16F_IRQ_IRQ1)
+ {
+ putreg8((getreg8(Z16F_IRQ0_ENH) | Z16_IRQ0_BIT(irq)), Z16F_IRQ0_ENH);
+ }
+ else if (irq < Z16F_IRQ_IRQ2)
+ {
+ putreg8((getreg8(Z16F_IRQ1_ENH) | Z16_IRQ1_BIT(irq)), Z16F_IRQ1_ENH);
+ }
+ else if (irq < NR_IRQS)
+ {
+ putreg8((getreg8(Z16F_IRQ2_ENH) | Z16_IRQ2_BIT(irq)), Z16F_IRQ2_ENH);
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: up_maskack_irq
+ *
+ * Description:
+ * Mask the IRQ and acknowledge it
+ *
+ ****************************************************************************/
+
+void up_maskack_irq(int irq)
+{
+ /* System exceptions cannot be disabled or acknowledged */
+
+ if (irq >= Z16F_IRQ_IRQ0)
+ {
+ /* Disable the interrupt by clearing the corresponding bit in the
+ * appropriate IRQ enable register and acknowledge it by setting the
+ * corresponding bit in the IRQ status register.
+ */
+
+ if (irq < Z16F_IRQ_IRQ1)
+ {
+ putreg8((getreg8(Z16F_IRQ0_ENH) & ~Z16_IRQ0_BIT(irq)), Z16F_IRQ0_ENH);
+ putreg8(Z16_IRQ0_BIT(irq), Z16F_IRQ0);
+ }
+ else if (irq < Z16F_IRQ_IRQ2)
+ {
+ putreg8((getreg8(Z16F_IRQ1_ENH) & ~Z16_IRQ1_BIT(irq)), Z16F_IRQ1_ENH);
+ putreg8(Z16_IRQ1_BIT(irq), Z16F_IRQ2);
+ }
+ else if (irq < NR_IRQS)
+ {
+ putreg8((getreg8(Z16F_IRQ2_ENH) & ~Z16_IRQ2_BIT(irq)), Z16F_IRQ2_ENH);
+ putreg8(Z16_IRQ2_BIT(irq), Z16F_IRQ2);
+ }
+ }
+}
diff --git a/nuttx/arch/z16/src/z16f/z16f_timerisr.c b/nuttx/arch/z16/src/z16f/z16f_timerisr.c
new file mode 100644
index 000000000..12925b933
--- /dev/null
+++ b/nuttx/arch/z16/src/z16f/z16f_timerisr.c
@@ -0,0 +1,135 @@
+/***************************************************************************
+ * z16f/z16f_timerisr.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ***************************************************************************/
+
+/***************************************************************************
+ * Included Files
+ ***************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "clock_internal.h"
+#include "up_internal.h"
+
+/***************************************************************************
+ * Definitions
+ ***************************************************************************/
+
+/* System clock frequency value from ZDS target settings */
+
+extern _Erom unsigned long SYS_CLK_FREQ;
+#define _DEFCLK ((unsigned long)&SYS_CLK_FREQ)
+
+/***************************************************************************
+ * Private Types
+ ***************************************************************************/
+
+/***************************************************************************
+ * Private Function Prototypes
+ ***************************************************************************/
+
+/***************************************************************************
+ * Global Functions
+ ***************************************************************************/
+
+/***************************************************************************
+ * Function: up_timerisr
+ *
+ * Description:
+ * The timer ISR will perform a variety of services for various portions
+ * of the system.
+ *
+ ***************************************************************************/
+
+int up_timerisr(int irq, uint32 *regs)
+{
+ /* Process timer interrupt */
+
+ sched_process_timer();
+ return 0;
+}
+
+/***************************************************************************
+ * Function: up_timerinit
+ *
+ * Description:
+ * This function is called during start-up to initialize
+ * the timer interrupt.
+ *
+ ***************************************************************************/
+
+void up_timerinit(void)
+{
+ up_disable_irq(Z16F_IRQ_SYSTIMER);
+
+ /* Disable the timer and configure for divide by 1 and continuous mode. */
+
+ putreg16( Z16F_TIMERSCTL1_DIV1 | Z16F_TIMERSCTL1_CONT);
+
+ /* Assign an intial timer value */
+
+ putreg16(0x0001, Z16F_TIMER0_HL);
+
+ /* Set the timer reload value.
+ *
+ * In continuous mode:
+ *
+ * timer_frequency = system_clock_freqency / divisor / reload_value
+ * or
+ * reload_value = (system_clock_frequency / timer_frequency / divisor
+ *
+ * For system_clock_frequency=200MHz, timer_frequency=100KHz, and divisor=1,
+ * this yields 200.
+ */
+
+ putreg16(((uint32)_DEFCLK / 100000), Z16F_TIMER0_R);
+
+ /* Enable the timer */
+
+ putreg8((getret8(Z16F_TIMER0_CTL1) |= Z16F_TIMERCTL1_TEN), Z16F_TIMER0_CTL1);
+
+ /* Set the timer priority */
+
+ /* Attach and enable the timer interrupt (leaving at priority 0 */
+
+ irq_attach(Z16F_IRQ_SYSTIMER, (xcpt_t)up_timerisr);
+ up_enable_irq(Z16F_IRQ_SYSTIMER);
+}
+
diff --git a/nuttx/arch/z80/src/common/up_releasestack.c b/nuttx/arch/z80/src/common/up_releasestack.c
index b00b9ab0c..48328737c 100644
--- a/nuttx/arch/z80/src/common/up_releasestack.c
+++ b/nuttx/arch/z80/src/common/up_releasestack.c
@@ -1,7 +1,7 @@
/************************************************************
* common/up_releasestack.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 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.
*
diff --git a/nuttx/arch/z80/src/common/up_udelay.c b/nuttx/arch/z80/src/common/up_udelay.c
index 9982644ea..98c409cb6 100644
--- a/nuttx/arch/z80/src/common/up_udelay.c
+++ b/nuttx/arch/z80/src/common/up_udelay.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_udelay.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 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.
*
diff --git a/nuttx/arch/z80/src/common/up_usestack.c b/nuttx/arch/z80/src/common/up_usestack.c
index 2da044182..de8e7e87c 100644
--- a/nuttx/arch/z80/src/common/up_usestack.c
+++ b/nuttx/arch/z80/src/common/up_usestack.c
@@ -1,7 +1,7 @@
/************************************************************
* common/up_usestack.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 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.
*
diff --git a/nuttx/configs/z16f2800100zcog/src/Makefile b/nuttx/configs/z16f2800100zcog/src/Makefile
index 33ac4263b..0de50c802 100644
--- a/nuttx/configs/z16f2800100zcog/src/Makefile
+++ b/nuttx/configs/z16f2800100zcog/src/Makefile
@@ -43,7 +43,7 @@ CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(INCLUDES) $(ARCH
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS =
+CSRCS = z16_lowinit.c
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/configs/z16f2800100zcog/src/z16f_lowinit.c b/nuttx/configs/z16f2800100zcog/src/z16f_lowinit.c
new file mode 100644
index 000000000..258cb4630
--- /dev/null
+++ b/nuttx/configs/z16f2800100zcog/src/z16f_lowinit.c
@@ -0,0 +1,81 @@
+/***************************************************************************
+ * configs/z16f2800100zcog/src/z16f_lowinit.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Based upon sample code included with the Zilog ZDS-II toolchain.
+ *
+ * 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
+ ***************************************************************************/
+
+/***************************************************************************
+ * Definitions
+ ***************************************************************************/
+
+/***************************************************************************
+ * Private Functions
+ ***************************************************************************/
+
+static void z16f_gpioinit(void)
+{
+ /* Configure LEDs and Run/Stop switch port */
+
+ putreg(getreg(Z16F_GPIOA_DD) | 0x87, Z16F_GPIOA_DD);
+ putreg(getreg(Z16F_GPIOA_OUT) | 0x07, Z16F_GPIOA_OUT);
+ putreg(getreg(Z16F_GPIOA_DD) | 0xF8, Z16F_GPIOA_DD);
+
+ /* Configure rate switch port */
+
+ putreg(getreg(Z16F_GPIOB_DD) | 0x20, Z16F_GPIOB_DD);
+ putreg(getreg(Z16F_GPIOB_AFL) | 0x20, Z16F_GPIOB_AFL);
+
+#if 0 /* Not yet */
+ ADC0MAX = 0x05;
+ ADC0CTL = 0xF5;
+#endif
+
+ /* Configure Direction switch port */
+
+ putreg(getreg() | 0x01, Z16F_GPIOC_DD);
+}
+
+/***************************************************************************
+ * Public Functions
+ ***************************************************************************/
+
+void z16f_lowinit(void)
+{
+ z16f_gpioinit();
+}
+