summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_irq.c9
-rw-r--r--nuttx/arch/z80/include/z8/irq.h28
-rw-r--r--nuttx/arch/z80/src/z8/chip.h23
-rw-r--r--nuttx/arch/z80/src/z8/z8_irq.c129
-rw-r--r--nuttx/arch/z80/src/z8/z8_timerisr.c145
5 files changed, 330 insertions, 4 deletions
diff --git a/nuttx/arch/z16/src/z16f/z16f_irq.c b/nuttx/arch/z16/src/z16f/z16f_irq.c
index 485b482fa..01e21229f 100644
--- a/nuttx/arch/z16/src/z16f/z16f_irq.c
+++ b/nuttx/arch/z16/src/z16f/z16f_irq.c
@@ -40,8 +40,10 @@
#include <nuttx/config.h>
#include <sys/types.h>
+
#include <nuttx/irq.h>
#include <arch/irq.h>
+#include <ez8.h>
#include "chip/chip.h"
#include "os_internal.h"
@@ -109,7 +111,8 @@ void up_disable_irq(int irq)
if (irq >= Z16F_IRQ_IRQ0)
{
/* Disable the interrupt by clearing the corresponding bit in the
- * appropriate IRQ enable register.
+ * appropriate IRQ enable high register. The enable low
+ * register is assumed to be zero, resulting interrupt disabled.
*/
if (irq < Z16F_IRQ_IRQ1)
@@ -142,7 +145,9 @@ void up_enable_irq(int irq)
if (irq >= Z16F_IRQ_IRQ0)
{
/* Enable the interrupt by setting the corresponding bit in the
- * appropriate IRQ enable register.
+ * appropriate IRQ enable register. The enable low
+ * register is assumed to be zero, resulting in "nomimal" interrupt
+ * priority.
*/
if (irq < Z16F_IRQ_IRQ1)
diff --git a/nuttx/arch/z80/include/z8/irq.h b/nuttx/arch/z80/include/z8/irq.h
index fec1da0bf..b994635be 100644
--- a/nuttx/arch/z80/include/z8/irq.h
+++ b/nuttx/arch/z80/include/z8/irq.h
@@ -72,7 +72,7 @@
# endif
#endif
-/* ez8 Interrupt Numbers */
+/* ez8 Interrupt Numbers ****************************************************/
#if defined(ENCORE_VECTORS)
@@ -198,7 +198,31 @@
#define Z8_IRQ_SYSTIMER Z8_TIMER0_IRQ
-/* IRQ State Save Formatt
+/* IRQ Management Macros ****************************************************/
+
+/* These macros map IRQ numbers to IRQ registers and bits.
+ * WARNING: These have only been verified for the Z8F640X family!
+ */
+
+#if defined(_Z8ENCORE_F640X) || defined(_Z8ENCORE_640_FAMILY)
+
+# define Z8_IRQ0_MIN Z8_TIMER2_IRQ
+# define Z8_IRQ0_BIT(irq) (Z8_ADC_IRQ - (irq))
+# define Z8_IRQ0_MAX Z8_ADC_IRQ
+
+# define Z8_IRQ1_MIN Z8_P7AD_IRQ
+# define Z8_IRQ1_BIT(irq) (Z8_P0AD_IRQ - (irq))
+# define Z8_IRQ1_MAX Z8_P0AD_IRQ
+
+# define Z8_IRQ2_MIN Z8_TIMER3_IRQ
+# define Z8_IRQ3_BIT(irq) (Z8_C0_IRQ - (irq))
+# define Z8_IRQ2_MAX Z8_C0_IRQ
+
+#else
+# error "Add IRQ support for Z8F family"
+#endif
+
+/* IRQ State Save Format ****************************************************
*
* These indices describe how the ez8 context is save in the state save array
*
diff --git a/nuttx/arch/z80/src/z8/chip.h b/nuttx/arch/z80/src/z8/chip.h
index be216f1e0..8bacfcfed 100644
--- a/nuttx/arch/z80/src/z8/chip.h
+++ b/nuttx/arch/z80/src/z8/chip.h
@@ -74,6 +74,29 @@
* ZDS-II header file, ez8.h, to provide the correct addresses for each register.
*/
+/* Timer Register Bit Definitions ***************************************************/
+
+/* Timer control register */
+
+#define Z8_TIMERCTL1_TEN _HX(80) /* Bit 7: Timer enabled */
+#define Z8_TIMERCTL1_TPOL _HX(40) /* Bit 6: Timer input/output polarity */
+#define Z8_TIMERSCTL_DIV1 _HX(00) /* Bits 3-5: Pre-scale divisor */
+#define Z8_TIMERSCTL_DIV2 _HX(08)
+#define Z8_TIMERSCTL_DIV4 _HX(10)
+#define Z8_TIMERSCTL_DIV8 _HX(18)
+#define Z8_TIMERSCTL_DIV16 _HX(20)
+#define Z8_TIMERSCTL_DIV32 _HX(28)
+#define Z8_TIMERSCTL_DIV64 _HX(30)
+#define Z8_TIMERSCTL_DIV128 _HX(38)
+#define Z8_TIMERSCTL_ONESHOT _HX(00) /* Bits 0-2: Timer mode */
+#define Z8_TIMERSCTL_CONT _HX(01)
+#define Z8_TIMERSCTL_COUNTER _HX(02)
+#define Z8_TIMERSCTL_PWM _HX(03)
+#define Z8_TIMERSCTL_CAPTURE _HX(04)
+#define Z8_TIMERSCTL_COMPARE _HX(05)
+#define Z8_TIMERSCTL_GATED _HX(06)
+#define Z8_TIMERSCTL_CAPCMP _HX(07)
+
/* Register access macros ***********************************************************
*
* The register access mechanism provided in ez8.h differs from the useful in other
diff --git a/nuttx/arch/z80/src/z8/z8_irq.c b/nuttx/arch/z80/src/z8/z8_irq.c
index 38f24a968..0c6af3939 100644
--- a/nuttx/arch/z80/src/z8/z8_irq.c
+++ b/nuttx/arch/z80/src/z8/z8_irq.c
@@ -74,6 +74,29 @@ struct z8_irqstate_s g_z8irqstate;
****************************************************************************/
/****************************************************************************
+ * Name: up_irqinitialize
+ ****************************************************************************/
+
+void up_irqinitialize(void)
+{
+ /* Clear and disable all interrupts. Set all to priority 0. */
+
+ putreg8(0xff, Z8_IRQ0);
+ putreg8(0xff, Z8_IRQ1);
+ putreg8(0xff, Z8_IRQ2);
+
+ putreg16(0x0000, Z8_IRQ0_EN);
+ putreg16(0x0000, Z8_IRQ1_EN);
+ putreg16(0x0000, Z8_IRQ2_EN);
+
+ /* And finally, enable interrupts */
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+ EI();
+#endif
+}
+
+/****************************************************************************
* Name: irqsave
*
* Description:
@@ -119,3 +142,109 @@ void irqrestore(irqstate_t flags)
EI();
}
}
+
+/****************************************************************************
+ * Name: up_disable_irq
+ *
+ * Description:
+ * Disable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_disable_irq(int irq)
+{
+ /* System exceptions cannot be disabled */
+
+ if (irq >= Z8_IRQ0_MIN)
+ {
+ /* Disable the interrupt by clearing the corresponding bit in the
+ * appropriate IRQ enable high register. The enable low
+ * register is assumed to be zero, resulting interrupt disabled.
+ */
+
+ if (irq < Z8_IRQ0_MAX)
+ {
+ putreg8((getreg8(Z8_IRQ0_ENH) & ~Z8_IRQ0_BIT(irq)), Z8_IRQ0_ENH);
+ }
+ else if (irq < Z8_IRQ1_MAX)
+ {
+ putreg8((getreg8(Z8_IRQ1_ENH) & ~Z8_IRQ1_BIT(irq)), Z8_IRQ1_ENH);
+ }
+ else if (irq < NR_IRQS)
+ {
+ putreg8((getreg8(Z8_IRQ2_ENH) & ~Z8_IRQ2_BIT(irq)), Z8_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 >= Z8_IRQ0_MIN)
+ {
+ /* Enable the interrupt by setting the corresponding bit in the
+ * appropriate IRQ enable high register. The enable low
+ * register is assumed to be zero, resulting in "nomimal" interrupt
+ * priority.
+ */
+
+ if (irq < Z8_IRQ0_MAX)
+ {
+ putreg8((getreg8(Z8_IRQ0_ENH) | Z8_IRQ0_BIT(irq)), Z8_IRQ0_ENH);
+ }
+ else if (irq < Z8_IRQ1_MAX)
+ {
+ putreg8((getreg8(Z8_IRQ1_ENH) | Z8_IRQ1_BIT(irq)), Z8_IRQ1_ENH);
+ }
+ else if (irq < NR_IRQS)
+ {
+ putreg8((getreg8(Z8_IRQ2_ENH) | Z8_IRQ2_BIT(irq)), Z8_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 >= Z8_IRQ0_MIN)
+ {
+ /* 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 < Z8_IRQ0_MAX)
+ {
+ putreg8((getreg8(Z8_IRQ0_ENH) & ~Z8_IRQ0_BIT(irq)), Z8_IRQ0_ENH);
+ putreg8(Z8_IRQ0_BIT(irq), Z8_IRQ0);
+ }
+ else if (irq < Z8_IRQ1_MAX)
+ {
+ putreg8((getreg8(Z8_IRQ1_ENH) & ~Z8_IRQ1_BIT(irq)), Z8_IRQ1_ENH);
+ putreg8(Z8_IRQ1_BIT(irq), Z8_IRQ2);
+ }
+ else if (irq < NR_IRQS)
+ {
+ putreg8((getreg8(Z8_IRQ2_ENH) & ~Z8_IRQ2_BIT(irq)), Z8_IRQ2_ENH);
+ putreg8(Z8_IRQ2_BIT(irq), Z8_IRQ2);
+ }
+ }
+}
diff --git a/nuttx/arch/z80/src/z8/z8_timerisr.c b/nuttx/arch/z80/src/z8/z8_timerisr.c
new file mode 100644
index 000000000..8ace6a677
--- /dev/null
+++ b/nuttx/arch/z80/src/z8/z8_timerisr.c
@@ -0,0 +1,145 @@
+/***************************************************************************
+ * arch/z80/src/z8/z8_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 <ez8.h>
+
+#include "chip/chip.h"
+#include "clock_internal.h"
+#include "up_internal.h"
+
+/***************************************************************************
+ * Definitions
+ ***************************************************************************/
+
+/* System clock frequency value from ZDS target settings */
+
+extern ROM uint32 __user_frequency;
+#define _DEFCLK ((uint32)&__user_frequency)
+
+/***************************************************************************
+ * Private Types
+ ***************************************************************************/
+
+/***************************************************************************
+ * Private Functions
+ ***************************************************************************/
+
+/***************************************************************************
+ * Public 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(Z8_IRQ_SYSTIMER);
+
+ /* Write to the timer control register to disable the timer, configure
+ * the timer for continuous mode, and set up the pre-scale value for
+ * divide by 4.
+ */
+
+ putreg8( Z8_TIMERSCTL_DIV4 | Z8_TIMERSCTL_CONT, Z8_TIMER0_CTL);
+
+ /* Write to the timer high and low byte registers to set a starting
+ * count value (this effects only the first pass in continuous mode)
+ */
+
+ putreg16(0x0001, Z8_TIMER0_HL);
+
+ /* Write to the timer reload register to set the reload value.
+ *
+ * In continuous mode:
+ *
+ * timer_period = reload_value x prescale / system_clock_frequency
+ * or
+ * reload_value = (timer_period * system_clock_frequency) / prescale
+ *
+ * For system_clock_frequency=18.432MHz, timer_period=10mS, and prescale=4,
+ * then reload_value=46,080 - OR:
+ *
+ * reload_value = system_clock_frequency / 400
+ */
+
+ putreg16(((uint32)_DEFCLK / 400), Z8_TIMER0_R);
+
+ /* Write to the timer control register to enable the timer and to
+ * initiate counting
+ */
+
+ putreg8((getreg8(Z8_TIMER0_CTL) | Z8_TIMERCTL_TEN), Z8_TIMER0_CTL);
+
+ /* Set the timer priority */
+
+ /* Attach and enable the timer interrupt (leaving at priority 0 */
+
+ irq_attach(Z8_IRQ_SYSTIMER, (xcpt_t)up_timerisr);
+ up_enable_irq(Z8_IRQ_SYSTIMER);
+}
+