summaryrefslogtreecommitdiff
path: root/nuttx/arch/z16
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-25 17:49:43 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-25 17:49:43 +0000
commit347fa8f13710529e0306c2d894e3ea4f05534918 (patch)
tree67c25d0d51af7e78da47d381dc524df98a10d6fa /nuttx/arch/z16
parentc93c3e4c38b095e65cfc374f1cfee094e141f0fb (diff)
downloadpx4-nuttx-347fa8f13710529e0306c2d894e3ea4f05534918.tar.gz
px4-nuttx-347fa8f13710529e0306c2d894e3ea4f05534918.tar.bz2
px4-nuttx-347fa8f13710529e0306c2d894e3ea4f05534918.zip
Add z16f system exception handling logic.
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@564 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/z16')
-rw-r--r--nuttx/arch/z16/include/z16f/irq.h66
-rw-r--r--nuttx/arch/z16/src/common/up_allocateheap.c1
-rw-r--r--nuttx/arch/z16/src/common/up_assert.c1
-rw-r--r--nuttx/arch/z16/src/common/up_createstack.c1
-rw-r--r--nuttx/arch/z16/src/common/up_doirq.c6
-rw-r--r--nuttx/arch/z16/src/common/up_sigdeliver.c1
-rw-r--r--nuttx/arch/z16/src/z16f/Make.defs2
-rw-r--r--nuttx/arch/z16/src/z16f/chip.h35
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_head.S895
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_lowuart.S467
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_sysexec.c126
11 files changed, 887 insertions, 714 deletions
diff --git a/nuttx/arch/z16/include/z16f/irq.h b/nuttx/arch/z16/include/z16f/irq.h
index f9bcd1482..7434b1f25 100644
--- a/nuttx/arch/z16/include/z16f/irq.h
+++ b/nuttx/arch/z16/include/z16f/irq.h
@@ -49,42 +49,40 @@
* Definitions
****************************************************************************/
-/* Interrupt Vectors */
-
-#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 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 */
-#define Z16F_IRQ_UART1RX (23) /* Vector: IRQ2.6 0x54 UART1 RX */
-#define Z16F_IRQ_PWMTIMER (24) /* Vector: IRQ2.7 0x50 PWM Timer */
+/* Interrupt Vectors (excluding reset and sysexec which are handled differently) */
+
+#define Z16F_IRQ_IRQ0 ( 0) /* First of 8 IRQs controlled by IRQ0 registers */
+#define Z16F_IRQ_ADC ( 0) /* Vector: 0x2C IRQ0.0 ADC */
+#define Z16F_IRQ_SPI ( 1) /* Vector: 0x28 IRQ0.1 SPI */
+#define Z16F_IRQ_I2C ( 2) /* Vector: 0x24 IRQ0.2 I2C */
+#define Z16F_IRQ_UART0TX ( 3) /* Vector: 0x20 IRQ0.3 UART0 TX */
+#define Z16F_IRQ_UART0RX ( 4) /* Vector: 0x1C IRQ0.4 UART0 RX */
+#define Z16F_IRQ_TIMER0 ( 5) /* Vector: 0x18 IRQ0.5 Timer 0 */
+#define Z16F_IRQ_TIMER1 ( 6) /* Vector: 0x14 IRQ0.6 Timer 1 */
+#define Z16F_IRQ_TIMER2 ( 7) /* Vector: 0x10 IRQ0.7 Timer 2 */
+
+#define Z16F_IRQ_IRQ1 ( 8) /* First of 8 IRQs controlled by IRQ1 registers */
+#define Z16F_IRQ_P0AD ( 8) /* Vector: 0x4C IRQ1.0 Port A/D0, rising/falling edge */
+#define Z16F_IRQ_P1AD ( 9) /* Vector: 0x48 IRQ1.1 Port A/D1, rising/falling edge */
+#define Z16F_IRQ_P2AD (10) /* Vector: 0x44 IRQ1.2 Port A/D2, rising/falling edge */
+#define Z16F_IRQ_P3AD (11) /* Vector: 0x40 IRQ1.3 Port A/D3, rising/falling edge */
+#define Z16F_IRQ_P4AD (12) /* Vector: 0x3C IRQ1.4 Port A/D4, rising/falling edge */
+#define Z16F_IRQ_P5AD (13) /* Vector: 0x38 IRQ1.5 Port A/D5, rising/falling edge */
+#define Z16F_IRQ_P6AD (14) /* Vector: 0x34 IRQ1.6 Port A/D6, rising/falling edge */
+#define Z16F_IRQ_P7AD (15) /* Vector: 0x30 IRQ1.7 Port A/D7, rising/falling edge */
+
+#define Z16F_IRQ_IRQ2 (16) /* First of 8 IRQs controlled by IRQ2 registers */
+#define Z16F_IRQ_C0 (16) /* Vector: IRQ2.0 0x6C Port C0, both edges DMA0 */
+#define Z16F_IRQ_C1 (17) /* Vector: IRQ2.1 0x68 Port C1, both edges DMA1 */
+#define Z16F_IRQ_C2 (18) /* Vector: IRQ2.2 0x64 Port C2, both edges DMA2 */
+#define Z16F_IRQ_C3 (19) /* Vector: IRQ2.3 0x60 Port C3, both edges DMA3 */
+#define Z16F_IRQ_PWMFAULT (20) /* Vector: IRQ2.4 0x5C PWM Fault */
+#define Z16F_IRQ_UART1TX (21) /* Vector: IRQ2.5 0x58 UART1 TX */
+#define Z16F_IRQ_UART1RX (22) /* Vector: IRQ2.6 0x54 UART1 RX */
+#define Z16F_IRQ_PWMTIMER (23) /* Vector: IRQ2.7 0x50 PWM Timer */
#define Z16F_IRQ_SYSTIMER Z16F_IRQ_TIMER0
-#define NR_IRQS (25)
+#define NR_IRQS (24)
/* These macros will map an IRQ to a register bit position */
diff --git a/nuttx/arch/z16/src/common/up_allocateheap.c b/nuttx/arch/z16/src/common/up_allocateheap.c
index de4256cbf..015b6c978 100644
--- a/nuttx/arch/z16/src/common/up_allocateheap.c
+++ b/nuttx/arch/z16/src/common/up_allocateheap.c
@@ -43,6 +43,7 @@
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/mm.h>
+#include <arch/board/board.h>
#include "chip/chip.h"
#include "up_internal.h"
diff --git a/nuttx/arch/z16/src/common/up_assert.c b/nuttx/arch/z16/src/common/up_assert.c
index 3a6d39ed8..9fb6436a0 100644
--- a/nuttx/arch/z16/src/common/up_assert.c
+++ b/nuttx/arch/z16/src/common/up_assert.c
@@ -46,6 +46,7 @@
#include <nuttx/irq.h>
#include <nuttx/arch.h>
+#include <arch/board/board.h>
#include "chip/chip.h"
#include "os_internal.h"
diff --git a/nuttx/arch/z16/src/common/up_createstack.c b/nuttx/arch/z16/src/common/up_createstack.c
index 7b731bf62..68c3da28f 100644
--- a/nuttx/arch/z16/src/common/up_createstack.c
+++ b/nuttx/arch/z16/src/common/up_createstack.c
@@ -45,6 +45,7 @@
#include <nuttx/kmalloc.h>
#include <nuttx/arch.h>
+#include <arch/board/board.h>
#include "chip/chip.h"
#include "up_internal.h"
diff --git a/nuttx/arch/z16/src/common/up_doirq.c b/nuttx/arch/z16/src/common/up_doirq.c
index 93c8c9639..f5f483f41 100644
--- a/nuttx/arch/z16/src/common/up_doirq.c
+++ b/nuttx/arch/z16/src/common/up_doirq.c
@@ -40,9 +40,11 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <assert.h>
+
#include <nuttx/irq.h>
#include <nuttx/arch.h>
-#include <assert.h>
+#include <arch/board/board.h>
#include "chip/chip.h"
#include "os_internal.h"
@@ -79,7 +81,7 @@
FAR chipreg_t *up_doirq(int irq, FAR chipreg_t *regs)
{
- chipreg_t *ret = regs;
+ FAR chipreg_t *ret = regs;
up_ledon(LED_INIRQ);
#ifdef CONFIG_SUPPRESS_INTERRUPTS
diff --git a/nuttx/arch/z16/src/common/up_sigdeliver.c b/nuttx/arch/z16/src/common/up_sigdeliver.c
index 5cd96d202..8360b032a 100644
--- a/nuttx/arch/z16/src/common/up_sigdeliver.c
+++ b/nuttx/arch/z16/src/common/up_sigdeliver.c
@@ -45,6 +45,7 @@
#include <nuttx/irq.h>
#include <nuttx/arch.h>
+#include <arch/board/board.h>
#include "os_internal.h"
#include "up_internal.h"
diff --git a/nuttx/arch/z16/src/z16f/Make.defs b/nuttx/arch/z16/src/z16f/Make.defs
index c50e07039..3fb62ae73 100644
--- a/nuttx/arch/z16/src/z16f/Make.defs
+++ b/nuttx/arch/z16/src/z16f/Make.defs
@@ -44,5 +44,5 @@ CMN_CSRCS = up_allocateheap.c up_initialize.c up_schedulesigaction.c \
up_exit.c up_releasestack.c up_idle.c up_reprioritizertr.c
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
+CHIP_CSRCS = z16f_clkinit.c z16f_sysexec.c z16f_irq.c z16f_timerisr.c z16f_serial.c
diff --git a/nuttx/arch/z16/src/z16f/chip.h b/nuttx/arch/z16/src/z16f/chip.h
index 47e152e6b..bcfff9279 100644
--- a/nuttx/arch/z16/src/z16f/chip.h
+++ b/nuttx/arch/z16/src/z16f/chip.h
@@ -42,6 +42,7 @@
************************************************************************************/
#include <nuttx/config.h>
+#include <arch/irq.h>
/************************************************************************************
* Definitions
@@ -199,6 +200,28 @@
#define Z16F_IRQ2_ENH _HX32(ffffe03a) /* 8-bit: IRQ2 Enable High Bit */
#define Z16F_IRQ2_ENL _HX32(ffffe03c) /* 8-bit: IRQ2 Enable Low Bit */
+/* System exception status register bit definitions *********************************/
+
+#define Z16F_SYSEXCPH_SPOVF _HX8(80) /* Bit 7: Stack pointer overflow */
+#define Z16F_SYSEXCPH_PCOVF _HX8(40) /* Bit 6: Program counter overflow */
+#define Z16F_SYSEXCPH_DIV0 _HX8(20) /* Bit 5: Divide by zero */
+#define Z16F_SYSEXCPH_DIVOVF _HX8(10) /* Bit 4: Divide overflow */
+#define Z16F_SYSEXCPH_ILL _HX8(08) /* Bit 3: Illegal instruction */
+ /* Bits 0-2: Reserved */
+ /* Bits 3-7: Reserved */
+#define Z16F_SYSEXCPL_WDTOSC _HX8(04) /* Bit 2: WDT oscillator failure */
+#define Z16F_SYSEXCPL_PRIOSC _HX8(02) /* Bit 1: Primary oscillator failure */
+#define Z16F_SYSEXCPL_WDT _HX8(01) /* Bit 0: Watchdog timer interrupt */
+
+#define Z16F_SYSEXCP_SPOVF (Z16F_SYSEXCPH_SPOVF << 8)
+#define Z16F_SYSEXCP_PCOVF (Z16F_SYSEXCPH_PCOVF << 8)
+#define Z16F_SYSEXCP_DIV0 (Z16F_SYSEXCPH_DIV0 << 8)
+#define Z16F_SYSEXCP_DIVOVF (Z16F_SYSEXCPH_DIVOVF << 8)
+#define Z16F_SYSEXCP_ILL (Z16F_SYSEXCPH_ILL << 8)
+#define Z16F_SYSEXCP_WDTOSC Z16F_SYSEXCPL_WDTOSC
+#define Z16F_SYSEXCP_PRIOSC Z16F_SYSEXCPL_PRIOSC
+#define Z16F_SYSEXCP_WDT Z16F_SYSEXCPL_WDT
+
/* Oscillator control registers *****************************************************/
#define Z16F_OSC_CTL _HX32(ffffe0A0) /* 8-bit: Oscillator Control */
@@ -519,11 +542,19 @@ extern "C" {
* debugging support for up_lowputc (or getc) is enabled.
*/
-extern void z16f_lowinit(void);
+EXTERN void z16f_lowinit(void);
#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC)
-extern void z16f_lowuartinit(void);
+EXTERN void z16f_lowuartinit(void);
#endif
+/* This function handles Z16F system execeptions */
+
+EXTERN void z16f_sysexec(FAR chipreg_t *regs);
+
+/* Entry point to reset the processor */
+
+EXTERN void z16f_reset(void);
+
#undef EXTERN
#ifdef __cplusplus
}
diff --git a/nuttx/arch/z16/src/z16f/z16f_head.S b/nuttx/arch/z16/src/z16f/z16f_head.S
index 300ff98df..85bfc04ef 100755
--- a/nuttx/arch/z16/src/z16f/z16f_head.S
+++ b/nuttx/arch/z16/src/z16f/z16f_head.S
@@ -1,441 +1,454 @@
-/**************************************************************************
- * 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
-#ifdef CONFIG_ARCH_LEDS
- xref _up_ledinit:EROM
-#endif
-#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
-
- /* Initialize onboard LEDs */
-
-#ifdef CONFIG_ARCH_LEDS
- bl _up_ledinit
-#endif
- /* 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
+/**************************************************************************
+ * 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
+#ifdef CONFIG_ARCH_LEDS
+ xref _up_ledinit:EROM
+#endif
+#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC)
+ xref _z16f_lowuartinit:EROM
+#endif
+ xref _os_start:EROM
+ xref _up_doirq:EROM
+ xref _z16f_sysexec:EROM
+ xdef _z16f_reset
+
+ 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=_z16f_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: _z16f_reset
+ *
+ * Description:
+ * Reset entry point
+ *
+ **************************************************************************/
+
+_z16f_reset:
+ /* Initialize the init/idle task stack */
+
+ ld sp, #(_near_stack+1) /* Set Stack Pointer to the top of internal RAM */
+ clr fp
+
+ /* Initialize onboard LEDs */
+
+#ifdef CONFIG_ARCH_LEDS
+ call _up_ledinit
+#endif
+ /* 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 _z16f_reset2
+_z16f_reset1:
+ ld.b (r0++), #0
+_z16f_reset2:
+ djnz r1, _z16f_reset1
+
+ lea r0, _low_farbss
+ ld r1, #_len_farbss+1
+ jp _z16f_reset4
+_z16f_reset3:
+ ld.b (r0++), #0
+_z16f_reset4:
+ djnz r1, _z16f_reset3
+
+ /* Copy ROM data into RAM */
+
+ lea r0, _low_near_romdata
+ lea r1, _low_neardata
+ ld r2, #_len_neardata+1
+ jp _z16f_reset6
+_z16f_reset5:
+ ld.b r3, (r0++)
+ ld.b (r1++), r3
+_z16f_reset6:
+ djnz r2, _z16f_reset5
+
+ lea r0, _low_far_romdata
+ lea r1, _low_fardata
+ ld r2, #_len_fardata+1
+ jp _z16f_reset8
+_z16f_reset7:
+ ld.b r3, (r0++)
+ ld.b (r1++), r3
+_z16f_reset8:
+ djnz r2, _z16f_reset7
+
+ /* Perform low-level hardware initialization */
+
+ call _z16f_lowinit /* Perform low-level hardware initialization */
+
+ /* Start NuttX */
+
+ call _os_start /* Start the operating system */
+_halt1: /* _os_start() should not return */
+ halt
+ jp _halt1
+
+/**************************************************************************
+ * Name: _sysexec_isr
+ *
+ * Description:
+ * System exception interrupt handler. On entry, the stack looks like
+ * this:
+ *
+ * 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 */
+
+ /* Calculate the value of the SP BEFORE the interrupt occurred and
+ * push that as the saved value of r15=sp
+ */
+
+ ld r1, #-6 /* return(4) + flags(1) + padding(1) */
+ 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 system exception with arg1(r1)=address
+ * of the register save structure.
+ */
+
+ ld r1, sp
+ call _z16f_sysexec /* Handle in C logic */
+
+_halt2: /* _z16f_sysexec() should not return */
+ halt
+ jp _halt2
+
+/**************************************************************************
+ * 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
+ *
+ **************************************************************************/
+
+_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 80409d45c..037b3dd80 100755
--- a/nuttx/arch/z16/src/z16f/z16f_lowuart.S
+++ b/nuttx/arch/z16/src/z16f/z16f_lowuart.S
@@ -1,234 +1,233 @@
-/*************************************************************************
- * 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 _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_sysexec.c b/nuttx/arch/z16/src/z16f/z16f_sysexec.c
new file mode 100644
index 000000000..8ee91764c
--- /dev/null
+++ b/nuttx/arch/z16/src/z16f/z16f_sysexec.c
@@ -0,0 +1,126 @@
+/***************************************************************************
+ * z16f/z16f_sysexec.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 "os_internal.h"
+#include "up_internal.h"
+
+/***************************************************************************
+ * Definitions
+ ***************************************************************************/
+
+#ifdef CONFIG_ARCH_LOWPUTC
+# define SYSDBG lib_lowprintf
+#else
+# define SYSDBG lib_rawprintf
+#endif
+
+/***************************************************************************
+ * Private Types
+ ***************************************************************************/
+
+/***************************************************************************
+ * Private Functions
+ ***************************************************************************/
+
+/***************************************************************************
+ * Global Functions
+ ***************************************************************************/
+
+/***************************************************************************
+ * Function: z16f_sysexec
+ *
+ * Description:
+ * Handle a Z16F system execption
+ *
+ ***************************************************************************/
+
+void z16f_sysexec(FAR chipreg_t *regs)
+{
+ int errcode = OSERR_ERREXCEPTION;
+ uint16 excp;
+
+ /* The cause of the the system exception is indicated in the SYSEXCPH&L
+ * registers
+ */
+
+ excp = getreg16(Z16F_SYSEXCP);
+ if ((excp & Z16F_SYSEXCP_SPOVF) != 0)
+ {
+ SYSDBG("SP OVERFLOW\n");
+ }
+ if ((excp & Z16F_SYSEXCP_PCOVF) != 0)
+ {
+ SYSDBG("PC OVERFLOW\n");
+ }
+ if ((excp & Z16F_SYSEXCP_DIV0) != 0)
+ {
+ SYSDBG("Divide by zero\n");
+ }
+ if ((excp & Z16F_SYSEXCP_DIVOVF) != 0)
+ {
+ SYSDBG("Divide overflow\n");
+ }
+ if ((excp & Z16F_SYSEXCP_ILL) != 0)
+ {
+ SYSDBG("Illegal instruction\n");
+ errcode = OSERR_UNDEFINEDINSN;
+ }
+ if ((excp & Z16F_SYSEXCP_WDTOSC) != 0)
+ {
+ SYSDBG("WDT oscillator failure\n");
+ }
+ if ((excp & Z16F_SYSEXCP_PRIOSC) != 0)
+ {
+ SYSDBG("Primary Oscillator Failure\n");
+ }
+ if ((excp & Z16F_SYSEXCP_WDT) != 0)
+ {
+ SYSDBG("Watchdog timeout\n");
+ z16f_reset();
+ }
+ PANIC(errcode);
+}