summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-24 22:43:38 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-24 22:43:38 +0000
commitb146fd97783dd3b0784d2af61dedc541a53b1140 (patch)
tree79efb10f5364d450c68c73c6fcb069ca1065a422 /nuttx/arch
parent4d266f054dd181e35ffbe6546dc2d7c7617d63b1 (diff)
downloadpx4-nuttx-b146fd97783dd3b0784d2af61dedc541a53b1140.tar.gz
px4-nuttx-b146fd97783dd3b0784d2af61dedc541a53b1140.tar.bz2
px4-nuttx-b146fd97783dd3b0784d2af61dedc541a53b1140.zip
Add Z16f context switching logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@562 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/z16/include/z16f/irq.h80
-rw-r--r--nuttx/arch/z16/src/common/up_doirq.c15
-rw-r--r--nuttx/arch/z16/src/common/up_internal.h2
-rw-r--r--nuttx/arch/z16/src/z16f/Make.defs2
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_head.S697
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_lowuart.S468
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_restoreusercontext.S105
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_saveusercontext.S222
8 files changed, 964 insertions, 627 deletions
diff --git a/nuttx/arch/z16/include/z16f/irq.h b/nuttx/arch/z16/include/z16f/irq.h
index 613710a52..f9bcd1482 100644
--- a/nuttx/arch/z16/include/z16f/irq.h
+++ b/nuttx/arch/z16/include/z16f/irq.h
@@ -74,9 +74,9 @@
#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_C0 (17) /* Vector: IRQ2.0 0x6C Port C0, both edges DMA0 */
+#define Z16F_IRQ_C1 (18) /* Vector: IRQ2.1 0x68 Port C1, both edges DMA1 */
+#define Z16F_IRQ_C2 (19) /* Vector: IRQ2.2 0x64 Port C2, both edges DMA2 */
#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 */
@@ -96,33 +96,69 @@
*
* This stack frame is created on each interrupt. These registers are stored
* in the TCB to many context switches.
+ *
+ * The following represent all of the "static" registers r8-r15. These
+ * are registers that whose value must be retained across function calls.
+ * These registers must be saved bothby interrupt handling context switch
+ * switch logic and also by user-initiated context switches.
+ *
+ * Registers are saved in the order consistent with pushmho <r8-r15>,
+ * that is with r15 pushed first and r8 push last. Since the z16f has
+ * a "push-down" stack, the registers will be "in order" in memory.
+ */
+
+#define REG_R8 ( 0) /* 32-bits: R8 */
+#define REG_R9 ( 2) /* 32-bits: R9 */
+#define REG_R10 ( 4) /* 32-bits: R10 */
+#define REG_R11 ( 6) /* 32-bits: R11 */
+#define REG_R12 ( 8) /* 32-bits: R12 */
+#define REG_R13 (10) /* 32-bits: R13 */
+
+/* The frame pointer and the SP at the point of task resumption must
+ * always be saved.
+ */
+
+#define REG_R14 (12) /* 32-bits: R14 = fp */
+#define REG_FP REG_R14
+#define REG_R15 (14) /* 32-bits: R15 = sp */
+#define REG_SP REG_R15
+
+/* The following represent all of the "volatile" registers r0-r7. These
+ * are registers that whose value need not be retained across function
+ * calls. These registers must be saved by interrupt handling context
+ * switch logic but not by user-initiated context switches.
+ *
+ * Registers are saved in the order consistent with pushmlo <r0-r7>,
+ * that is with r7 pushed first and r0 push last. Since the z16f has
+ * a "push-down" stack, the registers will be "in order" in memory.
+ */
+
+#define REG_R0 (16) /* 32-bits: R0 */
+#define REG_R1 (18) /* 32-bits: R1 */
+#define REG_R2 (20) /* 32-bits: R2 */
+#define REG_R3 (22) /* 32-bits: R3 */
+#define REG_R4 (24) /* 32-bits: R4 */
+#define REG_R5 (26) /* 32-bits: R5 */
+#define REG_R6 (28) /* 32-bits: R6 */
+#define REG_R7 (30) /* 32-bits: R7 */
+
+/* The following two offsets represent the state of the stack on entry
+ * into the interrupt handler:
+ *
+ * TOS[0] = PC[31:24]
+ * TOS[1] = PC[23:16]
+ * TOS[2] = PC[15:8]
+ * TOS[3] = PC[7:0]
+ * TOS[4] = 0
+ * TOS[5] = flags
*/
-#define REG_R0 ( 0) /* 32-bits: R0 */
-#define REG_R1 ( 2) /* 32-bits: R0 */
-#define REG_R2 ( 4) /* 32-bits: R0 */
-#define REG_R3 ( 6) /* 32-bits: R0 */
-#define REG_R4 ( 8) /* 32-bits: R0 */
-#define REG_R5 (10) /* 32-bits: R0 */
-#define REG_R6 (12) /* 32-bits: R0 */
-#define REG_R7 (14) /* 32-bits: R0 */
-#define REG_R8 (16) /* 32-bits: R0 */
-#define REG_R9 (18) /* 32-bits: R0 */
-#define REG_R10 (20) /* 32-bits: R0 */
-#define REG_R11 (22) /* 32-bits: R0 */
-#define REG_R12 (24) /* 32-bits: R0 */
-#define REG_R13 (26) /* 32-bits: R0 */
-#define REG_R14 (28) /* 32-bits: R0 */
-#define REG_R15 (30) /* 32-bits: R0 */
#define REG_PC (32) /* 32-bits: Return PC */
#define REG_FLAGS (34) /* 16-bits: Flags register (with 0x00 padding) */
#define XCPTCONTEXT_REGS (35)
#define XCPTCONTEXT_SIZE (2 * XCPTCONTEXT_REGS)
-#define REG_FP REG_R14
-#define REG_SP REG_R15
-
/****************************************************************************
* Public Types
****************************************************************************/
diff --git a/nuttx/arch/z16/src/common/up_doirq.c b/nuttx/arch/z16/src/common/up_doirq.c
index fab038411..93c8c9639 100644
--- a/nuttx/arch/z16/src/common/up_doirq.c
+++ b/nuttx/arch/z16/src/common/up_doirq.c
@@ -68,8 +68,19 @@
* Public Functions
****************************************************************************/
-void up_doirq(int irq, chipreg_t *regs)
+/****************************************************************************
+ * Name: up_doirq
+ *
+ * Description:
+ * Interface between low-level IRQ decode logic and the NuttX IRQ dispatch
+ * logic.
+ *
+ ****************************************************************************/
+
+FAR chipreg_t *up_doirq(int irq, FAR chipreg_t *regs)
{
+ chipreg_t *ret = regs;
+
up_ledon(LED_INIRQ);
#ifdef CONFIG_SUPPRESS_INTERRUPTS
PANIC(OSERR_ERREXCEPTION);
@@ -93,6 +104,7 @@ void up_doirq(int irq, chipreg_t *regs)
/* Indicate that we are no long in an interrupt handler */
+ ret = current_regs;
current_regs = NULL;
/* Unmask the last interrupt (global interrupts are still
@@ -103,4 +115,5 @@ void up_doirq(int irq, chipreg_t *regs)
}
up_ledoff(LED_INIRQ);
#endif
+ return ret;
}
diff --git a/nuttx/arch/z16/src/common/up_internal.h b/nuttx/arch/z16/src/common/up_internal.h
index c09226bf0..206fdc98a 100644
--- a/nuttx/arch/z16/src/common/up_internal.h
+++ b/nuttx/arch/z16/src/common/up_internal.h
@@ -97,7 +97,7 @@ extern chipreg_t *current_regs;
/* Defined in files with the same name as the function */
extern void up_copystate(FAR chipreg_t *dest, FAR chipreg_t *src);
-extern void up_doirq(int irq, FAR chipreg_t *regs);
+extern FAR chipreg_t *up_doirq(int irq, FAR chipreg_t *regs);
extern void up_restoreusercontext(FAR chipreg_t *regs);
extern void up_irqinitialize(void);
extern int up_saveusercontext(FAR chipreg_t *regs);
diff --git a/nuttx/arch/z16/src/z16f/Make.defs b/nuttx/arch/z16/src/z16f/Make.defs
index 4c3a610e4..c50e07039 100644
--- a/nuttx/arch/z16/src/z16f/Make.defs
+++ b/nuttx/arch/z16/src/z16f/Make.defs
@@ -43,6 +43,6 @@ CMN_CSRCS = up_allocateheap.c up_initialize.c up_schedulesigaction.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 z16f_saveusercontext.S
+CHIP_SSRCS = z16f_lowuart.S z16f_saveusercontext.S z16f_restoreusercontext.S
CHIP_CSRCS = z16f_clkinit.c z16f_irq.c z16f_timerisr.c z16f_serial.c
diff --git a/nuttx/arch/z16/src/z16f/z16f_head.S b/nuttx/arch/z16/src/z16f/z16f_head.S
index 9e9012a5a..ca69b5ddd 100755
--- a/nuttx/arch/z16/src/z16f/z16f_head.S
+++ b/nuttx/arch/z16/src/z16f/z16f_head.S
@@ -1,264 +1,433 @@
-/**************************************************************************
- * arch/z16/src/z16f/z16f_head.S
- * Z16F Reset Entry Point
- *
- * 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>
-
-/**************************************************************************
- * External References / External Definitions
- **************************************************************************/
-
- xref _z16f_lowinit:EROM
-#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC)
- xref _z16f_lowuartinit:EROM
-#endif
- xref _os_start:EROM
- xdef _reset
- xdef _sysexc_isr
- xdef _timer2_isr
- xdef _timer1_isr
- xdef _timer0_isr
- xdef _uart0rx_isr
- xdef _uart0tx_isr
- xdef _i2c_isr
- xdef _spi_isr
- xdef _adc_isr
- xdef _p7ad_isr
- xdef _p6ad_isr
- xdef _p5ad_isr
- xdef _p4ad_isr
- xdef _p3ad_isr
- xdef _p2ad_isr
- xdef _p1ad_isr
- xdef _p0ad_isr
- xdef _pwmtimer_isr
- xdef _uart1rx_isr
- xdef _uart1tx_isr
- xdef _pwmfault_isr
- xdef _c3_isr
- xdef _c2_isr
- xdef _c1_isr
- xdef _c0_isr
- xdef _common_isr
-
- xref _low_nearbss:RAM
- xref _len_nearbss
- xref _low_farbss:ERAM
- xref _len_farbss:ERAM
- xref _low_neardata:RAM
- xref _len_neardata
- xref _low_near_romdata:EROM
- xref _low_fardata:ERAM
- xref _len_fardata:ERAM
- xref _low_far_romdata:EROM
- xref far_heapbot:ERAM
- xref _far_stack:ERAM
- xref _near_stack:RAM
-
-/**************************************************************************
- * Flash Option Byte Setup
- **************************************************************************/
-
- define FOPTIONSEG, SPACE=ROM, ORG=0
- segment FOPTIONSEG
- db %FF
- db %FF
- db %FF
- db %FF
-
-/**************************************************************************
- * vectors
- **************************************************************************/
-
- vector RESET=_reset
- vector SYSEXC=_sysexc_isr
- vector TIMER2=_timer2_isr
- vector TIMER1=_timer1_isr
- vector TIMER0=_timer0_isr
- vector UART0_RX=_uart0rx_isr
- vector UART0_TX=_uart0tx_isr
- vector I2C=_i2c_isr
- vector SPI=_spi_isr
- vector ADC=_adc_isr
- vector P7AD=_p7ad_isr
- vector P6AD=_p6ad_isr
- vector P5AD=_p5ad_isr
- vector P4AD=_p4ad_isr
- vector P3AD=_p3ad_isr
- vector P2AD=_p2ad_isr
- vector P1AD=_p1ad_isr
- vector P0AD=_p0ad_isr
- vector PWM_TIMER=_pwmtimer_isr
- vector UART1_RX=_uart1rx_isr
- vector UART1_TX=_uart1tx_isr
- vector PWM_FAULT=_pwmfault_isr
- vector C3=_c3_isr
- vector C2=_c3_isr
- vector C1=_c2_isr
- vector C0=_c0_isr
-
-/**************************************************************************
- * Equates
- **************************************************************************/
-
-/**************************************************************************
- * Data Allocation
- **************************************************************************/
-
-/**************************************************************************
- * Code
- **************************************************************************/
-
- define CODESEG, SPACE=EROM
- segment CODESEG
-
-/**************************************************************************
- * Name: _reset
- *
- * Description:
- * Reset entry point
- *
- **************************************************************************/
-
-_reset:
- /* Initialize the init/idle task stack */
-
- ld sp, #(_near_stack+1) /* Set Stack Pointer to the top of internal RAM */
- clr fp
-
- /* Perform VERY early UART initialization so that we can use it here */
-
-#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC)
- call _z16f_lowuartinit /* Initialize the UART for debugging */
-#endif
- /* Initialize the hardware stack overflow register */
-
-#ifdef CONFIG_Z16F_INITSPOV
- ld r0, #(_near_stack_bot+1)
- ld spov, r0
-#endif
- /* Clear BSS */
-
- lea r0, _low_nearbss
- ld r1, #_len_nearbss+1
- jp _reset2
-_reset1:
- ld.b (r0++), #0
-_reset2:
- djnz r1, _reset1
-
- lea r0, _low_farbss
- ld r1, #_len_farbss+1
- jp _reset4
-_reset3:
- ld.b (r0++), #0
-_reset4:
- djnz r1, _reset3
-
- /* Copy ROM data into RAM */
-
- lea r0, _low_near_romdata
- lea r1, _low_neardata
- ld r2, #_len_neardata+1
- jp _reset6
-_reset5:
- ld.b r3, (r0++)
- ld.b (r1++), r3
-_reset6:
- djnz r2, _reset5
-
- lea r0, _low_far_romdata
- lea r1, _low_fardata
- ld r2, #_len_fardata+1
- jp _reset8
-_reset7:
- ld.b r3, (r0++)
- ld.b (r1++), r3
-_reset8:
- djnz r2, _reset7
-
- /* Perform low-level hardware initialization */
-
- call _z16f_lowinit /* Perform low-level hardware initialization */
-
- /* Start NuttX */
-
- call _os_start /* Start the operating system */
-_halted: /* _os_start() should not return */
- halt
- jp _halted
-
-/**************************************************************************
- * Name: Interrupt handlers
- *
- * Description:
- * All interrupts will be vectored to the following locations.
- *
- **************************************************************************/
-
-_sysexc_isr:
-_timer2_isr:
-_timer1_isr:
-_timer0_isr:
-_uart0rx_isr:
-_uart0tx_isr:
-_i2c_isr:
-_spi_isr:
-_adc_isr:
-_p7ad_isr:
-_p6ad_isr:
-_p5ad_isr:
-_p4ad_isr:
-_p3ad_isr:
-_p2ad_isr:
-_p1ad_isr:
-_p0ad_isr:
-_pwmtimer_isr:
-_uart1rx_isr:
-_uart1tx_isr:
-_pwmfault_isr:
-_c3_isr:
-_c2_isr:
-_c1_isr:
-_c0_isr:
-_common_isr:
- nop
- iret
-
- end
+/**************************************************************************
+ * arch/z16/src/z16f/z16f_head.S
+ * Z16F Reset Entry Point
+ *
+ * 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 <arch/irq.h>
+
+/**************************************************************************
+ * External References / External Definitions
+ **************************************************************************/
+
+ xref _z16f_lowinit:EROM
+#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC)
+ xref _z16f_lowuartinit:EROM
+#endif
+ xref _os_start:EROM
+ xref _up_doirq:EROM
+ xdef _reset
+ xdef _sysexc_isr
+ xdef _timer2_isr
+ xdef _timer1_isr
+ xdef _timer0_isr
+ xdef _uart0rx_isr
+ xdef _uart0tx_isr
+ xdef _i2c_isr
+ xdef _spi_isr
+ xdef _adc_isr
+ xdef _p7ad_isr
+ xdef _p6ad_isr
+ xdef _p5ad_isr
+ xdef _p4ad_isr
+ xdef _p3ad_isr
+ xdef _p2ad_isr
+ xdef _p1ad_isr
+ xdef _p0ad_isr
+ xdef _pwmtimer_isr
+ xdef _uart1rx_isr
+ xdef _uart1tx_isr
+ xdef _pwmfault_isr
+ xdef _c3_isr
+ xdef _c2_isr
+ xdef _c1_isr
+ xdef _c0_isr
+ xdef _common_isr
+
+ xref _low_nearbss:RAM
+ xref _len_nearbss
+ xref _low_farbss:ERAM
+ xref _len_farbss:ERAM
+ xref _low_neardata:RAM
+ xref _len_neardata
+ xref _low_near_romdata:EROM
+ xref _low_fardata:ERAM
+ xref _len_fardata:ERAM
+ xref _low_far_romdata:EROM
+ xref far_heapbot:ERAM
+ xref _far_stack:ERAM
+ xref _near_stack:RAM
+
+/**************************************************************************
+ * Flash Option Byte Setup
+ **************************************************************************/
+
+ define FOPTIONSEG, SPACE=ROM, ORG=0
+ segment FOPTIONSEG
+ db %FF
+ db %FF
+ db %FF
+ db %FF
+
+/**************************************************************************
+ * vectors
+ **************************************************************************/
+
+ vector RESET=_reset
+ vector SYSEXC=_sysexc_isr
+ vector TIMER2=_timer2_isr
+ vector TIMER1=_timer1_isr
+ vector TIMER0=_timer0_isr
+ vector UART0_RX=_uart0rx_isr
+ vector UART0_TX=_uart0tx_isr
+ vector I2C=_i2c_isr
+ vector SPI=_spi_isr
+ vector ADC=_adc_isr
+ vector P7AD=_p7ad_isr
+ vector P6AD=_p6ad_isr
+ vector P5AD=_p5ad_isr
+ vector P4AD=_p4ad_isr
+ vector P3AD=_p3ad_isr
+ vector P2AD=_p2ad_isr
+ vector P1AD=_p1ad_isr
+ vector P0AD=_p0ad_isr
+ vector PWM_TIMER=_pwmtimer_isr
+ vector UART1_RX=_uart1rx_isr
+ vector UART1_TX=_uart1tx_isr
+ vector PWM_FAULT=_pwmfault_isr
+ vector C3=_c3_isr
+ vector C2=_c3_isr
+ vector C1=_c2_isr
+ vector C0=_c0_isr
+
+/**************************************************************************
+ * Equates
+ **************************************************************************/
+
+/**************************************************************************
+ * Data Allocation
+ **************************************************************************/
+
+/**************************************************************************
+ * Code
+ **************************************************************************/
+
+ define CODESEG, SPACE=EROM
+ segment CODESEG
+
+/**************************************************************************
+ * Name: _reset
+ *
+ * Description:
+ * Reset entry point
+ *
+ **************************************************************************/
+
+_reset:
+ /* Initialize the init/idle task stack */
+
+ ld sp, #(_near_stack+1) /* Set Stack Pointer to the top of internal RAM */
+ clr fp
+
+ /* Perform VERY early UART initialization so that we can use it here */
+
+#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC)
+ call _z16f_lowuartinit /* Initialize the UART for debugging */
+#endif
+ /* Initialize the hardware stack overflow register */
+
+#ifdef CONFIG_Z16F_INITSPOV
+ ld r0, #(_near_stack_bot+1)
+ ld spov, r0
+#endif
+ /* Clear BSS */
+
+ lea r0, _low_nearbss
+ ld r1, #_len_nearbss+1
+ jp _reset2
+_reset1:
+ ld.b (r0++), #0
+_reset2:
+ djnz r1, _reset1
+
+ lea r0, _low_farbss
+ ld r1, #_len_farbss+1
+ jp _reset4
+_reset3:
+ ld.b (r0++), #0
+_reset4:
+ djnz r1, _reset3
+
+ /* Copy ROM data into RAM */
+
+ lea r0, _low_near_romdata
+ lea r1, _low_neardata
+ ld r2, #_len_neardata+1
+ jp _reset6
+_reset5:
+ ld.b r3, (r0++)
+ ld.b (r1++), r3
+_reset6:
+ djnz r2, _reset5
+
+ lea r0, _low_far_romdata
+ lea r1, _low_fardata
+ ld r2, #_len_fardata+1
+ jp _reset8
+_reset7:
+ ld.b r3, (r0++)
+ ld.b (r1++), r3
+_reset8:
+ djnz r2, _reset7
+
+ /* Perform low-level hardware initialization */
+
+ call _z16f_lowinit /* Perform low-level hardware initialization */
+
+ /* Start NuttX */
+
+ call _os_start /* Start the operating system */
+_halted: /* _os_start() should not return */
+ halt
+ jp _halted
+
+/**************************************************************************
+ * Name: Interrupt handlers
+ *
+ * Description:
+ * All interrupts will be vectored to the following locations.
+ * On entry, the stack contains the following:
+ *
+ * TOS[0] = PC[31:24]
+ * TOS[1] = PC[23:16]
+ * TOS[2] = PC[15:8]
+ * TOS[3] = PC[7:0]
+ * TOS[4] = 0
+ * TOS[5] = flags
+ *
+ **************************************************************************/
+
+_sysexc_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_SYSEXC /* r1 = SYSEXEC IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_timer2_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_TIMER0 /* r1 = Timer 2 IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_timer1_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_TIMER0 /* r1 = Timer 1 IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_timer0_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_TIMER0 /* r1 = Timer 0 IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_uart0rx_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_UART0RX /* r1 = UART0 RX IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_uart0tx_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_UART0TX /* r1 = UART0 TX IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_i2c_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_I2C /* r1 = I2C IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_spi_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_SPI /* r1 = SPI IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_adc_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_ADC /* r1 = ADC IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_p7ad_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_P7AD /* r1 = Port A/D7, rising/falling edge IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_p6ad_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_P6AD /* r1 = Port A/D6, rising/falling edge IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_p5ad_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_P5AD /* r1 = Port A/D5, rising/falling edge IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_p4ad_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_P4AD /* r1 = Port A/D4, rising/falling edge IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_p3ad_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_P3AD /* r1 = Port A/D3, rising/falling edgeEXEC IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_p2ad_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_P2AD /* r1 = Port A/D2, rising/falling edge IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_p1ad_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_P1AD /* r1 = Port A/D1, rising/falling edge IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_p0ad_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_P0AD /* r1 = Port A/D0, rising/falling edge IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_pwmtimer_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_PWMTIMER /* r1 = PWM Timer IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_uart1rx_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_UART1RX /* r1 = UART1 RX IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_uart1tx_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_UART1TX /* r1 = UART1 TX IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_pwmfault_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_PWMFAULT /* r1 = PWM Fault IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_c3_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_C3 /* r1 = Port C3, both edges DMA3 IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_c2_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_C2 /* r1 = Port C2, both edges DMA2 IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_c1_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_C1 /* r1 = Port C1, both edges DMA1 IRQ number */
+ jp _common_isr /* Join common interrupt handling logic */
+
+_c0_isr:
+ pushmlo <r0-r7> /* Save r0-r7 on the stack */
+ ld r1, #Z16F_IRQ_C0 /* r1 = Port C0, both edges DMA0 IRQ number */
+ /* Join common interrupt handling logic */
+
+
+/**************************************************************************
+ * Name: _common_isr
+ *
+ * Description:
+ * Common interrupt handling logic.
+ *
+ * On entry:
+ *
+ * r0 = IRQ number
+ *
+ * And the stack contains the following:
+ *
+ * TOS[ 0- 3] = r0
+ * TOS[ 4- 7] = r1
+ * TOS[ 8-11] = r2
+ * TOS[12-15] = r3
+ * TOS[16-19] = r4
+ * TOS[20-23] = r5
+ * TOS[24-27] = r6
+ * TOS[28-31] = r7
+ * TOS[32-33] = return PC
+ * TOS[34-35] = flags (with padding)
+ *
+ **************************************************************************/
+
+_common_isr:
+ /* Calculate the value of the SP BEFORE the interrupt occurred and
+ * push that as the saved value of r15=sp
+ */
+
+ ld r1, #-36 /* See stack accounting above */
+ add r1, sp /* r1 = Value of the SP before the interrupt */
+ push r1 /* Push r1 in the spot for the saved SP */
+
+ /* Save all of the remaining registers */
+
+ pushmhi <r8-r14>
+
+ /* SP now holds the address of the beginning of the save structure
+ * on the stack. Now handle the interrupt with arg1(r1)=IRQ number and
+ * arg2(r2)=address of the register save structure.
+ */
+
+ ld r2, sp
+ call _up_doirq
+
+ /* Upon return, _up_doirq will provide that address of the save structure
+ * to use to return from the interrupt in r0. This may or may not be the
+ * same value as sp.
+ */
+
+ ld sp, 2*REG_SP(r0) /* sp=Value of SP on return from interrupt */
+ ld.w r1, 2*REG_FLAGS(r0) /* r1=padded flags value */
+ push.w r1 /* Push padded flags value onto the stack */
+ ld r1, 2*REG_PC(r0) /* r1=return address */
+ push r1 /* Push the return address onto the stack */
+
+ ld sp, r0 /* sp=Value of SP at call to _up_doirq */
+ popmhi <r8-r14> /* Restore r8-r14 */
+ popmlo <r0-r7> /* Restore r0-r7 */
+ iret /* Return from interrupt */
+
+ end
diff --git a/nuttx/arch/z16/src/z16f/z16f_lowuart.S b/nuttx/arch/z16/src/z16f/z16f_lowuart.S
index e25b3b439..80409d45c 100755
--- a/nuttx/arch/z16/src/z16f/z16f_lowuart.S
+++ b/nuttx/arch/z16/src/z16f/z16f_lowuart.S
@@ -1,234 +1,234 @@
-/*************************************************************************
- * arch/z16/src/z16f/z16f_lowuart.asm
- * Z16F UART management
- *
- * 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 "chip/chip.h"
-
-#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC)
-
-/*************************************************************************
- * External References / External Definitions
- *************************************************************************/
-
- xdef z16f_lowuartinit
- xref _SYS_CLK_FREQ:EROM
-#ifdef CONFIG_ARCH_LOWPUTC
- xdef _z16f_xmitc
- xdef _up_lowputc
-#endif
-#ifdef CONFIG_ARCH_LOWGETC
- xdef _up_lowgetc
-#endif
-
-/*************************************************************************
- * Data Allocation
- *************************************************************************/
-
- define CODESEG, SPACE=EROM
- segment CODESEG
-
-/*************************************************************************
- * Code
- *************************************************************************/
-
-/*************************************************************************
- * Name: z16f_lowuartinit
- *
- * Description:
- * Initialize UART0 or UART1
- *
- * Parameters:
- * None
- *
- *************************************************************************/
-
-z16f_lowuartinit:
- pushmlo <r0, r3> /* Save registers */
-
- /* Calculate and set the baud rate generation register */
-
-
-#ifdef CONFIG_UART0_SERIAL_CONSOLE
- ld r3, #CONFIG_UART0_BAUD /* r3 = baud */
-#else
- ld r3, #CONFIG_UART1_BAUD /* r3 = baud */
-#endif
- ld r0, r3 /* r0 = baud */
- sll r0, #3 /* r0 = baud * 8 */
- add r0, #_SYS_CLK_FREQ /* r3 = freq + baud * 8*/
- sll r3, #4 /* r3 = baud * 16 */
- udiv r0, r3 /* BRG = (freq + baud * 8)/(baud * 16) */
-
-#ifdef CONFIG_UART0_SERIAL_CONSOLE
- ld.w Z16F_UART0_BR, r0 /* Z16F_UART0_BR = BRG */
-
- /* Set the GPIO Alternate Function Register Lo (AFL) register */
-
- ld r0, #%30
- or.b Z16F_GPIOA_AFL, r0 /* Z16F_GPIOA_AFL |= %30 */
-
- /* Enable UART receive (REN) and transmit (TEN) */
-
- clr.b Z16F_UART0_CTL1 /* Z16F_UART0_CTL1 = 0 */
- ld r0, #(Z16F_UARTCTL0_TEN|Z16F_UARTCTL0_REN)
- ld.b Z16F_UART0_CTL0, r0 /* Z16F_UART0_CTL0 = %c0 */
-#else
- ld.w Z16F_UART1_BR, r0 /* Z16F_UART1_BR = BRG */
-
- /* Set the GPIO Alternate Function Register Lo (AFL) register */
-
- ld r0, #%30
- or.b Z16F_GPIOD_AFL, r0 /* Z16F_GPIOD_AFL |= %30 */
-
- /* Enable UART receive (REN) and transmit (TEN) */
-
- clr.b Z16F_UART1_CTL1 /* Z16F_UART1_CTL1 = 0 */
- ld r0, #(Z16F_UARTCTL0_TEN|Z16F_UARTCTL0_REN)
- ld.b Z16F_UART1_CTL0, r0 /* Z16F_UART1_CTL0 = %c0 */
-#endif
- popmlo <r0, r3> /* Restore registers */
- ret /* Return */
-
-
-/*************************************************************************
- * Name: _z16f_xmitc
- *
- * Description:
- * Send one character on the selected port
- *
- * Parmeters:
- * r1 = character
- *
- *************************************************************************/
-
-#ifdef CONFIG_ARCH_LOWPUTC
-_z16f_xmitc:
- pushmlo <r0> /* Save registers */
-
-_z16f_xmitc1:
- ld r0, Z16F_UARTSTAT0_TDRE /* TDRE=Transmitter Data Register Empty */
-#ifdef CONFIG_UART0_SERIAL_CONSOLE
- tm.b Z16F_UART0_STAT0, r0 /* r0 = Z16F_UART0_STAT0 */
- jp eq, _z16f_xmitc1 /* While (!(Z16F_UART0_STAT0 & TDRE)) */
- ld.b Z16F_UART0_TXD, r1 /* Z16F_UART0_TXD = r1 (character) */
-#else
- tm.b Z16F_UART1_STAT0, r0 /* r0 = Z16F_UART0_STAT1 */
- jp eq, _z16f_xmitc1 /* While (!(Z16F_UART1_STAT0 & TDRE)) */
- ld.b Z16F_UART1_TXD, r1 /* Z16F_UART1_TXD = r1 (character) */
-#endif
- popmlo <r0> /* Restore registers */
- ret /* Return */
-#endif
-
-/*************************************************************************
- * Name: _up_lowputc
- *
- * Description:
- * Send one character to the selected serial console
- *
- * Parmeters:
- * r1 = character
- *
- * Return
- * R0 = 0
- *
- *************************************************************************/
-
-#ifdef CONFIG_ARCH_LOWPUTC
-_up_lowputc:
- pushmlo <r1,r5> /* Save registers */
- ld r0, r1
- ext.ub r5, r0
- cp r5, #10
- jp ne, _up_lowputc1 /* If (character == \n) */
-
- ld r1,#13
- call _z16f_xmitc /* Call _z16f_xmitc with \r */
-
-_up_lowputc1:
- ld r1, r0
- call _z16f_xmitc /* Xall _z16f_xmitc with character */
-
- ld r0, #0 /* return r0 = 0 */
- popmlo <r1,r5> /* Restore registers */
- ret /* Return */
-#endif
-
-/*************************************************************************
- * Name: _up_lowgetc
- *
- * Description:
- * Get a character from the serial port
- *
- * Parmeters:
- * None
- *
- * Return
- * R0 = Character read
- *
- *************************************************************************/
-
-#ifdef CONFIG_ARCH_LOWGETC
-_up_lowgetc:
-up_lowgetc1:
- ld r0, #Z16F_UARTSTAT0_RDA /* RDA=Receive data available */
-#ifdef CONFIG_UART0_SERIAL_CONSOLE
- tm.b Z16F_UART0_STAT0, r0
- jp eq, _up_lowgetc1 /* While (!Z16F_UART0_STAT0 & RDA)) */
- ld.ub r0, Z16F_UART0_RXD /* r0 = Z16F_UART0_RXD */
-#else
- tm.b Z16F_UART1_STAT0,r0 /* While (!Z16F_UART1_STAT0 & RDA) */
- jp eq, _up_lowgetc1
- ld.ub r0, Z16F_UART1_RXD /* r0 = Z16F_UART1_RXD */
-#endif
- cp r0, #%0d /* Test for '\r' */
- jp eq, _up_lowgetc2
-
- cp r0, #%0d /* Test \r + high bit */
- jp ne, _up_lowgetc3
-_up_lowgetc2:
- ld r0, #%0a /* Convert '\r' to '\n' */
-_up_lowgetc3: /* Return value in r0 */
- ret /* Return */
-#endif
-
-#endif /* CONFIG_ARCH_LOWPUTC || CONFIG_ARCH_LOWGETC */
-
- end
+/*************************************************************************
+ * arch/z16/src/z16f/z16f_lowuart.asm
+ * Z16F UART management
+ *
+ * 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 "chip/chip.h"
+
+#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC)
+
+/*************************************************************************
+ * External References / External Definitions
+ *************************************************************************/
+
+ xdef _z16f_lowuartinit
+ xref _SYS_CLK_FREQ:EROM
+#ifdef CONFIG_ARCH_LOWPUTC
+ xdef _z16f_xmitc
+ xdef _up_lowputc
+#endif
+#ifdef CONFIG_ARCH_LOWGETC
+ xdef _up_lowgetc
+#endif
+
+/*************************************************************************
+ * Data Allocation
+ *************************************************************************/
+
+ define CODESEG, SPACE=EROM
+ segment CODESEG
+
+/*************************************************************************
+ * Code
+ *************************************************************************/
+
+/*************************************************************************
+ * Name: z16f_lowuartinit
+ *
+ * Description:
+ * Initialize UART0 or UART1
+ *
+ * Parameters:
+ * None
+ *
+ *************************************************************************/
+
+_z16f_lowuartinit:
+ pushmlo <r0, r3> /* Save registers */
+
+ /* Calculate and set the baud rate generation register */
+
+
+#ifdef CONFIG_UART0_SERIAL_CONSOLE
+ ld r3, #CONFIG_UART0_BAUD /* r3 = baud */
+#else
+ ld r3, #CONFIG_UART1_BAUD /* r3 = baud */
+#endif
+ ld r0, r3 /* r0 = baud */
+ sll r0, #3 /* r0 = baud * 8 */
+ add r0, #_SYS_CLK_FREQ /* r3 = freq + baud * 8*/
+ sll r3, #4 /* r3 = baud * 16 */
+ udiv r0, r3 /* BRG = (freq + baud * 8)/(baud * 16) */
+
+#ifdef CONFIG_UART0_SERIAL_CONSOLE
+ ld.w Z16F_UART0_BR, r0 /* Z16F_UART0_BR = BRG */
+
+ /* Set the GPIO Alternate Function Register Lo (AFL) register */
+
+ ld r0, #%30
+ or.b Z16F_GPIOA_AFL, r0 /* Z16F_GPIOA_AFL |= %30 */
+
+ /* Enable UART receive (REN) and transmit (TEN) */
+
+ clr.b Z16F_UART0_CTL1 /* Z16F_UART0_CTL1 = 0 */
+ ld r0, #(Z16F_UARTCTL0_TEN|Z16F_UARTCTL0_REN)
+ ld.b Z16F_UART0_CTL0, r0 /* Z16F_UART0_CTL0 = %c0 */
+#else
+ ld.w Z16F_UART1_BR, r0 /* Z16F_UART1_BR = BRG */
+
+ /* Set the GPIO Alternate Function Register Lo (AFL) register */
+
+ ld r0, #%30
+ or.b Z16F_GPIOD_AFL, r0 /* Z16F_GPIOD_AFL |= %30 */
+
+ /* Enable UART receive (REN) and transmit (TEN) */
+
+ clr.b Z16F_UART1_CTL1 /* Z16F_UART1_CTL1 = 0 */
+ ld r0, #(Z16F_UARTCTL0_TEN|Z16F_UARTCTL0_REN)
+ ld.b Z16F_UART1_CTL0, r0 /* Z16F_UART1_CTL0 = %c0 */
+#endif
+ popmlo <r0, r3> /* Restore registers */
+ ret /* Return */
+
+
+/*************************************************************************
+ * Name: _z16f_xmitc
+ *
+ * Description:
+ * Send one character on the selected port
+ *
+ * Parmeters:
+ * r1 = character
+ *
+ *************************************************************************/
+
+#ifdef CONFIG_ARCH_LOWPUTC
+_z16f_xmitc:
+ pushmlo <r0> /* Save registers */
+
+_z16f_xmitc1:
+ ld r0, Z16F_UARTSTAT0_TDRE /* TDRE=Transmitter Data Register Empty */
+#ifdef CONFIG_UART0_SERIAL_CONSOLE
+ tm.b Z16F_UART0_STAT0, r0 /* r0 = Z16F_UART0_STAT0 */
+ jp eq, _z16f_xmitc1 /* While (!(Z16F_UART0_STAT0 & TDRE)) */
+ ld.b Z16F_UART0_TXD, r1 /* Z16F_UART0_TXD = r1 (character) */
+#else
+ tm.b Z16F_UART1_STAT0, r0 /* r0 = Z16F_UART0_STAT1 */
+ jp eq, _z16f_xmitc1 /* While (!(Z16F_UART1_STAT0 & TDRE)) */
+ ld.b Z16F_UART1_TXD, r1 /* Z16F_UART1_TXD = r1 (character) */
+#endif
+ popmlo <r0> /* Restore registers */
+ ret /* Return */
+#endif
+
+/*************************************************************************
+ * Name: _up_lowputc
+ *
+ * Description:
+ * Send one character to the selected serial console
+ *
+ * Parmeters:
+ * r1 = character
+ *
+ * Return
+ * R0 = 0
+ *
+ *************************************************************************/
+
+#ifdef CONFIG_ARCH_LOWPUTC
+_up_lowputc:
+ pushmlo <r1,r5> /* Save registers */
+ ld r0, r1
+ ext.ub r5, r0
+ cp r5, #10
+ jp ne, _up_lowputc1 /* If (character == \n) */
+
+ ld r1,#13
+ call _z16f_xmitc /* Call _z16f_xmitc with \r */
+
+_up_lowputc1:
+ ld r1, r0
+ call _z16f_xmitc /* Xall _z16f_xmitc with character */
+
+ ld r0, #0 /* return r0 = 0 */
+ popmlo <r1,r5> /* Restore registers */
+ ret /* Return */
+#endif
+
+/*************************************************************************
+ * Name: _up_lowgetc
+ *
+ * Description:
+ * Get a character from the serial port
+ *
+ * Parmeters:
+ * None
+ *
+ * Return
+ * R0 = Character read
+ *
+ *************************************************************************/
+
+#ifdef CONFIG_ARCH_LOWGETC
+_up_lowgetc:
+up_lowgetc1:
+ ld r0, #Z16F_UARTSTAT0_RDA /* RDA=Receive data available */
+#ifdef CONFIG_UART0_SERIAL_CONSOLE
+ tm.b Z16F_UART0_STAT0, r0
+ jp eq, _up_lowgetc1 /* While (!Z16F_UART0_STAT0 & RDA)) */
+ ld.ub r0, Z16F_UART0_RXD /* r0 = Z16F_UART0_RXD */
+#else
+ tm.b Z16F_UART1_STAT0,r0 /* While (!Z16F_UART1_STAT0 & RDA) */
+ jp eq, _up_lowgetc1
+ ld.ub r0, Z16F_UART1_RXD /* r0 = Z16F_UART1_RXD */
+#endif
+ cp r0, #%0d /* Test for '\r' */
+ jp eq, _up_lowgetc2
+
+ cp r0, #%0d /* Test \r + high bit */
+ jp ne, _up_lowgetc3
+_up_lowgetc2:
+ ld r0, #%0a /* Convert '\r' to '\n' */
+_up_lowgetc3: /* Return value in r0 */
+ ret /* Return */
+#endif
+
+#endif /* CONFIG_ARCH_LOWPUTC || CONFIG_ARCH_LOWGETC */
+
+ end
diff --git a/nuttx/arch/z16/src/z16f/z16f_restoreusercontext.S b/nuttx/arch/z16/src/z16f/z16f_restoreusercontext.S
new file mode 100755
index 000000000..447ba1124
--- /dev/null
+++ b/nuttx/arch/z16/src/z16f/z16f_restoreusercontext.S
@@ -0,0 +1,105 @@
+/*************************************************************************
+ * arch/z16/src/z16f/z16f_restoreusercontext.asm
+ *
+ * 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 <arch/irq.h>
+#include "chip/chip.h"
+
+/*************************************************************************
+ * External References / External Definitions
+ *************************************************************************/
+
+ xdef _up_restoreusercontext
+
+/*************************************************************************
+ * Data Allocation
+ *************************************************************************/
+
+ define CODESEG, SPACE=EROM
+ segment CODESEG
+
+/*************************************************************************
+ * Code
+ *************************************************************************/
+
+/*************************************************************************
+ * Name: up_restoreusercontext
+ *
+ * Description:
+ * Restore the current user context.
+ *
+ * Parameters:
+ * r1: pointer to the register save array in the XCPT structure
+ *
+ *************************************************************************/
+
+_up_restoreusercontext:
+ /* Disable interrupts throughout the following */
+
+ di
+
+ /* Set up the stack for return */
+
+ ld sp, 2*REG_SP(r1) /* sp=Value of SP on return */
+ ld r2, 2*REG_PC(r1) /* r2=return address */
+ push r1 /* Push the return address onto the stack */
+
+ /* Retore r8-r18 */
+
+ ld sp, r1 /* sp=Value of SP at call to _up_doirq */
+ popmhi <r8-r14> /* Restore r8-r14 */
+
+ /* Test if interrupts should be enabled upon return */
+
+ ld.w r2, 2*REG_FLAGS(r1) /* r2=padded flags value */
+ tm r2, #(Z16F_CNTRL_FLAGS_IRQE << 8) /* Test (shifted) IRQE bit */
+ jp z, _up_returndisabled /* Jump if interrupts should remain disabled */
+
+ /* Return with interrupts enabled */
+
+ popmlo <r0-r7> /* Restore r0-r7 */
+ ei /* Enable interrupts and return */
+ ret
+
+ /* Return with interrupts disabled */
+
+_up_returndisabled:
+ popmlo <r0-r7> /* Restore r0-r7 */
+ ret
+ end
diff --git a/nuttx/arch/z16/src/z16f/z16f_saveusercontext.S b/nuttx/arch/z16/src/z16f/z16f_saveusercontext.S
index 339ced811..8ae7b1775 100644
--- a/nuttx/arch/z16/src/z16f/z16f_saveusercontext.S
+++ b/nuttx/arch/z16/src/z16f/z16f_saveusercontext.S
@@ -1,104 +1,118 @@
-/*************************************************************************
- * arch/z16/src/z16f/z16f_saveusercontext.asm
- *
- * 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 <arch/irq.h>
-#include "chip/chip.h"
-
-/*************************************************************************
- * External References / External Definitions
- *************************************************************************/
-
- xdef up_saveusercontext
-
-/*************************************************************************
- * Data Allocation
- *************************************************************************/
-
- define CODESEG, SPACE=EROM
- segment CODESEG
-
-/*************************************************************************
- * Code
- *************************************************************************/
-
-/*************************************************************************
- * Name: up_saveusercontext
- *
- * Description:
- * Save the current user context.
- * r0-r7: These are caller saved registers and do not need to be stored
- * here
- * r8-r13: There callee saved registers must be preserved
- * r14: Frame pointer
- * r15: Stack pointer (with return address on stack)
- *
- * Parameters:
- * r1: pointer to the register save array in the XCPT structure
- *
- *************************************************************************/
-
-up_saveusercontext:
- /* Save the flags (needed to restore the interrupt state) */
-
- ld r3, Z16F_CNTRL_FLAGS /* Fetch the flags register */
- sll r3, #8 /* Pad with zero */
- ld 2*REG_FLAGS(r1), r3
-
- /* Save r8-R13 */
-
- ld 2*REG_R8(r1), r8 /* Save r8 */
- ld 2*REG_R8(r1), r9 /* Save r9 */
- ld 2*REG_R8(r1), r10 /* Save r10 */
- ld 2*REG_R8(r1), r11 /* Save r11 */
- ld 2*REG_R8(r1), r12 /* Save r12 */
- ld 2*REG_R8(r1), r13 /* Save r13 */
-
- /* Save the stack pointer and the frame pointer */
-
- ld 2*REG_FP(r1), fp /* Save the frame pointer */
- ld 2*REG_SP(r1), sp /* Save the stack pointer */
-
- /* Save the return address at the top of the stack */
-
- ld r0, (sp) /* Save the return address */
- ld 2*REG_PC(r1), r0
- clr r0 /* Always returns 0 */
- ret
- end
+/*************************************************************************
+ * arch/z16/src/z16f/z16f_saveusercontext.asm
+ *
+ * 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 <arch/irq.h>
+#include "chip/chip.h"
+
+/*************************************************************************
+ * External References / External Definitions
+ *************************************************************************/
+
+ xdef _up_saveusercontext
+
+/*************************************************************************
+ * Data Allocation
+ *************************************************************************/
+
+ define CODESEG, SPACE=EROM
+ segment CODESEG
+
+/*************************************************************************
+ * Code
+ *************************************************************************/
+
+/*************************************************************************
+ * Name: up_saveusercontext
+ *
+ * Description:
+ * Save the current user context.
+ * r0-r7: These are caller saved registers and do not need to be stored
+ * here
+ * r8-r13: There callee saved registers must be preserved
+ * r14: Frame pointer
+ * r15: Stack pointer (with return address on stack)
+ *
+ * Parameters:
+ * r1: pointer to the register save array in the XCPT structure
+ *
+ *************************************************************************/
+
+_up_saveusercontext:
+ /* Save the flags (needed to restore the interrupt state) */
+
+ ld r3, Z16F_CNTRL_FLAGS /* Fetch the flags register */
+ sll r3, #8 /* Pad with zero */
+ ld.w 2*REG_FLAGS(r1), r3 /* Save 16-bit value */
+
+ /* Save r8-R13 */
+
+ ld 2*REG_R8(r1), r8 /* Save r8 */
+ ld 2*REG_R9(r1), r9 /* Save r9 */
+ ld 2*REG_R10(r1), r10 /* Save r10 */
+ ld 2*REG_R11(r1), r11 /* Save r11 */
+ ld 2*REG_R12(r1), r12 /* Save r12 */
+ ld 2*REG_R13(r1), r13 /* Save r13 */
+
+ /* Save the stack pointer and the frame pointer */
+
+ ld 2*REG_FP(r1), fp /* Save the frame pointer */
+ ld 2*REG_SP(r1), sp /* Save the stack pointer */
+
+ /* Save the return address at the top of the stack */
+
+ ld r0, (sp) /* Save the return address */
+ ld 2*REG_PC(r1), r0
+
+ /* Set the return value so that if when the task is restarted
+ * (via z16f_restoreusercontext() or via interrupt handling return),
+ * the returned value will be 1
+ */
+
+ ld r0, #1
+ ld 2*REG_R0(r1), r0
+
+ /* But always return 0 when returning from this function. The
+ * apparent return value tells the higher level logic whether the
+ * user context was saved or restored (in the spirit of setjmp and longjmp)
+ */
+
+ clr r0 /* Always returns 0 */
+ ret
+ end