summaryrefslogtreecommitdiff
path: root/stm32
diff options
context:
space:
mode:
Diffstat (limited to 'stm32')
-rw-r--r--stm32/Tupfile74
-rw-r--r--stm32/debug.h11
-rw-r--r--stm32/serial.c194
-rw-r--r--stm32/serial.h8
-rw-r--r--stm32/stm32vl-discovery.ld31
-rw-r--r--stm32/z180-stamp-stm32.c763
-rw-r--r--stm32/z80-if.c731
-rw-r--r--stm32/z80-if.h32
8 files changed, 1844 insertions, 0 deletions
diff --git a/stm32/Tupfile b/stm32/Tupfile
new file mode 100644
index 0000000..1778623
--- /dev/null
+++ b/stm32/Tupfile
@@ -0,0 +1,74 @@
+include_rules
+
+PROG = z180-stamp-stm32
+SRC = z180-stamp-stm32.c serial.c z80-if.c
+SRC_Z = ../z180/hdrom.c
+#TARGETS = $(PROG).elf
+
+FP_FLAGS = -msoft-float
+DEFS = -DSTM32F1 -DBAUD=115200
+
+LIBNAME = opencm3_stm32f1
+OPENCM3_DIR = $(TOP)/libopencm3
+LDSCRIPT = stm32vl-discovery.ld
+
+###############################################################################
+# Executables
+
+TOOLCHAINDIR = /usr/local/gcc-arm-none-eabi-4_8-2014q2/bin
+TOOLCHAIN = $(TOOLCHAINDIR)/arm-none-eabi
+
+CC = $(TOOLCHAIN)-gcc
+LD = $(TOOLCHAIN)-gcc
+AR = $(TOOLCHAIN)-ar
+AS = $(TOOLCHAIN)-as
+OBJCOPY = $(TOOLCHAIN)-objcopy
+OBJDUMP = $(TOOLCHAIN)-objdump
+SIZE = $(TOOLCHAIN)-size
+GDB = $(TOOLCHAIN)-gdb
+
+###############################################################################
+
+INCLUDES += $(OPENCM3_DIR)/include
+LIBDIRS += $(OPENCM3_DIR)/lib
+
+SCRIPT_DIR = $(OPENCM3_DIR)/scripts
+
+
+ifdef DEBUG
+DEFS += -DDEBUG=2
+endif
+
+CFLAGS += -g -Os
+CFLAGS += -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd
+CFLAGS += -std=gnu99
+CFLAGS += -Wall -Wextra -Wimplicit-function-declaration
+CFLAGS += -Wredundant-decls
+#CFLAGS += -fno-common -ffunction-sections -fdata-sections
+CFLAGS += -I $(INCLUDES)
+
+CPPFLAGS += $(DEFS)
+
+# Linker flags
+LDFLAGS += --static -nostartfiles
+LDFLAGS += -T$(LDSCRIPT)
+LDFLAGS += -Wl,--gc-sections
+LDFLAGS += -Wl,--cref
+
+LDLIBS += -L$(LIBDIRS) -l$(LIBNAME)
+LDLIBS += -Wl,--start-group -lc -lgcc -lnosys -Wl,--end-group
+
+
+!cc = |> ^ CC %f^ $(CC) $(CFLAGS) $(CPPFLAGS) -c %f -o %o |> %B.o
+!LINK = |> ^ LINK %o^ $(LD) $(CFLAGS) $(LDFLAGS) -Wl,-Map=%O.map %f $(LDLIBS) -o %o |> | %O.map
+!OBJCOPY= |> ^ OBJCOPY %o^ $(OBJCOPY) -Oihex %f %o |>
+!OBJDUMP= |> ^ OBJDUMP %o^ $(OBJDUMP) -h -S %f > %o |> %O.lss
+!SIZE = |> ^ SIZE^ $(SIZE) %f |>
+
+: foreach $(SRC) $(SRC_Z) | ../z180/hdrom.h |> !cc |> {objs}
+
+: {objs} |> !LINK |> $(PROG).elf
+: $(PROG).elf |> !OBJCOPY |> %B.hex
+: $(PROG).elf |> !OBJDUMP |> %B.lss
+: $(PROG).elf |> !SIZE |>
+
diff --git a/stm32/debug.h b/stm32/debug.h
new file mode 100644
index 0000000..d542317
--- /dev/null
+++ b/stm32/debug.h
@@ -0,0 +1,11 @@
+
+#ifndef DEBUG_H_
+#define DEBUG_H_
+
+#ifdef DEBUG
+#define DBG_P(lvl, ...) if (DEBUG>=lvl) fprintf( stderr, __VA_ARGS__ )
+#else
+#define DBG_P(lvl, ...)
+#endif
+
+#endif /* DEBUG_H_ */
diff --git a/stm32/serial.c b/stm32/serial.c
new file mode 100644
index 0000000..9193005
--- /dev/null
+++ b/stm32/serial.c
@@ -0,0 +1,194 @@
+/*
+ * serial.c
+ *
+ * Created on: 04.05.2014
+ * Author: leo
+ */
+
+#include <errno.h>
+#include <stdio.h>
+#include <unistd.h>
+
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/usart.h>
+#include <libopencm3/cm3/nvic.h>
+#include "serial.h"
+
+
+#define USART_CONSOLE USART1
+
+int _write(int fd, char *ptr, int len) __attribute__((used));
+
+
+struct ring {
+ uint8_t *data;
+ int size;
+ volatile int begin;
+ volatile int end;
+};
+
+
+#define BUFFER_SIZE 256
+
+struct ring rx_ring;
+struct ring tx_ring;
+uint8_t rx_ring_buffer[BUFFER_SIZE];
+uint8_t tx_ring_buffer[BUFFER_SIZE];
+
+
+static void ring_init(struct ring *ring, uint8_t *buf, int size)
+{
+ ring->data = buf;
+ ring->size = size;
+ ring->begin = 0;
+ ring->end = 0;
+}
+
+static int ring_write_ch(struct ring *ring, uint8_t ch)
+{
+ int ep = (ring->end + 1) % ring->size;
+
+ if ((ep) != ring->begin) {
+ ring->data[ring->end] = ch;
+ ring->end = ep;
+ return 1;
+ }
+
+ return -1;
+}
+
+static int ring_write(struct ring *ring, uint8_t *data, int size)
+{
+ int i;
+
+ for (i = 0; i < size; i++) {
+ if (ring_write_ch(ring, data[i]) < 0)
+ return -i;
+ }
+
+ return i;
+}
+
+static int ring_read_ch(struct ring *ring)
+{
+ int ret = -1;
+
+ if (ring->begin != ring->end) {
+ ret = ring->data[ring->begin];
+ ring->begin = (ring->begin +1) % ring->size;
+ }
+
+ return ret;
+}
+
+void usart_setup(void)
+{
+ /* Initialize output ring buffer. */
+ ring_init(&rx_ring, rx_ring_buffer, BUFFER_SIZE);
+ ring_init(&tx_ring, tx_ring_buffer, BUFFER_SIZE);
+
+ /* Enable the USART1 interrupt. */
+ nvic_enable_irq(NVIC_USART1_IRQ);
+
+ /* Setup GPIO pin GPIO_USART1_TX/LED_GREEN_PIN on GPIO port A for transmit. */
+ /* TODO: USART1 --> USART_CONSOLE */
+
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_TX);
+
+ /* Setup GPIO pin GPIO_USART1_RE_RX on GPIO port B for receive. */
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_FLOAT, GPIO_USART1_RX);
+
+ /* Setup UART parameters. */
+// usart_set_baudrate(USART_CONSOLE, 38400);
+ usart_set_baudrate(USART_CONSOLE, 115200);
+ usart_set_databits(USART_CONSOLE, 8);
+ usart_set_stopbits(USART_CONSOLE, USART_STOPBITS_1);
+ usart_set_parity(USART_CONSOLE, USART_PARITY_NONE);
+ usart_set_flow_control(USART_CONSOLE, USART_FLOWCONTROL_NONE);
+ usart_set_mode(USART_CONSOLE, USART_MODE_TX_RX);
+
+ /* Enable USART1 Receive interrupt. */
+ USART_CR1(USART1) |= USART_CR1_RXNEIE;
+
+ /* Finally enable the USART. */
+ usart_enable(USART_CONSOLE);
+}
+
+void usart1_isr(void)
+{
+ /* Check if we were called because of RXNE. */
+ if (((USART_CR1(USART1) & USART_CR1_RXNEIE) != 0) &&
+ ((USART_SR(USART1) & USART_SR_RXNE) != 0)) {
+
+ /* Retrieve the data from the peripheral. */
+ ring_write_ch(&rx_ring, usart_recv(USART1));
+
+ }
+
+ /* Check if we were called because of TXE. */
+ if (((USART_CR1(USART1) & USART_CR1_TXEIE) != 0) &&
+ ((USART_SR(USART1) & USART_SR_TXE) != 0)) {
+
+ int data;
+
+ data = ring_read_ch(&tx_ring);
+
+ if (data == -1) {
+ /* Disable the TXE interrupt, it's no longer needed. */
+ USART_CR1(USART1) &= ~USART_CR1_TXEIE;
+ } else {
+ /* Put data into the transmit register. */
+ usart_send(USART1, data);
+ }
+ }
+}
+
+/*--------------------------------------------------------------------------*/
+
+void serial_setup(void)
+{
+ usart_setup();
+}
+
+/*--------------------------------------------------------------------------*/
+
+/**
+ * Use USART_CONSOLE as a console.
+ * This is a syscall for newlib
+ * @param fd
+ * @param ptr
+ * @param len
+ * @return
+ */
+int _write(int fd, char *ptr, int len)
+{
+ int i;
+
+ if (fd == STDOUT_FILENO || fd == STDERR_FILENO) {
+ for (i = 0; i < len; i++) {
+ if (ptr[i] == '\n') {
+ serial_putc('\r');
+ }
+ serial_putc(ptr[i]);
+ }
+ return i;
+ }
+ errno = EIO;
+ return -1;
+}
+
+int serial_getc(void)
+{
+ return ring_read_ch(&rx_ring);
+}
+
+void serial_putc(uint8_t data)
+{
+ while (ring_write_ch(&tx_ring, data) < 0)
+ ;
+
+ /* Enable the TXE interrupt. */
+ USART_CR1(USART1) |= USART_CR1_TXEIE;
+}
diff --git a/stm32/serial.h b/stm32/serial.h
new file mode 100644
index 0000000..1a0f510
--- /dev/null
+++ b/stm32/serial.h
@@ -0,0 +1,8 @@
+#ifndef SERIAL_H
+#define SERIAL_H
+
+void serial_setup(void);
+void serial_putc(uint8_t);
+int serial_getc(void);
+
+#endif /* SERIAL_H */
diff --git a/stm32/stm32vl-discovery.ld b/stm32/stm32vl-discovery.ld
new file mode 100644
index 0000000..40de3d3
--- /dev/null
+++ b/stm32/stm32vl-discovery.ld
@@ -0,0 +1,31 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/* Linker script for ST STM32VLDISCOVERY (STM32F100RB, 128K flash, 8K RAM). */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K
+}
+
+/* Include the common ld script. */
+INCLUDE libopencm3_stm32f1.ld
+
diff --git a/stm32/z180-stamp-stm32.c b/stm32/z180-stamp-stm32.c
new file mode 100644
index 0000000..15d732d
--- /dev/null
+++ b/stm32/z180-stamp-stm32.c
@@ -0,0 +1,763 @@
+/*
+ */
+
+#include <stdio.h>
+
+#include <libopencmsis/core_cm3.h>
+#include <libopencm3/cm3/nvic.h>
+#include <libopencm3/cm3/systick.h>
+#include <libopencm3/stm32/rtc.h>
+#include <libopencm3/stm32/rcc.h>
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/timer.h>
+
+#define ODR 0x0c
+#define IDR 0x08
+
+
+#include "debug.h"
+#include "serial.h"
+#include "z80-if.h"
+#include "../z180/hdrom.h"
+
+#define ESCCHAR ('^'-0x40)
+
+#define S_10MS_TO (1<<0)
+
+/*
+ * LED Connections
+ */
+
+#define LED_PORT GPIOC
+#define LED_BLUE_PIN GPIO8
+#define BLUE 8
+#define LED_GREEN_PIN GPIO9
+#define GREEN 9
+
+
+#define LED_BLUE_ON() BBIO_PERIPH(LED_PORT+ODR, BLUE) = 1
+#define LED_BLUE_OFF() BBIO_PERIPH(LED_PORT+ODR, BLUE) = 0
+#define LED_BLUE_TOGGLE() BBIO_PERIPH(LED_PORT+ODR, BLUE) = !BBIO_PERIPH(LED_PORT+ODR, BLUE)
+
+#define LED_GREEN_ON() BBIO_PERIPH(LED_PORT+ODR, GREEN) = 1
+#define LED_GREEN_OFF() BBIO_PERIPH(LED_PORT+ODR, GREEN) = 0
+#define LED_GREEN_TOGGLE() BBIO_PERIPH(LED_PORT+ODR, GREEN) = !BBIO_PERIPH(LED_PORT+ODR, GREEN)
+
+
+/*
+ * Button connections
+ */
+
+//BBIO_PERIPH(GPIOA+IDR, 0);
+
+#define KEY_PORT GPIOA_IDR
+#define KEY0 GPIO0
+//#define KEY1 GPIO1
+//#define KEY2 GPIO2
+
+#define REPEAT_MASK KEY0 // repeat: key0
+#define REPEAT_START 100 // after 1s
+#define REPEAT_NEXT 20 // every 200ms
+
+
+typedef enum {
+ NOTHING, PULSE, BLINK1, BLINK2
+} LED_MODE;
+
+typedef struct {
+ uint8_t mode;
+ uint8_t ontime, offtime;
+} led_stat_t;
+
+volatile uint8_t led_timer[2];
+led_stat_t led_stat[2];
+
+volatile int timeout_1s;
+volatile uint32_t Stat;
+
+
+/*--------------------------------------------------------------------------*/
+
+
+static void clock_setup(void)
+{
+ //rcc_clock_setup_in_hse_8mhz_out_24mhz();
+ rcc_clock_setup_in_hsi_out_24mhz();
+
+ /* Enable clocks for:
+ GPIO port A (for GPIO_USART1_TX and Button)
+ GPIO port C (LEDs)
+ USART1
+ TIM16 (RST-Pin)
+ TIM1 (IOCS1)
+ */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR,
+ RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN
+ | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN
+ | RCC_APB2ENR_USART1EN | RCC_APB2ENR_AFIOEN
+ | RCC_APB2ENR_TIM1EN | RCC_APB2ENR_TIM16EN);
+ /* Enable clocks for:
+ TIM3
+ */
+ rcc_peripheral_enable_clock(&RCC_APB1ENR,
+ RCC_APB1ENR_TIM3EN);
+
+ /* Enable clocks for:
+ DMA1
+ */
+ rcc_peripheral_enable_clock(&RCC_AHBENR,
+ RCC_AHBENR_DMA1EN);
+}
+
+static void systick_setup(void)
+{
+ /* SysTick interrupt every N clock pulses: set reload to N-1 */
+ STK_RVR = 24000000/1000 - 1;
+
+ /* Set source to core clock, enable int and start counting. */
+ STK_CSR = STK_CSR_CLKSOURCE_AHB | STK_CSR_TICKINT | STK_CSR_ENABLE;
+}
+
+#if 0
+static void nvic_setup(void)
+{
+// nvic_enable_irq(NVIC_RTC_IRQ);
+// nvic_set_priority(NVIC_RTC_IRQ, 1);
+}
+#endif
+
+static void tim3_setup(void)
+{
+ TIM3_CR1 = TIM_CR1_CMS_EDGE | TIM_CR1_DIR_UP;
+
+ TIM3_CCMR2 = 0
+ | TIM_CCMR2_OC4M_FORCE_LOW
+ /* | TIM_CCMR2_OC4M_FORCE_HIGH */
+ /* | TIM_CCMR2_OC4M_PWM2 */
+
+ /* | TIM_CCMR2_OC4PE */
+ /* | TIM_CCMR2_OC4FE */
+ | TIM_CCMR2_CC4S_OUT;
+
+ TIM3_CCER = TIM_CCER_CC4E
+ | TIM_CCER_CC4P;
+
+ TIM3_ARR = 48; /* default */
+ TIM3_CCR4 = 1; /* */
+}
+
+static void gpio_setup(void)
+{
+
+ /* Disable JTAG-DP, but leave SW-DP Enabled. (free PA15, PB3, PB4)
+ Remap SPI1 to PB3, PB4, PB5 and PA15.
+ Remap TIM3 (CH1/PC6, CH2/PC7, CH3/PC8, CH4/PC9)
+ Port D0/Port D1 mapping on OSC_IN/OSC_OUT
+ */
+ gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_ON,
+ AFIO_MAPR_SPI1_REMAP
+ | AFIO_MAPR_TIM3_REMAP_FULL_REMAP
+ | AFIO_MAPR_PD01_REMAP);
+
+ /* LEDs and User Button. */
+ gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, LED_BLUE_PIN);
+ gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_10_MHZ,
+ GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, LED_GREEN_PIN);
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_FLOAT, GPIO0);
+}
+
+
+/*--------------------------------------------------------------------------*/
+
+void delay_systicks(int ticks)
+{
+ int start, stop, now;
+
+ start = STK_CVR;
+ stop = start - ticks;
+ if (stop < 0) {
+ stop += STK_RVR;
+ do {
+ now = STK_CVR;
+ } while ((now > stop) || (now <= start));
+ } else {
+ do {
+ now = STK_CVR;
+ } while ((now > stop) && (now <= start));
+ }
+}
+
+
+/*--------------------------------------------------------------------------*/
+
+static void led_toggle(uint8_t lednr) {
+ if (lednr == 0)
+ LED_BLUE_TOGGLE();
+ else if (lednr == 1)
+ LED_GREEN_TOGGLE();
+}
+
+static void led_on(uint8_t lednr) {
+ if (lednr == 0)
+ LED_BLUE_ON();
+ else if (lednr == 1)
+ LED_GREEN_ON();
+}
+
+static void led_off(uint8_t lednr) {
+ if (lednr == 0)
+ LED_BLUE_OFF();
+ else if (lednr == 1)
+ LED_GREEN_OFF();
+}
+
+static uint8_t led_is_on(uint8_t lednr) {
+ if (lednr == 0)
+ return BBIO_PERIPH(LED_PORT+ODR, BLUE);
+ else if (lednr == 1)
+ return BBIO_PERIPH(LED_PORT+ODR, GREEN);
+ else
+ return 0;
+}
+
+static void ledset(uint8_t lednr, uint8_t what, uint8_t len) {
+
+ led_stat[lednr].mode = what;
+ switch (what) {
+ case PULSE:
+ led_stat[lednr].ontime = len;
+ led_stat[lednr].offtime = 0;
+ led_timer[lednr] = len;
+ led_on(lednr);
+ break;
+ case BLINK1:
+ case BLINK2:
+ if (what == BLINK1)
+ led_stat[lednr].offtime = 100 - len;
+ else
+ led_stat[lednr].offtime = 200 - len;
+ led_stat[lednr].ontime = len;
+ led_timer[lednr] = len;
+ led_on(lednr);
+ break;
+ default:
+ break;
+ }
+}
+
+/*--------------------------------------------------------------------------*/
+
+static volatile uint16_t key_state,
+ key_press, // key press detect
+ key_rpt; // key long press and repeat
+
+
+static uint16_t get_key_press(uint16_t key_mask) {
+ __disable_irq();
+ // read and clear atomic !
+ key_mask &= key_press; // read key(s)
+ key_press ^= key_mask; // clear key(s)
+ __enable_irq();
+ return key_mask;
+}
+
+/*
+static uint16_t get_key_rpt(uint16_t key_mask) {
+ __disable_irq();
+ // read and clear atomic !
+ key_mask &= key_rpt; // read key(s)
+ key_rpt ^= key_mask; // clear key(s)
+ __enable_irq();
+ return key_mask;
+}
+*/
+
+static uint16_t get_key_short(uint16_t key_mask) {
+ __disable_irq();
+ // read key state and key press atomic !
+ return get_key_press(key_state & key_mask);
+}
+
+/*
+static uint16_t get_key_long(uint16_t key_mask) {
+ return get_key_press(get_key_rpt(key_mask));
+}
+*/
+
+static void key_timerproc() {
+ static uint16_t key_in_last, rpt;
+ uint16_t key_in, c;
+
+ key_in = KEY_PORT;
+
+ c = key_in_last & key_in & ~key_state;
+
+// key_state = key_state & key_in_last | (key_state | key_in_last) & key_in;
+// key_state = key_state & key_in | (key_state | key_in) & key_in_last;
+
+ key_state = c | ((key_in_last | key_in) & key_state);
+
+// key_state = (key_state&key_in_last) | (key_state&key_in) | (key_in_last&key_in);
+
+ key_press |= c;
+
+ key_in_last = key_in;
+
+
+ if ((key_state & REPEAT_MASK) == 0) // check repeat function
+ rpt = REPEAT_START;
+ if (--rpt == 0) {
+ rpt = REPEAT_NEXT; // repeat delay
+ key_rpt |= key_state & REPEAT_MASK;
+ }
+
+}
+
+/*--------------------------------------------------------------------------*/
+
+void sys_tick_handler(void)
+{
+ static int_fast8_t tick_10ms = 0;
+ static int_fast16_t count_ms = 0;
+
+ int_fast8_t i;
+
+ ++tick_10ms;
+ if (tick_10ms == 10)
+ {
+ Stat |= S_10MS_TO;
+
+ tick_10ms = 0;
+
+ i = led_timer[0];
+ if (i)
+ led_timer[0] = i - 1;
+ i = led_timer[1];
+ if (i)
+ led_timer[1] = i - 1;
+
+ key_timerproc();
+
+ /* Drive timer procedure of low level disk I/O module */
+ //disk_timerproc();
+ }
+
+ count_ms++;
+ if (count_ms == 1000) {
+ count_ms = 0;
+
+ i = timeout_1s;
+ if (i)
+ timeout_1s = i - 1;
+ }
+}
+
+void rtc_isr(void)
+{
+ /* The interrupt flag isn't cleared by hardware, we have to do it. */
+ rtc_clear_flag(RTC_SEC);
+
+}
+
+/*--------------------------------------------------------------------------*/
+
+void tim3_set(int mode)
+{
+ uint16_t cc_mode;
+
+ cc_mode = TIM_CCMR2_CC4S_OUT;
+
+ TIM3_CR1 = TIM_CR1_CMS_EDGE | TIM_CR1_DIR_UP /*| TIM_CR1_OPM */ ;
+
+ if (mode < 0)
+ cc_mode |= TIM_CCMR2_OC4M_FORCE_LOW;
+ else if (mode == 0)
+ cc_mode |= TIM_CCMR2_OC4M_FORCE_HIGH;
+ else {
+ TIM3_ARR = mode;
+ TIM3_CCR4 = mode/2;
+ cc_mode |= TIM_CCMR2_OC4M_PWM2;
+ }
+
+ TIM3_CCMR2 = cc_mode;
+
+ if (mode > 0)
+ TIM3_CR1 |= TIM_CR1_CEN;
+}
+
+/*--------------------------------------------------------------------------*/
+
+static uint32_t z80_sram_cmp(uint32_t addr, uint32_t length, uint8_t wval, int inc)
+{
+ uint8_t rval;
+ int_fast8_t errors = 0;
+
+ DBG_P(1, "SRAM: Check %#.5x byte... ", length);
+ while (length--) {
+ if ((rval = z80_read(addr)) != wval) {
+ if (errors == 0) {
+ printf("\nSRAM: Address W R\n" \
+ " -------------\n");
+// 12345 00 11
+ }
+ printf(" %.5lx %.2x %.2x\n", addr, wval, rval);
+
+ if (++errors > 16 )
+ break;
+ }
+ addr++;
+ wval += inc;
+ }
+ DBG_P(1, "Done.\n");
+
+ return addr;
+}
+
+#if 0
+static void z80_sram_fill(uint32_t addr, int length, uint8_t startval, int inc)
+{
+ printf("SRAM: Write %#.5x byte... ", length); //fflush(stdout);
+ while (length--) {
+ z80_write(addr, startval);
+ ++addr;
+ startval += inc;
+ }
+ printf("Done.\n");
+}
+
+
+void z80_sram_fill_string(uint32_t addr, int length, const char *text)
+{
+ char c;
+ const char *p = text;
+
+ while (length--) {
+ z80_write(addr++, c = *p++);
+ if (c == 0)
+ p = text;
+ }
+}
+
+
+uint32_t z80_sram_cmp_string(uint32_t addr, int length, const char *text)
+{
+ char c;
+ const char *p = text;
+
+ while (length--) {
+ c = *p++;
+ if (z80_read(addr) != c)
+ break;
+ ++addr;
+ if (c == 0)
+ p = text;
+ }
+ return addr;
+}
+
+const char * const qbfox = "Zhe quick brown fox jumps over the lazy dog!";
+const char * const qbcat = "Zhe quick brown fox jumps over the lazy cat!";
+
+#endif
+
+uint8_t z80_get_byte(uint32_t adr)
+{
+ uint8_t data;
+
+ z80_request_bus();
+ data = z80_read(adr),
+ z80_release_bus();
+
+ return data;
+}
+
+
+/*--------------------------------------------------------------------------*/
+
+static void do_10ms(void)
+{
+ for (uint_fast8_t i = 0; i < 2; i++) {
+ switch (led_stat[i].mode) {
+ case PULSE:
+ if (led_timer[i] == 0) {
+ led_off(i);
+ led_stat[i].mode = NOTHING;
+ }
+ break;
+ case BLINK1:
+ case BLINK2:
+ if (led_timer[i] == 0) {
+ if (led_is_on(i))
+ led_timer[i] = led_stat[i].offtime;
+ else
+ led_timer[i] = led_stat[i].ontime;
+ led_toggle(i);
+ }
+ break;
+ default:
+ break;
+ }
+ }
+}
+
+struct msg_item {
+ uint8_t fct;
+ uint8_t sub_min, sub_max;
+ void (*func)(uint8_t, int, uint8_t *);
+};
+
+uint32_t msg_to_addr(uint8_t *msg)
+{
+ uint32_t addr = msg[0] | (msg[1] << 8) | ((uint32_t)msg[2] << 16);
+
+ return addr;
+
+}
+
+void do_msg_ini_msgfifo(uint8_t subf, int len, uint8_t * msg)
+{
+ (void)subf; (void)len;
+
+ z80_init_msg_fifo(msg_to_addr(msg));
+}
+
+
+void do_msg_ini_memfifo(uint8_t subf, int len, uint8_t * msg)
+{
+ (void)len;
+
+ z80_memfifo_init(subf - 1, msg_to_addr(msg));
+}
+
+
+void do_msg_char_out(uint8_t subf, int len, uint8_t * msg)
+{
+ (void)subf;
+
+ while (len--)
+ putchar(*msg++);
+}
+
+
+const struct msg_item z80_messages[] =
+{
+ { 0, /* fct nr. */
+ 0, 0, /* sub fct nr. from, to */
+ &do_msg_ini_msgfifo},
+ { 0,
+ 1, 2,
+ &do_msg_ini_memfifo},
+ { 1,
+ 1, 1,
+ &do_msg_char_out},
+ { 0xff, /* end mark */
+ 0, 0,
+ 0},
+
+};
+
+
+
+
+void do_message(int len, uint8_t *msg)
+{
+ uint8_t fct, sub_fct;
+ int_fast8_t i = 0;
+
+ if (len >= 2) {
+ fct = *msg++;
+ sub_fct = *msg++;
+ len -= 2;
+
+ while (fct != z80_messages[i].fct)
+ ++i;
+
+ if (z80_messages[i].fct == 0xff) {
+ DBG_P(1, "do_message: Unknown function: %i, %i\n",
+ fct, sub_fct);
+ return; /* TODO: unknown message # */
+ }
+
+ while (fct == z80_messages[i].fct) {
+ if (sub_fct >= z80_messages[i].sub_min && sub_fct <= z80_messages[i].sub_max )
+ break;
+ ++i;
+ }
+
+ if (z80_messages[i].fct != fct) {
+ DBG_P(1, "do_message: Unknown sub function: %i, %i\n",
+ fct, sub_fct);
+ return; /* TODO: unknown message sub# */
+ }
+
+ (z80_messages[i].func)(sub_fct, len, msg);
+
+
+ } else {
+ /* TODO: error */
+ DBG_P(1, "do_message: to few arguments (%i); this shouldn't happen!\n", len);
+ }
+}
+
+
+
+#define CTRBUF_LEN 256
+
+void check_msg_fifo(void)
+{
+ int ch;
+ static int_fast8_t state;
+ static int msglen,idx;
+ static uint8_t buffer[CTRBUF_LEN];
+
+ while (state != 3 && (ch = z80_msg_fifo_getc()) >= 0) {
+ switch (state) {
+ case 0: /* wait for start of message */
+ if (ch == 0x81) {
+ msglen = 0;
+ idx = 0;
+ state = 1;
+ }
+ break;
+ case 1: /* get msg len */
+ if (ch > 0 && ch <= CTRBUF_LEN) {
+ msglen = ch;
+ state = 2;
+ } else
+ state = 0;
+ break;
+ case 2: /* get message */
+ buffer[idx++] = ch;
+ if (idx == msglen)
+ state = 3;
+ break;
+ }
+ }
+
+ if (state == 3) {
+ do_message(msglen, buffer);
+ state = 0;
+ }
+}
+
+
+void z80_load_mem(void)
+{
+ unsigned sec = 0;
+ uint32_t sec_base = hdrom_start;
+
+ DBG_P(1, "Loading z80 memory... \n");
+
+ while (sec < hdrom_sections) {
+ DBG_P(2, " From: 0x%.5lX to: 0x%.5lX (%5li bytes)\n",
+ hdrom_address[sec],
+ hdrom_address[sec]+hdrom_length_of_sections[sec] - 1,
+ hdrom_length_of_sections[sec]);
+
+ z80_write_block((unsigned char *) &hdrom[sec_base], /* src */
+ hdrom_address[sec], /* dest */
+ hdrom_length_of_sections[sec]); /* len */
+ sec_base+=hdrom_length_of_sections[sec];
+ sec++;
+ }
+}
+/*--------------------------------------------------------------------------*/
+
+int main(void)
+{
+ int_fast8_t state = 0;
+ int ch;
+
+ clock_setup();
+ gpio_setup();
+ tim3_setup();
+ setvbuf(stdout, NULL, _IONBF, 0);
+ serial_setup();
+ printf("\n(STM32F100+HD64180)_stamp Tester\n");
+
+ DBG_P(1, "z80_setup_bus... ");
+ z80_setup_msg_fifo();
+ z80_setup_bus();
+ DBG_P(1, "done.\n");
+
+ /*
+ * If the RTC is pre-configured just allow access, don't reconfigure.
+ * Otherwise enable it with the LSE as clock source and 0x7fff as
+ * prescale value.
+ */
+ rtc_auto_awake(LSE, 0x7fff);
+
+ systick_setup();
+
+ DBG_P(1, "Get bus... ");
+ z80_busreq(LOW);
+ z80_reset(HIGH);
+ z80_request_bus();
+ DBG_P(1, "got it!\n");
+
+ z80_memset(0, 0x76, 0x80000);
+ //z80_sram_fill(0, 512 * 1024, 0x76, 0);
+ z80_sram_cmp(0, (uint32_t)512 * 1024, 0x76, 0);
+
+ z80_load_mem();
+ z80_reset(LOW);
+ DBG_P(1, "Bus released!\n");
+ z80_release_bus();
+ z80_reset(HIGH);
+ DBG_P(1, "Reset released!\n");
+
+
+ ledset(0, BLINK1, 50);
+
+ while (1) {
+
+ if (Stat & S_10MS_TO) {
+ Stat &= ~S_10MS_TO;
+ do_10ms();
+ }
+
+ if (get_key_short(KEY0)) {
+ z80_reset_pulse();
+ }
+
+ if ((ch = serial_getc()) >= 0) {
+ switch (state) {
+ case 0:
+ if (ch == ESCCHAR) {
+ state = 1;
+ /* TODO: Timer starten */
+ } else
+ z80_memfifo_putc(fifo_out, ch);
+ break;
+ case 1:
+ switch (ch) {
+
+ case 'h': /* test: green led on */
+ tim3_set(-1);
+ break;
+ case 'l': /* test: green led off */
+ tim3_set(0);
+ break;
+ case 'p': /* test: pulse on led pin */
+ tim3_set(24000000 / 1000000 * 5); /* 5 us */
+ break;
+ case 'r':
+ z80_reset_pulse();
+ break;
+
+ case ESCCHAR:
+ default:
+ z80_memfifo_putc(fifo_out, ch);
+ }
+ state = 0;
+ break;
+ }
+ }
+
+ check_msg_fifo();
+ }
+
+ return 0;
+}
diff --git a/stm32/z80-if.c b/stm32/z80-if.c
new file mode 100644
index 0000000..171fea9
--- /dev/null
+++ b/stm32/z80-if.c
@@ -0,0 +1,731 @@
+/**
+ *
+ * Pin assignments
+ *
+ * | Z180-Sig | STM32-Port |Buffer | Dir | Special Function |
+ * +------------+---------------+-------+-------+-----------------------+
+ * | A0 | A 1 | P | O | |
+ * | A1 | A 2 | P | O | |
+ * | A2 | A 3 | P | O | |
+ * | A3 | A 4 | P | O | |
+ * | A4 | A 5 | P | O | |
+ * | A5 | A 6 | P | O | |
+ * | A6 | A 7 | P | O | |
+ * | A7 | A 8 | | O | |
+ * | A8 | C 0 | P | O | |
+ * | A9 | C 1 | P | O | |
+ * | A10 | C 2 | P | O | |
+ * | A11 | C 3 | P | O | |
+ * | A12 | C 4 | P | O | |
+ * | A13 | C 5 | P | O | |
+ * | A14 | C 6 | | O | |
+ * | A15 | C 7 | | O | |
+ * | A16 | C 10 | | O | |
+ * | A17 | C 11 | | O | |
+ * | A18 | C 12 | | O | |
+ * | D0 | B 8 | | I/O | |
+ * | D1 | B 9 | | I/O | |
+ * | D2 | B 10 | | I/O | |
+ * | D3 | B 11 | | I/O | |
+ * | D4 | B 12 | | I/O | |
+ * | D5 | B 13 | | I/O | |
+ * | D6 | B 14 | | I/O | |
+ * | D7 | B 15 | | I/O | |
+ * | ME | C 13 | P | O | |
+ * | RD | B 0 | P | O | |
+ * | WR | B 1 | P | O | |
+ * | BUSREQ | D 2 | | O | |
+ * | IOCS1 | A 11 | | I | TIM1_CH4 |
+ * | BUSACK | A 12 | | I | |
+ * | HALT | A 12 | | I | |
+ * | NMI | B 7 | | O | |
+ * | RST | B 6 | | O | TIM16_CH1N |
+ * | | | | | |
+ * | | A 9 | | | af1 USART1_TX |
+ * | | A 10 | | | af1 USART1_RX |
+ * | | A 15 | | JTDI | remap SPI1_NSS' |
+ * | | B 3 | | JTDO | remap SPI1_SCK' |
+ * | | B 4 | |NJTRST | remap SPI1_MISO' |
+ * | | B 5 | | | remap SPI1_MOSI' |
+ * | | C 14 | | | af1 OSC32 |
+ * | | C 15 | | | af1 OSC32 |
+
+
+AFIO_MAPR2 =
+AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_ON (frees
+AFIO_MAPR_SPI1_REMAP
+
+ */
+
+/**
+ *
+ * Pin assignments
+ *
+ * | Z180-Sig | STM32-Port | Buffer | Dir |Special Function |
+ * | -------- | ---------- | ------ | --- | --------------- |
+ * | A0 |A 1 |P |O | |
+ * | A1 |A 2 |P |O | |
+ * | A2 |A 3 |P |O | |
+ * | A3 |A 4 |P |O | |
+ * | A4 |A 5 |P |O | |
+ * | A5 |A 6 |P |O | |
+ * | A6 |A 7 |P |O | |
+ * | A7 |A 8 | |O | |
+ * | A8 |C 0 |P |O | |
+ * | A9 |C 1 |P |O | |
+ * | A10 |C 2 |P |O | |
+ * | A11 |C 3 |P |O | |
+ * | A12 |C 4 |P |O | |
+ * | A13 |C 5 |P |O | |
+ * | A14 |C 6 | |O | |
+ * | A15 |C 7 | |O | |
+ * | A16 |C 10 | |O | |
+ * | A17 |C 11 | |O | |
+ * | A18 |C 12 | |O | |
+ * | D0 |B 8 | |I/O | |
+ * | D1 |B 9 | |I/O | |
+ * | D2 |B 10 | |I/O | |
+ * | D3 |B 11 | |I/O | |
+ * | D4 |B 12 | |I/O | |
+ * | D5 |B 13 | |I/O | |
+ * | D6 |B 14 | |I/O | |
+ * | D7 |B 15 | |I/O | |
+ * | ME |C 13 |P |O | |
+ * | RD |B 0 |P |O | |
+ * | WR |B 1 |P |O | |
+ * | BUSREQ |D 2 | |O | |
+ * | IOCS1 |A 11 | |I |TIM1_CH4 |
+ * | BUSACK |A 12 | |I | |
+ * | HALT |A 12 | |I | |
+ * | NMI |B 7 | |O | |
+ * | RST |B 6 | |O |TIM16_CH1N |
+ * | | | | | |
+ * | |A 9 | | |af1 USART1_TX |
+ * | |A 10 | | |af1 USART1_RX |
+ * | |A 15 | |JTDI | remap SPI1_NSS' |
+ * | |B 3 | |JTDO |remap SPI1_SCK' |
+ * | |B 4 | |NJTRST |remap SPI1_MISO' |
+ * | |B 5 | | |remap SPI1_MOSI' |
+ * | |C 14 | | |af1 OSC32 |
+ * | |C 15 | | |af1 OSC32 |
+
+
+AFIO_MAPR2 =
+AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_ON (frees
+AFIO_MAPR_SPI1_REMAP
+
+ */
+
+#include <stdio.h>
+
+
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/rcc.h>
+#include <libopencm3/stm32/timer.h>
+#include <libopencm3/stm32/dma.h>
+#include "debug.h"
+#include "z80-if.h"
+
+
+/* Number of array elements */
+#define NELEMS(x) (sizeof x/sizeof *x)
+
+#define ODR 0x0c
+#define IDR 0x08
+
+#define CONCAT(x,y) x ## y
+#define EVALUATOR(x,y) CONCAT(x,y)
+
+#define GPIO_(X) CONCAT(GPIO, X)
+
+
+
+
+#define P_ME GPIOC
+#define ME 13
+#define P_RD GPIOB
+#define RD 0
+#define P_WR GPIOB
+#define WR 1
+#define P_BUSREQ GPIOD
+#define BUSREQ 2
+#define P_BUSACK GPIOA
+#define BUSACK 12
+//#define P_HALT GPIOA
+//#define HALT 12
+#define P_IOCS1 GPIOA
+#define IOCS1 11
+#define P_NMI GPIOB
+#define NMI 7
+#define P_RST GPIOB
+#define RST 6
+
+#define ADp1_OFS 0
+#define ADp1_WIDTH 8
+#define ADp1_SHIFT 1
+#define ADp1_PORT GPIOA
+
+#define ADp2_OFS ADp1_WIDTH
+#define ADp2_WIDTH 8
+#define ADp2_SHIFT 0
+#define ADp2_PORT GPIOC
+
+#define ADp3_OFS (ADp2_OFS+ADp2_WIDTH)
+#define ADp3_WIDTH 3
+#define ADp3_SHIFT 10
+#define ADp3_PORT GPIOC
+
+#define ADunbuff1_WIDTH 1
+#define ADunbuff1_SHIFT 8
+#define ADunbuff1_PORT GPIOA
+
+#define ADunbuff2_WIDTH 2
+#define ADunbuff2_SHIFT 6
+#define ADunbuff2_PORT GPIOC
+
+#define ADunbuff3_WIDTH 3
+#define ADunbuff3_SHIFT 10
+#define ADunbuff3_PORT GPIOC
+
+#define DB_OFS 0
+#define DB_WIDTH 8
+#define DB_SHIFT 8
+#define DB_PORT GPIOB
+
+#define GPIO_ME GPIO_(ME)
+#define GPIO_RD GPIO_(RD)
+#define GPIO_WR GPIO_(WR)
+#define GPIO_BUSREQ GPIO_(BUSREQ)
+#define GPIO_BUSACK GPIO_(BUSACK)
+//#define GPIO_HALT GPIO_(HALT)
+#define GPIO_IOCS1 GPIO_(IOCS1)
+#define GPIO_NMI GPIO_(NMI)
+#define GPIO_RST GPIO_(RST)
+
+#define Z80_O_ME BBIO_PERIPH(P_ME+ODR, ME)
+#define Z80_O_RD BBIO_PERIPH(P_RD+ODR, RD)
+#define Z80_O_WR BBIO_PERIPH(P_WR+ODR, WR)
+#define Z80_O_BUSREQ BBIO_PERIPH(P_BUSREQ+ODR, BUSREQ)
+#define Z80_O_NMI BBIO_PERIPH(P_NMI+ODR, NMI)
+#define Z80_O_RST BBIO_PERIPH(P_RST+ODR, RST)
+
+#define Z80_I_BUSACK BBIO_PERIPH(P_BUSACK+IDR, BUSACK)
+//#define Z80_I_HALT BBIO_PERIPH(P_HALT+IDR, HALT)
+
+
+#define MASK(n) ((1<<n)-1)
+
+#define IOFIELD_SET(src, ofs, width, shift) \
+ ((((src>>ofs) & MASK(width)) << shift) | ((((~src>>ofs) & MASK(width)) << shift) << 16))
+
+#define IOFIELD_GET(src, width, shift) \
+ ((src>>shift) & MASK(width))
+
+#define CNF_MODE_I_F (GPIO_CNF_INPUT_FLOAT<<2 |GPIO_MODE_INPUT)
+#define CNF_MODE_O_PP (GPIO_CNF_OUTPUT_PUSHPULL<<2 | GPIO_MODE_OUTPUT_10_MHZ)
+
+#define DB_MODE_INPUT ( (CNF_MODE_I_F << (4 * 0)) \
+ | (CNF_MODE_I_F << (4 * 1)) \
+ | (CNF_MODE_I_F << (4 * 2)) \
+ | (CNF_MODE_I_F << (4 * 3)) \
+ | (CNF_MODE_I_F << (4 * 4)) \
+ | (CNF_MODE_I_F << (4 * 5)) \
+ | (CNF_MODE_I_F << (4 * 6)) \
+ | (CNF_MODE_I_F << (4 * 7)))
+
+#define DB_MODE_OUTPUT ( (CNF_MODE_O_PP << (4 * 0)) \
+ | (CNF_MODE_O_PP << (4 * 1)) \
+ | (CNF_MODE_O_PP << (4 * 2)) \
+ | (CNF_MODE_O_PP << (4 * 3)) \
+ | (CNF_MODE_O_PP << (4 * 4)) \
+ | (CNF_MODE_O_PP << (4 * 5)) \
+ | (CNF_MODE_O_PP << (4 * 6)) \
+ | (CNF_MODE_O_PP << (4 * 7)))
+
+
+/*--------------------------------------------------------------------------*/
+
+static void tim16_setup(void)
+{
+ RCC_APB2RSTR |= RCC_APB2RSTR_TIM16RST;
+ RCC_APB2RSTR &= ~RCC_APB2RSTR_TIM16RST;
+
+ TIM16_BDTR = TIM_BDTR_MOE;
+
+ TIM16_CCMR1 = 0
+ | TIM_CCMR1_OC1M_FORCE_LOW
+ | TIM_CCMR1_CC1S_OUT;
+
+ TIM16_CCER = TIM_CCER_CC1NE
+ | TIM_CCER_CC1NP;
+
+ TIM16_ARR = 48; /* default */
+ TIM16_CCR1 = 1; /* */
+}
+
+/*--------------------------------------------------------------------------*/
+
+static void tim16_set(int mode)
+{
+ uint16_t cc_mode;
+
+ cc_mode = TIM_CCMR1_CC1S_OUT;
+
+ TIM16_CR1 = TIM_CR1_OPM;
+
+ if (mode < 0)
+ cc_mode |= TIM_CCMR1_OC1M_FORCE_LOW;
+ else if (mode == 0)
+ cc_mode |= TIM_CCMR1_OC1M_FORCE_HIGH;
+ else {
+ TIM16_ARR = mode;
+ cc_mode |= TIM_CCMR1_OC1M_PWM2;
+ }
+
+ TIM16_CCMR1 = cc_mode;
+
+ if (mode > 0)
+ TIM16_CR1 |= TIM_CR1_CEN;
+}
+
+/*--------------------------------------------------------------------------*/
+
+
+
+/*
+ * A0..A6, A8..A13 are buffered. No need to disable.
+ * A7, A14..A18: set to input.
+ */
+
+static void z80_setup_adrbus_tristate(void)
+{
+#if 0
+ gpio_set_mode(ADunbuff1_PORT, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_FLOAT, MASK(ADunbuff1_WIDTH) << ADunbuff1_SHIFT);
+ gpio_set_mode(ADunbuff2_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT,
+ (MASK(ADunbuff2_WIDTH) << ADunbuff2_SHIFT) | (MASK(ADunbuff3_WIDTH) << ADunbuff3_SHIFT));
+#else
+ GPIO_CRH(GPIOA) = (GPIO_CRH(GPIOA) & ~(0x0f << (4 * 0)))
+ | (CNF_MODE_I_F << (4 * 0));
+ GPIO_CRL(GPIOC) = (GPIO_CRL(GPIOC) & ~((0x0f << (4 * 6)) | (0x0f << (4 * 7))))
+ | ((CNF_MODE_I_F << (4 * 6)) | (CNF_MODE_I_F << (4 * 7)));
+ GPIO_CRH(GPIOC) = (GPIO_CRH(GPIOC) & ~((0x0f << (4*2)) | (0x0f << (4*3)) | (0x0f << (4*4))))
+ | ((CNF_MODE_I_F << (4*2)) | (CNF_MODE_I_F << (4*3)) | (CNF_MODE_I_F << (4*4)));
+#endif
+}
+
+
+static void z80_setup_adrbus_active(void)
+{
+#if 0
+ gpio_set_mode(ADunbuff1_PORT, GPIO_MODE_OUTPUT_10_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, MASK(ADunbuff1_WIDTH) << ADunbuff1_SHIFT);
+ gpio_set_mode(ADunbuff2_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_PUSHPULL,
+ (MASK(ADunbuff2_WIDTH) << ADunbuff2_SHIFT) | (MASK(ADunbuff3_WIDTH) << ADunbuff3_SHIFT));
+#else
+ GPIO_CRH(GPIOA) = (GPIO_CRH(GPIOA) & ~(0x0f << (4 * 0)))
+ | (CNF_MODE_O_PP << (4 * 0));
+ GPIO_CRL(GPIOC) = (GPIO_CRL(GPIOC) & ~((0x0f << (4 * 6)) | (0x0f << (4 * 7))))
+ | ((CNF_MODE_O_PP << (4 * 6)) | (CNF_MODE_O_PP << (4 * 7)));
+ GPIO_CRH(GPIOC) = (GPIO_CRH(GPIOC) & ~((0x0f << (4*2)) | (0x0f << (4*3)) | (0x0f << (4*4))))
+ | ((CNF_MODE_O_PP << (4*2)) | (CNF_MODE_O_PP << (4*3)) | (CNF_MODE_O_PP << (4*4)));
+#endif
+}
+
+
+static void z80_setup_dbus_in(void)
+{
+ GPIO_CRH(DB_PORT) = DB_MODE_INPUT;
+}
+
+static void z80_setup_dbus_out(void)
+{
+ GPIO_CRH(DB_PORT) = DB_MODE_OUTPUT;
+}
+
+
+static void z80_setaddress(uint32_t addr)
+{
+ GPIO_BSRR(ADp1_PORT) = IOFIELD_SET(addr, ADp1_OFS, ADp1_WIDTH, ADp1_SHIFT);
+ GPIO_BSRR(ADp2_PORT) = IOFIELD_SET(addr, ADp2_OFS, ADp2_WIDTH, ADp2_SHIFT);
+ GPIO_BSRR(ADp3_PORT) = IOFIELD_SET(addr, ADp3_OFS, ADp3_WIDTH, ADp3_SHIFT);
+}
+
+void z80_setup_bus(void)
+{
+ tim16_setup();
+
+ gpio_set_mode(P_RST, GPIO_MODE_OUTPUT_10_MHZ,
+ GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_RST);
+ Z80_O_BUSREQ = 1;
+ gpio_set_mode(P_BUSREQ, GPIO_MODE_OUTPUT_10_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO_BUSREQ);
+ Z80_O_NMI = 1;
+ gpio_set_mode(P_NMI, GPIO_MODE_OUTPUT_10_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO_NMI);
+ Z80_O_ME = 1;
+ Z80_O_RD = 1;
+ Z80_O_WR = 1;
+ gpio_set_mode(P_ME, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO_ME);
+ gpio_set_mode(P_RD, GPIO_MODE_OUTPUT_10_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO_RD | GPIO_WR);
+
+ //Z80_O_BUSREQ = 0;
+ //while(Z80_I_BUSACK == 1);
+
+ gpio_set_mode(ADp1_PORT, GPIO_MODE_OUTPUT_10_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, MASK(ADp1_WIDTH) << ADp1_SHIFT);
+ gpio_set_mode(ADp2_PORT, GPIO_MODE_OUTPUT_10_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, MASK(ADp2_WIDTH) << ADp2_SHIFT);
+ gpio_set_mode(ADp3_PORT, GPIO_MODE_OUTPUT_10_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, MASK(ADp3_WIDTH) << ADp3_SHIFT);
+
+ z80_setup_dbus_in();
+}
+
+void z80_request_bus(void)
+{
+ Z80_O_BUSREQ = 0;
+ while(Z80_I_BUSACK == 1);
+ z80_setup_adrbus_active();
+}
+
+void z80_release_bus(void)
+{
+ z80_setup_dbus_in();
+ z80_setup_adrbus_tristate();
+ Z80_O_BUSREQ = 1;
+ while(Z80_I_BUSACK == 0);
+}
+
+void z80_reset(level_t level)
+{
+ int x = level ? -1 : 0;
+
+ tim16_set(x);
+
+// Z80_O_RST = level;
+}
+
+void z80_reset_pulse(void)
+{
+ tim16_set(48);
+}
+
+void z80_busreq(level_t level)
+{
+ Z80_O_BUSREQ = level;
+}
+
+#if 0
+int z80_stat_halt(void)
+{
+ return Z80_I_HALT;
+}
+#endif
+
+void z80_write(uint32_t addr, uint8_t data)
+{
+ z80_setaddress(addr);
+ Z80_O_ME = 0;
+ GPIO_BSRR(DB_PORT) = IOFIELD_SET(data, DB_OFS, DB_WIDTH, DB_SHIFT);
+ z80_setup_dbus_out();
+ Z80_O_WR = 0;
+ Z80_O_WR = 1;
+ Z80_O_ME = 1;
+}
+
+uint8_t z80_read(uint32_t addr)
+{
+ uint8_t data;
+
+ z80_setaddress(addr);
+ Z80_O_ME = 0;
+ z80_setup_dbus_in();
+ Z80_O_RD = 0;
+ Z80_O_RD = 0;
+ data = IOFIELD_GET(GPIO_IDR(DB_PORT),DB_WIDTH, DB_SHIFT);
+ Z80_O_RD = 1;
+ Z80_O_ME = 1;
+
+ return data;
+}
+
+
+void z80_memset(uint32_t addr, uint8_t data, int length)
+{
+ z80_setup_dbus_out();
+ Z80_O_ME = 0;
+ while(length--) {
+ z80_setaddress(addr++);
+ GPIO_BSRR(DB_PORT) = IOFIELD_SET(data, DB_OFS, DB_WIDTH, DB_SHIFT);
+ Z80_O_WR = 0;
+ Z80_O_WR = 1;
+ }
+ Z80_O_ME = 1;
+}
+
+void z80_write_block(uint8_t *src, uint32_t dest, uint32_t length)
+{
+ uint8_t data;
+
+ z80_setup_dbus_out();
+ Z80_O_ME = 0;
+ while(length--) {
+ z80_setaddress(dest++);
+ data = *src++;
+ GPIO_BSRR(DB_PORT) = IOFIELD_SET(data, DB_OFS, DB_WIDTH, DB_SHIFT);
+ Z80_O_WR = 0;
+ Z80_O_WR = 1;
+ }
+ Z80_O_ME = 1;
+}
+
+/*
+ 0179' rx.bs_mask: ds 1 ; (buf_len - 1)
+ 017A' rx.in_idx: ds 1 ;
+ 017B' rx.out_idx: ds 1 ;
+ 017C' rx.buf: ds rx.buf_len ;
+ 018B' rx.buf_end equ $-1 ; last byte (start+len-1)
+
+ 018C' tx.bs_mask: ds 1 ; (buf_len - 1)
+ 018D' tx.in_idx: ds 1 ;
+ 018E' tx.out_idx: ds 1 ;
+ 018F' tx.buf: ds tx.buf_len ;
+ 019E' tx.buf_end equ $-1 ; last byte
+*/
+
+
+typedef struct __attribute__((packed)) {
+ uint8_t mask;
+ uint8_t in_idx;
+ uint8_t out_idx;
+ uint8_t buf[];
+} zfifo_t;
+
+
+
+#define FIFO_BUFSIZE_MASK -3
+#define FIFO_INDEX_IN -2
+#define FIFO_INDEX_OUT -1
+
+
+static struct {
+ uint32_t base;
+ uint8_t idx_out,
+ idx_in,
+ mask;
+ } fifo_dsc[NUM_FIFOS];
+
+
+void z80_memfifo_init(const fifo_t f, uint32_t adr)
+{
+
+DBG_P(2, "z80_memfifo_init: %i, %lx\n", f, adr);
+
+ fifo_dsc[f].base = adr;
+
+ z80_request_bus();
+
+ fifo_dsc[f].mask = z80_read(adr + FIFO_BUFSIZE_MASK);
+ fifo_dsc[f].idx_in = z80_read(adr + FIFO_INDEX_IN);
+ fifo_dsc[f].idx_out = z80_read(adr + FIFO_INDEX_OUT);
+
+ z80_release_bus();
+}
+
+
+int z80_memfifo_is_empty(const fifo_t f)
+{
+ int rc = 1;
+
+ if (fifo_dsc[f].base != 0) {
+
+ uint32_t adr = fifo_dsc[f].base + FIFO_INDEX_IN;
+ uint8_t idx;
+
+ z80_request_bus();
+ idx = z80_read(adr);
+ z80_release_bus();
+ rc = idx == fifo_dsc[f].idx_out;
+ }
+
+ return rc;
+}
+
+int z80_memfifo_is_full(const fifo_t f)
+{
+ int rc = 1;
+
+ if (fifo_dsc[f].base != 0) {
+ z80_request_bus();
+ rc = ((fifo_dsc[f].idx_in + 1) & fifo_dsc[f].mask)
+ == z80_read(fifo_dsc[f].base+FIFO_INDEX_OUT);
+ z80_release_bus();
+ }
+ return rc;
+}
+
+uint8_t z80_memfifo_getc(const fifo_t f)
+{
+ uint8_t rc, idx;
+
+ while (z80_memfifo_is_empty(f))
+ ;
+
+ z80_request_bus();
+ idx = fifo_dsc[f].idx_out;
+ rc = z80_read(fifo_dsc[f].base+idx);
+ fifo_dsc[f].idx_out = ++idx & fifo_dsc[f].mask;
+ z80_write(fifo_dsc[f].base+FIFO_INDEX_OUT, fifo_dsc[f].idx_out);
+ z80_release_bus();
+
+ return rc;
+}
+
+
+void z80_memfifo_putc(fifo_t f, uint8_t val)
+{
+ int idx;
+
+ while (z80_memfifo_is_full(f))
+ ;
+
+ z80_request_bus();
+ idx = fifo_dsc[f].idx_in;
+ z80_write(fifo_dsc[f].base+idx, val);
+ fifo_dsc[f].idx_in = ++idx & fifo_dsc[f].mask;
+ z80_write(fifo_dsc[f].base+FIFO_INDEX_IN, fifo_dsc[f].idx_in);
+ z80_release_bus();
+}
+
+/*--------------------------------------------------------------------------*/
+
+static struct {
+ uint32_t base;
+ //uint8_t idx_out, idx_in;
+ uint16_t count;
+ uint8_t buf[256];
+ } msg_fifo;
+
+/*--------------------------------------------------------------------------*/
+
+#if 0
+
+static void tim1_setup(void)
+{
+ RCC_APB2RSTR |= RCC_APB2RSTR_TIM1RST;
+ RCC_APB2RSTR &= ~RCC_APB2RSTR_TIM1RST;
+
+ TIM1_CR1 = 0;
+
+ TIM1_SMCR = 0
+ /* | TIM_SMCR_ETP */
+ /* | TIM_SMCR_ETF_CK_INT_N_2 */
+ | TIM_SMCR_TS_ETRF
+ | TIM_SMCR_SMS_OFF
+ ;
+
+ TIM1_DIER = TIM_DIER_TDE;
+
+
+ TIM1_CCMR1 = 0
+ | TIM_CCMR1_OC1M_FORCE_LOW
+ | TIM_CCMR1_CC1S_OUT;
+
+ TIM1_SMCR |= TIM_SMCR_SMS_TM;
+}
+
+#endif
+
+/*--------------------------------------------------------------------------*/
+
+static void tim1_ch4_setup(void)
+{
+ /* Reset Timer 1 */
+ RCC_APB2RSTR |= RCC_APB2RSTR_TIM1RST;
+ RCC_APB2RSTR &= ~RCC_APB2RSTR_TIM1RST;
+
+ TIM1_CCMR2 = 0
+ | TIM_CCMR2_CC4S_IN_TI2
+ | TIM_CCMR2_IC4F_OFF
+ | TIM_CCMR2_IC4PSC_OFF;
+
+ TIM1_CCER = 0
+ /* | TIM_CCER_CC4P */
+ | TIM_CCER_CC4E;
+
+ /* Enable DMA for channel 4 */
+ TIM1_DIER = TIM_DIER_CC4DE;
+}
+
+/*--------------------------------------------------------------------------*/
+
+static void dma1_ch4_setup(void)
+{
+ DMA1_CCR4 =
+ DMA_CCR_PL_VERY_HIGH
+ | DMA_CCR_MSIZE_8BIT
+ | DMA_CCR_PSIZE_8BIT
+ | DMA_CCR_MINC
+ | DMA_CCR_CIRC;
+
+ DMA1_CMAR4 = (uint32_t) msg_fifo.buf;
+
+#if (DB_SHIFT == 0) || (DB_SHIFT == 8)
+ DMA1_CPAR4 = DB_PORT + IDR + DB_SHIFT/8;
+#else
+ #error "Databus not byte aligned!"
+#endif
+
+ DMA1_CNDTR4 = NELEMS(msg_fifo.buf);
+// msg_fifo.count = NELEMS(msg_fifo.buf);
+ msg_fifo.count = 0;
+ msg_fifo.base = 0;
+
+ DMA1_CCR4 |= DMA_CCR_EN;
+}
+
+/*--------------------------------------------------------------------------*/
+
+void z80_setup_msg_fifo(void)
+{
+ gpio_set_mode(P_BUSACK, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_FLOAT, GPIO_BUSACK | GPIO_IOCS1);
+
+ tim1_ch4_setup();
+ dma1_ch4_setup();
+}
+
+
+void z80_init_msg_fifo(uint32_t addr)
+{
+
+DBG_P(1, "z80_init_msg_fifo: %lx\n", addr);
+
+ z80_request_bus();
+ z80_write(addr+FIFO_INDEX_OUT, z80_read(addr+FIFO_INDEX_IN));
+ z80_release_bus();
+ msg_fifo.base = addr;
+}
+
+
+int z80_msg_fifo_getc(void)
+{
+ int c = -1;
+
+ if (msg_fifo.count != (NELEMS(msg_fifo.buf) - DMA1_CNDTR4)) {
+ c = msg_fifo.buf[msg_fifo.count];
+ if (++msg_fifo.count == NELEMS(msg_fifo.buf))
+ msg_fifo.count = 0;
+
+ if (msg_fifo.base != 0) {
+ z80_request_bus();
+ z80_write(msg_fifo.base+FIFO_INDEX_OUT, msg_fifo.count);
+ z80_release_bus();
+ }
+ }
+
+ return c;
+}
diff --git a/stm32/z80-if.h b/stm32/z80-if.h
new file mode 100644
index 0000000..d7c030d
--- /dev/null
+++ b/stm32/z80-if.h
@@ -0,0 +1,32 @@
+
+typedef enum {LOW, HIGH} level_t;
+
+//static void z80_setup_adrbus_tristate(void);
+//static void z80_setup_adrbus_active(void);
+//static void z80_setup_dbus_in(void);
+//static void z80_setup_dbus_out(void);
+//static void z80_setaddress(uint32_t addr);
+void z80_setup_bus(void);
+void z80_write(uint32_t addr, uint8_t data);
+uint8_t z80_read(uint32_t addr);
+void z80_request_bus(void);
+void z80_release_bus(void);
+void z80_memset(uint32_t addr, uint8_t data, int length);
+void z80_reset(level_t level);
+void z80_reset_pulse(void);
+void z80_busreq(level_t level);
+void z80_write_block(uint8_t *src, uint32_t dest, uint32_t length);
+int z80_stat_halt(void);
+
+
+typedef enum fifo_t {fifo_in, fifo_out, NUM_FIFOS} fifo_t;
+
+void z80_memfifo_init(const fifo_t f, uint32_t adr);
+int z80_memfifo_is_empty(const fifo_t f);
+int z80_memfifo_is_full(const fifo_t f);
+uint8_t z80_memfifo_getc(const fifo_t f);
+void z80_memfifo_putc(fifo_t f, uint8_t val);
+
+void z80_setup_msg_fifo(void);
+void z80_init_msg_fifo(uint32_t addr);
+int z80_msg_fifo_getc(void);