summaryrefslogtreecommitdiff
path: root/nuttx/arch/z16/src/z16f
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-11 18:19:09 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-01-11 18:19:09 +0000
commit3b0eb489665d4d8422d34309a13b20fcf65f637a (patch)
tree865e706cf0ed1dbe84005bee16774f4f97055b4b /nuttx/arch/z16/src/z16f
parentddfaa63ee4ff54b4f875b33cc62823fe73419164 (diff)
downloadpx4-nuttx-3b0eb489665d4d8422d34309a13b20fcf65f637a.tar.gz
px4-nuttx-3b0eb489665d4d8422d34309a13b20fcf65f637a.tar.bz2
px4-nuttx-3b0eb489665d4d8422d34309a13b20fcf65f637a.zip
untest z16f code
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@553 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/z16/src/z16f')
-rw-r--r--nuttx/arch/z16/src/z16f/Make.defs10
-rw-r--r--nuttx/arch/z16/src/z16f/chip.h224
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_clkinit.c245
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_irq.c197
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_timerisr.c135
5 files changed, 782 insertions, 29 deletions
diff --git a/nuttx/arch/z16/src/z16f/Make.defs b/nuttx/arch/z16/src/z16f/Make.defs
index 3549e08d2..f360ca96d 100644
--- a/nuttx/arch/z16/src/z16f/Make.defs
+++ b/nuttx/arch/z16/src/z16f/Make.defs
@@ -36,7 +36,13 @@
HEAD_SSRC = z16f_head.S
CMN_SSRCS =
-CMN_CSRCS =
+CMN_CSRCS = up_allocateheap.c up_initialize.c up_schedulesigaction.c \
+ up_assert.c up_initialstate.c up_sigdeliver.c up_blocktask.c \
+ up_interruptcontext.c up_stackdump.c up_copystate.c \
+ up_mdelay.c up_udelay.c up_createstack.c up_registerdump.c \
+ up_unblocktask.c up_doirq.c up_releasepending.c up_usestack.c \
+ up_exit.c up_releasestack.c up_idle.c up_reprioritizertr.c
CHIP_SSRCS = z16f_lowuart.S
-CHIP_CSRCS =
+CHIP_CSRCS = z16f_clkinit.c z16f_irq.c z16f_timerisr.c
+
diff --git a/nuttx/arch/z16/src/z16f/chip.h b/nuttx/arch/z16/src/z16f/chip.h
index b91e44484..64124008e 100644
--- a/nuttx/arch/z16/src/z16f/chip.h
+++ b/nuttx/arch/z16/src/z16f/chip.h
@@ -83,7 +83,35 @@
# error "Z16F chip variant not specified"
#endif
-/* Memory areas**********************************************************************
+/* Flash option settings at address 0x00000000 ************************************/
+
+#define Z16F_FLOPTION0 rom char _flash_option0 _At 0x0
+#define Z16F_FLOPTION1 rom char _flash_option1 _At 0x1
+#define Z16F_FLOPTION2 rom char _flash_option2 _At 0x2
+#define Z16F_FLOPTION3 rom char _flash_option3 _At 0x3
+
+#define Z16F_FLOPTION0_EXTRNRC _HX8(00) /* Bits 6-7: OSC_SEL */
+#define Z16F_FLOPTION0_LOWFREQ _HX8(40)
+#define Z16F_FLOPTION0_MEDFREQ _HX8(80)
+#define Z16F_FLOPTION0_MAXPWR _HX8(c0)
+#define Z16F_FLOPTION0_WDTRES _HX8(20) /* Bit 5 */
+#define Z16F_FLOPTION0_WDTA0 _HX8(10) /* Bit 4 */
+#define Z16F_FLOPTION0_VBOA0 _HX8(08) /* Bit 3 */
+#define Z16F_FLOPTION0_DBGUART _HX8(04) /* Bit 2 */
+#define Z16F_FLOPTION0_FWP _HX8(02) /* Bit 1 */
+#define Z16F_FLOPTION0_RP _HX8(01) /* Bit 0 */
+
+#define Z16F_FLOPTION1_RESVD _HX8(f8) /* Bits 3-7: reserved */
+#define Z16F_FLOPTION1_MCEN _HX8(04) /* Bit 2: Motor control pins enable */
+#define Z16F_FLOPTION1_OFFH _HX8(02) /* High side OFF */
+#define Z16F_FLOPTION1_OFFL _HX8(01) /* Low side OFF */
+
+#define Z16F_FLOPTION2_RESVD _HX8(ff) /* Bits 0-7: reserved */
+
+#define Z16F_FLOPTION3_RESVD _HX8(bf) /* Bits 0-5,7: reserved */
+#define Z16F_FLOPTION3_NORMAL _HX8(40) /* Bit 6: 1:Normal 0:Low power mode */
+
+/* Memory areas *******************************************************************
*
* Internal non-volatile memory starts at address zero. The size
* of the internal non-volatile memory is chip-dependent.
@@ -117,6 +145,77 @@
#define Z16F_IIO_BASE _HX32(ffffe000) /* Internal I/O memory and SFRs */
#define Z16F_IIO_SIZE _HX32(00001fff)
+/* Control Registers ***************************************************************/
+
+#define Z16F_CNTRL_PCOV _HX32(ffffe004) /* 32-bits: Program counter overflow */
+#define Z16F_CNTRL_SPOV _HX32(ffffe00c) /* 32-bits: Stack pointer overflow */
+#define Z16F_CNTRL_FLAGS _HX32(ffffe100) /* 8-bits: flags */
+#define Z16F_CNTRL_CPUCTL _HX32(ffffe102) /* 8-bits: CPU control */
+
+/* Flag register bits ***************************************************************/
+
+#define Z16F_CNTRL_FLAGS_C _HX8(80) /* Bit 7: Carry flag */
+#define Z16F_CNTRL_FLAGS_Z _HX8(40) /* Bit 6: Zero flag */
+#define Z16F_CNTRL_FLAGS_S _HX8(20) /* Bit 5: Sign flag */
+#define Z16F_CNTRL_FLAGS_V _HX8(10) /* Bit 4: Overflow flag */
+#define Z16F_CNTRL_FLAGS_B _HX8(08) /* Bit 3: Blank flag */
+#define Z16F_CNTRL_FLAGS_F1 _HX8(04) /* Bit 2: User flag 1 */
+#define Z16F_CNTRL_FLAGS_CIRQE _HX8(02) /* Bit 1: Chained interrupt enable */
+#define Z16F_CNTRL_FLAGS_IRQE _HX8(01) /* Bit 0: Master interrupt enable */
+
+/* CPU control register bits ********************************************************/
+
+ /* Bits 7-2: Reserved, must be zero */
+ /* Bits 1-0: DMA bandwidth control */
+#define Z16F_CNTRL_CPUCTL_BWALL _HX8(00) /* DMA can consume 100% bandwidth */
+#define Z16F_CNTRL_CPUCTL_BW11 _HX8(01) /* DMA can do 1 transaction per 1 cycle */
+#define Z16F_CNTRL_CPUCTL_BW12 _HX8(01) /* DMA can do 1 transaction per 2 cycles */
+#define Z16F_CNTRL_CPUCTL_BW13 _HX8(01) /* DMA can do 1 transaction per 3 cycles */
+
+/* Trace registers ******************************************************************/
+
+#define Z16F_TRACE_CTL _HX32(ffffe013) /* 8-bit: Trace Control */
+#define Z16F_TRACE_ADDR _HX32(ffffe014) /* 32-bit: Trace Address */
+
+/* Interrupt controller registers ***************************************************/
+
+#define Z16F_SYSEXCP _HX32(ffffe020) /* 16-bit: System Exception Status */
+#define Z16F_SYSEXCPH _HX32(ffffe020) /* 8-bit: System Exception Status High */
+#define Z16F_SYSEXCPL _HX32(ffffe021) /* 8-bit: System Exception Status Low */
+#define Z16F_LASTIRQ _HX32(ffffe023) /* 8-bit: Last IRQ Register */
+#define Z16F_IRQ0 _HX32(ffffe030) /* 8-bit: Interrupt Request 0 */
+#define Z16F_IRQ0_SET _HX32(ffffe031) /* 8-bit: Interrupt Request 0 Set */
+#define Z16F_IRQ0_EN _HX32(ffffe032) /* 16-bit: IRQ0 Enable */
+#define Z16F_IRQ0_ENH _HX32(ffffe032) /* 8-bit: IRQ0 Enable High Bit */
+#define Z16F_IRQ0_ENL _HX32(ffffe033) /* 8-bit: IRQ0 Enable Low Bit */
+#define Z16F_IRQ1 _HX32(ffffe034) /* 8-bit: Interrupt Request 1 */
+#define Z16F_IRQ1_SET _HX32(ffffe035) /* 8-bit: Interrupt Request 1 Set */
+#define Z16F_IRQ1_EN _HX32(ffffe036) /* 16-bit: IRQ1 Enable */
+#define Z16F_IRQ1_ENH _HX32(ffffe036) /* 8-bit: IRQ1 Enable High Bit */
+#define Z16F_IRQ1_ENL _HX32(ffffe037) /* 8-bit: IRQ1 Enable Low Bit */
+#define Z16F_IRQ2 _HX32(ffffe038) /* 8-bit: Interrupt Request 2 */
+#define Z16F_IRQ2_SET _HX32(ffffe039) /* 8-bit Interrupt Request 2 Set */
+#define Z16F_IRQ2_EN _HX32(ffffe03a) /* 16-bit: IRQ2 Enable */
+#define Z16F_IRQ2_ENH _HX32(ffffe03a) /* 8-bit: IRQ2 Enable High Bit */
+#define Z16F_IRQ2_ENL _HX32(ffffe03c) /* 8-bit: IRQ2 Enable Low Bit */
+
+/* Oscillator control registers *****************************************************/
+
+#define Z16F_OSC_CTL _HX32(ffffe0A0) /* 8-bit: Oscillator Control */
+#define Z16F_OSC_DIV _HX32(ffffe0A1) /* 8-bit: Oscillator Divide */
+
+/* Oscillator control register bits *************************************************/
+
+#define Z16F_OSCCTL_INTEN _HX8(80) /* Bit 7: Internal oscillator enabled */
+#define Z16F_OSCCTL_XTLEN _HX8(40) /* Bit 6: Crystal oscillator enabled */
+#define Z16F_OSCCTL_WDTEN _HX8(20) /* Bit 5: Watchdog timer enabled */
+#define Z16F_OSCCTL_POFEN _HX8(10) /* Bit 4: Failure detection enabled */
+#define Z16F_OSCCTL_WDFEN _HX8(08) /* Bit 3: WD Failuare detection enabled*/
+#define Z16F_OSCCTL_FLPEN _HX8(04) /* Bit 2: Flash low power enabled */
+#define Z16F_OSCCTL_INT56 _HX8(00) /* Bits 0-1=0: Intenal 5.6 MHz */
+#define Z16F_OSCCTL_EXTCLK _HX8(02) /* Bits 0-1=2: Extenal clock */
+#define Z16F_OSCCTL_WDT10KHZ _HX8(03) /* Bits 0-1=3: WD Timer 10 KHz*/
+
/* GPIO Port A-K ********************************************************************/
#define Z16F_GPIOA_IN _HX32(ffffe100) /* 8-bits: Port A Input Data */
@@ -249,32 +348,103 @@
#define Z16F_UART1_BRH _HX32(ffffe216) /* 8-bits: UART1 Baud Rate High Byte */
#define Z16F_UART1_BRL _HX32(ffffe217) /* 8-bits: UART1 Baud Rate Low Byte */
-/* Control Registers ***************************************************************/
-
-#define Z16F_CNTRL_PCOV _HX32(fffffe04) /* 32-bits: Program counter overflow */
-#define Z16F_CNTRL_SPOV _HX32(fffffe0c) /* 32-bits: Stack pointer overflow */
-#define Z16F_CNTRL_FLAGS _HX32(fffffe10) /* 8-bits: flags */
-#define Z16F_CNTRL_CPUCTL _HX32(fffffe12) /* 8-bits: CPU control */
-
-/* Flag register bits ***************************************************************/
+/* Timer0/1/2 registers *************************************************************/
+
+#define Z16F_TIMER0_HL _HX32(ffffe300) /* 16-bit: Timer 0 */
+#define Z16F_TIMER0_H _HX32(ffffe300) /* 8-bit: Timer 0 High Byte */
+#define Z16F_TIMER0_L _HX32(ffffe301) /* 8-bit: Timer 0 Low Byte */
+#define Z16F_TIMER0_R _HX32(ffffe302) /* 16-bit: Timer 0 Reload */
+#define Z16F_TIMER0_RH _HX32(ffffe302) /* 8-bit: Timer 0 Reload High Byte */
+#define Z16F_TIMER0_RL _HX32(ffffe303) /* 8-bit: Timer 0 Reload Low Byte */
+#define Z16F_TIMER0_PWM _HX32(ffffe304) /* 16-bit: Timer 0 PWM */
+#define Z16F_TIMER0_PWMH _HX32(ffffe304) /* 8-bit: Timer 0 PWM High Byte */
+#define Z16F_TIMER0_PWML _HX32(ffffe305) /* 8-bit: Timer 0 PWM Low Byte */
+#define Z16F_TIMER0_CTL _HX32(ffffe306) /* 16-bit: Timer 0 Control */
+#define Z16F_TIMER0_CTL0 _HX32(ffffe306) /* 8-bit: Timer 0 Control 0 */
+#define Z16F_TIMER0_CTL1 _HX32(ffffe307) /* 8-bit: Timer 0 Control 1 */
+
+#define Z16F_TIMER1_HL _HX32(ffffe310) /* 16-bit: Timer 1 */
+#define Z16F_TIMER1_H _HX32(ffffe310) /* 8-bit: Timer 1 High Byte */
+#define Z16F_TIMER1_L _HX32(ffffe311) /* 8-bit: Timer 1 Low Byte */
+#define Z16F_TIMER1_R _HX32(ffffe312) /* 16-bit: Timer 1 Reload */
+#define Z16F_TIMER1_RH _HX32(ffffe312) /* 8-bit: Timer 1 Reload High Byte */
+#define Z16F_TIMER1_RL _HX32(ffffe313) /* 8-bit: Timer 1 Reload Low Byte */
+#define Z16F_TIMER1_PWM _HX32(ffffe314) /* 16-bit: Timer 1 PWM */
+#define Z16F_TIMER1_PWMH _HX32(ffffe314) /* 8-bit: Timer 1 PWM High Byte */
+#define Z16F_TIMER1_PWML _HX32(ffffe315) /* 8-bit: Timer 1 PWM Low Byte */
+#define Z16F_TIMER1_CTL _HX32(ffffe316) /* 16-bit: Timer 1 Control */
+#define Z16F_TIMER1_CTL0 _HX32(ffffe316) /* 8-bit: Timer 1 Control 0 */
+#define Z16F_TIMER1_CTL1 _HX32(ffffe317) /* 8-bit: Timer 1 Control 1 */
+
+#define Z16F_TIMER2_HL _HX32(ffffe320) /* 16-bit: Timer 2 */
+#define Z16F_TIMER2_H _HX32(ffffe320) /* 8-bit: Timer 2 High Byte */
+#define Z16F_TIMER2_L _HX32(ffffe321) /* 8-bit: Timer 2 Low Byte */
+#define Z16F_TIMER2_R _HX32(ffffe322) /* 16-bit: Timer 2 Reload */
+#define Z16F_TIMER2_RH _HX32(ffffe322) /* 8-bit: Timer 2 Reload High Byte */
+#define Z16F_TIMER2_RL _HX32(ffffe323) /* 8-bit: Timer 2 Reload Low Byte */
+#define Z16F_TIMER2_PWM _HX32(ffffe324) /* 16-bit: Timer 2 PWM */
+#define Z16F_TIMER2_PWMH _HX32(ffffe324) /* 8-bit: Timer 2 PWM High Byte */
+#define Z16F_TIMER2_PWML _HX32(ffffe325) /* 8-bit: Timer 2 PWM Low Byte */
+#define Z16F_TIMER2_CTL _HX32(ffffe326) /* 16-bit: Timer 2 Control */
+#define Z16F_TIMER2_CTL0 _HX32(ffffe326) /* 8-bit: Timer 2 Control 0 */
+#define Z16F_TIMER2_CTL1 _HX32(ffffe327) /* 8-bit: Timer 2 Control 1 */
+
+/* Common timer0/1/2 register bit definitions ***************************************/
+
+#define Z16F_TIMERCTL0_TMODE _HX8(80) /* Bit 7: Timer mode */
+ /* Bits 5-6: Timer configuration,
+ * Interpretation depends on timer mode */
+#define Z16F_TIMERCTL0_RELOAD _HX8(00) /* Interrupt occurs on reload or capture */
+#define Z16F_TIMERCTL0_DISABLED _HX8(40) /* Disabled */
+#define Z16F_TIMERCTL0_INACTIVE _HX8(40) /* Interrrupt occurs on inactive gate edge */
+#define Z16F_TIMERCTL0_CAPTURE _HX8(40) /* Interrupt occurs on capture */
+#define Z16F_TIMERCTL0_RELOAD _HX8(60) /* Interrupt occurs on reload */
+#define Z16F_TIMERCTL0_CASCADE _HX8(10) /* Bit 4: Timer is cascaded */
+ /* Bits 1-2: PW mode */
+#define Z16F_TIMERCTL0_NODELAY _HZ8(00) /* No delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(01) /* 2 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(02) /* 4 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(03) /* 8 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(04) /* 16 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(05) /* 32 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(06) /* 64 cycle delay */
+#define Z16F_TIMERCTL0_DELAY2 _HZ8(07) /* 128 cycle delay */
+
+#define Z16F_TIMERCTL1_TEN _HX8(80) /* Bit 7: Timer enable */
+#define Z16F_TIMERCTL1_TPOL _HX8(40) /* Bit 6: Input output polarity */
+ /* Bits 3-5: Timer prescale value */
+#define Z16F_TIMERSCTL1_DIV1 _HX8(00) /* Divide by 1 */
+#define Z16F_TIMERSCTL1_DIV2 _HX8(08) /* Divide by 2 */
+#define Z16F_TIMERSCTL1_DIV4 _HX8(10) /* Divide by 4 */
+#define Z16F_TIMERSCTL1_DIV8 _HX8(18) /* Divide by 8 */
+#define Z16F_TIMERSCTL1_DIV16 _HX8(20) /* Divide by 16 */
+#define Z16F_TIMERSCTL1_DIV32 _HX8(28) /* Divide by 32 */
+#define Z16F_TIMERSCTL1_DIV64 _HX8(30) /* Divide by 64 */
+#define Z16F_TIMERSCTL1_DIV128 _HX8(38) /* Divide by 128 */
+ /* Bits 0-2: Timer mode + CTL0 TMODE bit*/
+#define Z16F_TIMERSCTL1_ONESHOT _HX8(00) /* One shot mode (CTL0 TMOD = 0) */
+#define Z16F_TIMERSCTL1_PWMDO _HX8(00) /* One shot mode (CTL0 TMOD = 1) */
+#define Z16F_TIMERSCTL1_CONT _HX8(01) /* Continuous mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_CAPRST _HX8(01) /* Capture restart mode (CTL0 TMOD = 1)*/
+#define Z16F_TIMERSCTL1_COUNTER _HX8(02) /* Counter mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_CMPCNTR _HX8(02) /* Comparator counter mode (CTL0 TMOD = 1)*/
+#define Z16F_TIMERSCTL1_PWMSO _HX8(03) /* PWM single output mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_TRIGOS _HX8(03) /* Triggered one shot (CTL0 TMOD = 1)*/
+#define Z16F_TIMERSCTL1_CAPTURE _HX8(04) /* Capture mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_COMPARE _HX8(05) /* Compare mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_GATED _HX8(06) /* Gated mode (CTL0 TMOD = 0)*/
+#define Z16F_TIMERSCTL1_CAPCMP _HX8(07) /* Capture/Compare mode (CTL0 TMOD = 0)*/
+
+/* Register access macros ***********************************************************/
-#define Z16F_CNTRL_FLAGS_C _HX8(80) /* Bit 7: Carry flag */
-#define Z16F_CNTRL_FLAGS_Z _HX8(40) /* Bit 6: Zero flag */
-#define Z16F_CNTRL_FLAGS_S _HX8(20) /* Bit 5: Sign flag */
-#define Z16F_CNTRL_FLAGS_V _HX8(10) /* Bit 4: Overflow flag */
-#define Z16F_CNTRL_FLAGS_B _HX8(08) /* Bit 3: Blank flag */
-#define Z16F_CNTRL_FLAGS_F1 _HX8(04) /* Bit 2: User flag 1 */
-#define Z16F_CNTRL_FLAGS_CIRQE _HX8(02) /* Bit 1: Chained interrupt enable */
-#define Z16F_CNTRL_FLAGS_IRQE _HX8(01) /* Bit 0: Master interrupt enable */
-
-/* CPU control register bits ********************************************************/
-
- /* Bits 7-2: Reserved, must be zero */
- /* Bits 1-0: DMA bandwidth control */
-#define Z16F_CNTRL_CPUCTL_BWALL _HX8(00) /* DMA can consume 100% bandwidth */
-#define Z16F_CNTRL_CPUCTL_BW11 _HX8(01) /* DMA can do 1 transaction per 1 cycle */
-#define Z16F_CNTRL_CPUCTL_BW12 _HX8(01) /* DMA can do 1 transaction per 2 cycles */
-#define Z16F_CNTRL_CPUCTL_BW13 _HX8(01) /* DMA can do 1 transaction per 3 cycles */
+#ifndef __ASSEMBLY__
+# define getreg8(a) (*(ubyte volatile near*)((a) & 0xffff))
+# define putreg8(v,a) (*(ubyte volatile near*)((a) & 0xffff) = (v))
+# define getreg16(a) (*(uint16 volatile near*)((a) & 0xffff))
+# define putreg16(v,a) (*(uint16 volatile near*)((a) & 0xffff) = (v))
+# define getreg32(a) (*(uint32 volatile near*)((a) & 0xffff))
+# define putreg32(v,a) (*(uint32 volatile near*)((a) & 0xffff) = (v))
+#endif /* __ASSEMBLY__ */
/************************************************************************************
* Public Function Prototypes
@@ -302,6 +472,6 @@ extern void z16f_lowuartinit(void);
#ifdef __cplusplus
}
#endif
-#endif
+#endif /* __ASSEMBLY__ */
#endif /* __Z16F_CHIP_H */
diff --git a/nuttx/arch/z16/src/z16f/z16f_clkinit.c b/nuttx/arch/z16/src/z16f/z16f_clkinit.c
new file mode 100644
index 000000000..3b8fa87e8
--- /dev/null
+++ b/nuttx/arch/z16/src/z16f/z16f_clkinit.c
@@ -0,0 +1,245 @@
+/***************************************************************************
+ * z16f/z16f_clkinit.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Based upon sample code included with the Zilog ZDS-II toolchain.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ***************************************************************************/
+
+/***************************************************************************
+ * Included Files
+ ***************************************************************************/
+
+/***************************************************************************
+ * Definitions
+ ***************************************************************************/
+
+/* System clock source value from ZDS target settings */
+
+extern _Erom unsigned long SYS_CLK_SRC;
+#define _DEFSRC ((unsigned long)&SYS_CLK_SRC)
+
+/* System clock frequency value from ZDS target settings */
+
+extern _Erom unsigned long SYS_CLK_FREQ;
+#define _DEFCLK ((unsigned long)&SYS_CLK_FREQ)
+
+/* Setup FLASH options at address 0x00000000 */
+
+Z16F_FLOPTION0 = (Z16F_FLOPTION0_MAXPWR|Z16F_FLOPTION0_WDTRES|\
+ Z16F_FLOPTION0_WDTA0|Z16F_FLOPTION0_VBOA0|\
+ Z16F_FLOPTION0_DBGUART|Z16F_FLOPTION0_FWP|
+ Z16F_FLOPTION0_RP);
+Z16F_FLOPTION1 = (Z16F_FLOPTION1_RESVD|Z16F_FLOPTION1_MCEN|\
+ Z16F_FLOPTION1_OFFH|Z16F_FLOPTION1_OFFL);
+Z16F_FLOPTION2 = Z16F_FLOPTION2_RESVD;
+Z16F_FLOPTION3 = (Z16F_FLOPTION3_RESVD|Z16F_FLOPTION3_NORMAL);
+
+/***************************************************************************
+ * Private Functions
+ ***************************************************************************/
+
+#ifndef CONFIG_DEBUG
+/***************************************************************************
+ * System clock initialization--DEBUG. Code Using Frequency Input from
+ * ZDS IDE.
+ *
+ * The sysclk_init function below uses the flexibility of the ZDS debug
+ * environment to allow the user to experiment with different clock frequency
+ * settings to help determine the frequency requirements of his Project. The
+ * function allows the selection of internal 5.56 MHz, the 10 KHz Watch Dog
+ * timer or an external clock Source. ZNEO supports clock frequency division
+ * with the Clock Division Register. The clock division Register will divide
+ * by (a minimum of) 2 or more. An assumed clock value of 5.5 MHz internal or
+ * an external clock of 20 MHz was used as the crystal frequency to match the
+ * Demo Target. The User can enter a new frequency in the OTHER clock dialog
+ * Target Setting. The clock frequency is passed with the variable _DEFFREQ
+ * and the clock source is _DEFSRC.
+ *
+ * NOTE: The UART output is designed to work with 5.56 MHz internal and 20 MHz
+ * External clock frequencies at the Default Baud rate of 57.6K Baud.
+ * Entering different clock frequencies may cause the UART to stop transmitting
+ * unless the user makes changes to the UART routines.
+ *
+ * Function Not Recommended for Release Code.
+ *
+ ***************************************************************************/
+
+static void z16f_sysclkinit(void)
+{
+ /* _DEFSRC (SCKSEL Bits 1,0) is passed to program view the .linkcmd file */
+
+ int count;
+ int temp_oscdiv;
+
+ if ((getreg8(Z16F_OSC_CTL) & 0x03) != _DEFSRC)
+ {
+ if (_DEFSRC == 0)
+ {
+ /* Enable 5.6 MHz clock RESET DEFAULT*/
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xa0, Z16F_OSC_CTL);
+
+ /* Wait for oscillator to stabilize */
+
+ for (count = 0; count < 10000; count++);
+
+ /* Select 5.6 MHz clock */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xa0 | _DEFSRC, Z16F_OSC_CTL);
+ }
+
+ if (_DEFSRC == 1)
+ {
+ /* enable (reserved) clock */
+ }
+
+ if (_DEFSRC == 2 )
+ {
+ /* Enable external oscillator */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xe0, Z16F_OSC_CTL);
+
+ /* Wait for oscillator to stabilize */
+
+ for (count = 0; count < 10000; count++);
+
+ /* select external oscillator */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xe0 | _DEFSRC, Z16F_OSC_CTL);
+ }
+
+ if (_DEFSRC == 3)
+ {
+ /* Enable watchdog timer clock */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xb0, Z16F_OSC_CTL);
+
+ /* Wait for oscillator to stabilize */
+
+ for (count = 0; count < 10000; count++);
+
+ /* Select watch dog timer clock */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xb0 | _DEFSRC, Z16F_OSC_CTL);
+ }
+ }
+
+ /* Check SysClock Frequency.
+ * divide the clock if the user has selected the OTHER option for frequency.
+ */
+
+ if (((_DEFSRC == 0) && (_DEFCLK < 3000000ul)) ||
+ ((_DEFSRC == 2) && (_DEFCLK <= 10000000ul)))
+ {
+ if ( _DEFSRC ==0 )
+ {
+ temp_oscdiv = ( 5526000ul / (_DEFCLK +1) );
+ /* Example @ 32 KHz: 0xAC (172 decimal)*/
+ }
+ else
+ {
+ temp_oscdiv = (( 20000000ul / (_DEFCLK +1) ) + 1 );
+ }
+
+ /* Unlock and Set the Oscillator Division Register (Z16F_OSC_DIV) */
+
+ putreg8(0xE7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(temp_oscdiv, Z16F_OSC_DIV);
+ }
+
+ /* Wait for oscillator to stabilize */
+
+ for (count = 0; count < 10000; count++);
+}
+
+#else
+/***************************************************************************
+ * System Clock Initialization Recommended for Release Code
+ *
+ * The z16f_sysclkinit function below allows the user to switch from
+ * Internal to External Clock source and should be used for clock frequency
+ * switching to the External Clock. Note the delay to allow the clock to
+ * stabilize.
+ ***************************************************************************/
+
+static void z16f_sysclkinit(void)
+{
+ /*
+ * _DEFSRC (SCKSEL Bits 1,0) is passed to program from Target Settings Dialog.
+ * I.E. extern _Erom unsigned long SYS_CLK_SRC;
+ */
+ int count;
+
+ if ((getreg8(Z16F_OSC_CTL) & 0x03) != _DEFSRC)
+ {
+ /* enable external oscillator */
+
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xe0, Z16F_OSC_CTL);
+
+ /* wait for oscillator to stabilize */
+ for (count = 0; count < 10000; count++);
+
+ /* select external oscillator */
+ putreg8(0xe7, Z16F_OSC_CTL);
+ putreg8(0x18, Z16F_OSC_CTL);
+ putreg8(0xe0 | _DEFSRC, Z16F_OSC_CTL);
+ }
+}
+#endif /* CONFIG_DEBUG */
+
+/***************************************************************************
+ * Public Functions
+ ***************************************************************************/
+/***************************************************************************
+ * Name: z16f_clkinit
+ ***************************************************************************/
+void z16f_clkinit(void)
+{
+ z16f_sysclkinit();
+}
+
diff --git a/nuttx/arch/z16/src/z16f/z16f_irq.c b/nuttx/arch/z16/src/z16f/z16f_irq.c
new file mode 100644
index 000000000..f5335af15
--- /dev/null
+++ b/nuttx/arch/z16/src/z16f/z16f_irq.c
@@ -0,0 +1,197 @@
+/****************************************************************************
+ * z16f/z16f_irq.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <nuttx/irq.h>
+
+#include "chip/chip.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_irqinitialize
+ ****************************************************************************/
+
+void up_irqinitialize(void)
+{
+ /* Clear and disable all interrupts. Set all to priority 0. */
+
+ putreg8(0xff, Z16F_IRQ0);
+ putreg8(0xff, Z16F_IRQ1);
+ putreg8(0xff, Z16F_IRQ2);
+
+ putreg16(0x0000, Z16F_IRQ0_EN);
+ putreg16(0x0000, Z16F_IRQ1_EN);
+ putreg16(0x0000, Z16F_IRQ2_EN);
+
+ /* currents_regs is non-NULL only while processing an interrupt */
+
+ current_regs = NULL;
+
+ /* And finally, enable interrupts */
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+ EI();
+#endif
+}
+
+/****************************************************************************
+ * Name: up_disable_irq
+ *
+ * Description:
+ * Disable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_disable_irq(int irq)
+{
+ /* System exceptions cannot be disabled */
+
+ if (irq >= Z16F_IRQ_IRQ0)
+ {
+ /* Disable the interrupt by clearing the corresponding bit in the
+ * appropriate IRQ enable register.
+ */
+
+ if (irq < Z16F_IRQ_IRQ1)
+ {
+ putreg8((getreg8(Z16F_IRQ0_ENH) & ~Z16_IRQ0_BIT(irq)), Z16F_IRQ0_ENH);
+ }
+ else if (irq < Z16F_IRQ_IRQ2)
+ {
+ putreg8((getreg8(Z16F_IRQ1_ENH) & ~Z16_IRQ1_BIT(irq)), Z16F_IRQ1_ENH);
+ }
+ else if (irq < NR_IRQS)
+ {
+ putreg8((getreg8(Z16F_IRQ2_ENH) & ~Z16_IRQ2_BIT(irq)), Z16F_IRQ2_ENH);
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: up_enable_irq
+ *
+ * Description:
+ * Enable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_enable_irq(int irq)
+{
+ /* System exceptions cannot be disabled */
+
+ if (irq >= Z16F_IRQ_IRQ0)
+ {
+ /* Enable the interrupt by setting the corresponding bit in the
+ * appropriate IRQ enable register.
+ */
+
+ if (irq < Z16F_IRQ_IRQ1)
+ {
+ putreg8((getreg8(Z16F_IRQ0_ENH) | Z16_IRQ0_BIT(irq)), Z16F_IRQ0_ENH);
+ }
+ else if (irq < Z16F_IRQ_IRQ2)
+ {
+ putreg8((getreg8(Z16F_IRQ1_ENH) | Z16_IRQ1_BIT(irq)), Z16F_IRQ1_ENH);
+ }
+ else if (irq < NR_IRQS)
+ {
+ putreg8((getreg8(Z16F_IRQ2_ENH) | Z16_IRQ2_BIT(irq)), Z16F_IRQ2_ENH);
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: up_maskack_irq
+ *
+ * Description:
+ * Mask the IRQ and acknowledge it
+ *
+ ****************************************************************************/
+
+void up_maskack_irq(int irq)
+{
+ /* System exceptions cannot be disabled or acknowledged */
+
+ if (irq >= Z16F_IRQ_IRQ0)
+ {
+ /* Disable the interrupt by clearing the corresponding bit in the
+ * appropriate IRQ enable register and acknowledge it by setting the
+ * corresponding bit in the IRQ status register.
+ */
+
+ if (irq < Z16F_IRQ_IRQ1)
+ {
+ putreg8((getreg8(Z16F_IRQ0_ENH) & ~Z16_IRQ0_BIT(irq)), Z16F_IRQ0_ENH);
+ putreg8(Z16_IRQ0_BIT(irq), Z16F_IRQ0);
+ }
+ else if (irq < Z16F_IRQ_IRQ2)
+ {
+ putreg8((getreg8(Z16F_IRQ1_ENH) & ~Z16_IRQ1_BIT(irq)), Z16F_IRQ1_ENH);
+ putreg8(Z16_IRQ1_BIT(irq), Z16F_IRQ2);
+ }
+ else if (irq < NR_IRQS)
+ {
+ putreg8((getreg8(Z16F_IRQ2_ENH) & ~Z16_IRQ2_BIT(irq)), Z16F_IRQ2_ENH);
+ putreg8(Z16_IRQ2_BIT(irq), Z16F_IRQ2);
+ }
+ }
+}
diff --git a/nuttx/arch/z16/src/z16f/z16f_timerisr.c b/nuttx/arch/z16/src/z16f/z16f_timerisr.c
new file mode 100644
index 000000000..12925b933
--- /dev/null
+++ b/nuttx/arch/z16/src/z16f/z16f_timerisr.c
@@ -0,0 +1,135 @@
+/***************************************************************************
+ * z16f/z16f_timerisr.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ***************************************************************************/
+
+/***************************************************************************
+ * Included Files
+ ***************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <chip/chip.h>
+
+#include "clock_internal.h"
+#include "up_internal.h"
+
+/***************************************************************************
+ * Definitions
+ ***************************************************************************/
+
+/* System clock frequency value from ZDS target settings */
+
+extern _Erom unsigned long SYS_CLK_FREQ;
+#define _DEFCLK ((unsigned long)&SYS_CLK_FREQ)
+
+/***************************************************************************
+ * Private Types
+ ***************************************************************************/
+
+/***************************************************************************
+ * Private Function Prototypes
+ ***************************************************************************/
+
+/***************************************************************************
+ * Global Functions
+ ***************************************************************************/
+
+/***************************************************************************
+ * Function: up_timerisr
+ *
+ * Description:
+ * The timer ISR will perform a variety of services for various portions
+ * of the system.
+ *
+ ***************************************************************************/
+
+int up_timerisr(int irq, uint32 *regs)
+{
+ /* Process timer interrupt */
+
+ sched_process_timer();
+ return 0;
+}
+
+/***************************************************************************
+ * Function: up_timerinit
+ *
+ * Description:
+ * This function is called during start-up to initialize
+ * the timer interrupt.
+ *
+ ***************************************************************************/
+
+void up_timerinit(void)
+{
+ up_disable_irq(Z16F_IRQ_SYSTIMER);
+
+ /* Disable the timer and configure for divide by 1 and continuous mode. */
+
+ putreg16( Z16F_TIMERSCTL1_DIV1 | Z16F_TIMERSCTL1_CONT);
+
+ /* Assign an intial timer value */
+
+ putreg16(0x0001, Z16F_TIMER0_HL);
+
+ /* Set the timer reload value.
+ *
+ * In continuous mode:
+ *
+ * timer_frequency = system_clock_freqency / divisor / reload_value
+ * or
+ * reload_value = (system_clock_frequency / timer_frequency / divisor
+ *
+ * For system_clock_frequency=200MHz, timer_frequency=100KHz, and divisor=1,
+ * this yields 200.
+ */
+
+ putreg16(((uint32)_DEFCLK / 100000), Z16F_TIMER0_R);
+
+ /* Enable the timer */
+
+ putreg8((getret8(Z16F_TIMER0_CTL1) |= Z16F_TIMERCTL1_TEN), Z16F_TIMER0_CTL1);
+
+ /* Set the timer priority */
+
+ /* Attach and enable the timer interrupt (leaving at priority 0 */
+
+ irq_attach(Z16F_IRQ_SYSTIMER, (xcpt_t)up_timerisr);
+ up_enable_irq(Z16F_IRQ_SYSTIMER);
+}
+