summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
m---------libopencm30
-rw-r--r--stm32/Rules.mk8
-rw-r--r--stm32/debug.h11
-rw-r--r--stm32/serial.c194
-rw-r--r--stm32/serial.h8
-rw-r--r--stm32/z180-stamp-stm32.c381
-rw-r--r--stm32/z80-if.c140
-rw-r--r--stm32/z80-if.h17
8 files changed, 485 insertions, 274 deletions
diff --git a/libopencm3 b/libopencm3
-Subproject 2faa482669cb5984a87cf2b17bdbf4c8b83c23a
+Subproject 69726cd1a5baf455d247d3e2469e53cd26856c2
diff --git a/stm32/Rules.mk b/stm32/Rules.mk
index 764851b..7811f8b 100644
--- a/stm32/Rules.mk
+++ b/stm32/Rules.mk
@@ -4,11 +4,11 @@ P_BINARY := $(OBJPATH)/$(BINARY)
TARGETS := $(BINARY).elf #$(BINARY).bin
-SRCS := z180-stamp-stm32.c z80-if.c hdrom.c
+SRCS := z180-stamp-stm32.c serial.c z80-if.c hdrom.c
LIBNAME = opencm3_stm32f1
-DEFS = -DSTM32F1
+DEFS = -DSTM32F1 -DDEBUG=2
OPENCM3_DIR := $(TOP)/libopencm3
LDSCRIPT := $(d)/stm32vl-discovery.ld
@@ -20,7 +20,7 @@ STLINK_PORT = :3333
###############################################################################
# Executables
-TOOLCHAINDIR := /usr/local/gcc-arm-none-eabi-4_8-2014q1/bin
+TOOLCHAINDIR := /usr/local/gcc-arm-none-eabi-4_8-2014q2/bin
TOOLCHAIN := $(TOOLCHAINDIR)/arm-none-eabi
CC := $(TOOLCHAIN)-gcc
@@ -83,7 +83,7 @@ LDLIBS += -Wl,--start-group -lc -lgcc -lnosys -Wl,--end-group
###############################################################################
-$(BINARY).elf_DEPS = z180-stamp-stm32.o z80-if.o hdrom.o
+$(BINARY).elf_DEPS = z180-stamp-stm32.o serial.o z80-if.o hdrom.o
$(BINARY).elf_CMD = $(call echo_cmd,LINK $@) $(LD) $(LDFLAGS) $(ARCH_FLAGS) $^ $(LDLIBS) -o $@
.SUFFIXES: .elf .bin .hex .srec .list .map .images
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/z180-stamp-stm32.c b/stm32/z180-stamp-stm32.c
index ce161d8..f55e076 100644
--- a/stm32/z180-stamp-stm32.c
+++ b/stm32/z180-stamp-stm32.c
@@ -1,15 +1,12 @@
/*
*/
-#include <errno.h>
#include <stdio.h>
-#include <unistd.h>
#include <libopencmsis/core_cm3.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/rtc.h>
-#include <libopencm3/stm32/usart.h>
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/timer.h>
@@ -18,13 +15,13 @@
#define IDR 0x08
-
+#include "debug.h"
+#include "serial.h"
#include "z80-if.h"
#include "hdrom.h"
-#define USART_CONSOLE USART1
-int _write(int fd, char *ptr, int len) __attribute__((used));
+#define ESCCHAR ('^'-0x40)
#define S_10MS_TO (1<<0)
@@ -94,7 +91,6 @@ static void clock_setup(void)
USART1
TIM16 (RST-Pin)
TIM1 (IOCS1)
- TODO: USART1 --> USART_CONSOLE
*/
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN
@@ -174,55 +170,6 @@ static void gpio_setup(void)
}
-static void usart_setup(void)
-{
- /* 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 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_mode(USART_CONSOLE, USART_MODE_TX_RX);
- usart_set_parity(USART_CONSOLE, USART_PARITY_NONE);
- usart_set_flow_control(USART_CONSOLE, USART_FLOWCONTROL_NONE);
-
- /* Finally enable the USART. */
- usart_enable(USART_CONSOLE);
-}
-
-/*--------------------------------------------------------------------------*/
-
-/**
- * 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') {
- usart_send_blocking(USART_CONSOLE, '\r');
- }
- usart_send_blocking(USART_CONSOLE, ptr[i]);
- }
- return i;
- }
- errno = EIO;
- return -1;
-}
-
-
/*--------------------------------------------------------------------------*/
void delay_systicks(int ticks)
@@ -317,6 +264,7 @@ static uint16_t get_key_press(uint16_t key_mask) {
return key_mask;
}
+/*
static uint16_t get_key_rpt(uint16_t key_mask) {
__disable_irq();
// read and clear atomic !
@@ -325,6 +273,7 @@ static uint16_t get_key_rpt(uint16_t key_mask) {
__enable_irq();
return key_mask;
}
+*/
static uint16_t get_key_short(uint16_t key_mask) {
__disable_irq();
@@ -365,26 +314,6 @@ static void key_timerproc() {
key_rpt |= key_state & REPEAT_MASK;
}
-
-#if 0
-
-static char ds[30];
-int dsi = 0;
-
-ds[dsi++] = key_state & 1 ? '1' : '0';
-ds[dsi++] = key_in_last & 1 ? '1' : '0';
-ds[dsi++] = key_in & 1 ? '1' : '0';
-ds[dsi++] = ' ';
-
-//ds[dsi++] = key_state & 1 ? '1' : '0';
-//ds[dsi++] = key_in_last & 1 ? '1' : '0';
-
-//ds[dsi++] = ' ';
-//ds[dsi++] = ' ';
-ds[dsi++] = 0;
-puts(ds);
-#endif
-
}
/*--------------------------------------------------------------------------*/
@@ -466,7 +395,7 @@ static uint32_t z80_sram_cmp(uint32_t addr, int length, uint8_t wval, int inc)
uint8_t rval;
int errors = 0;
- printf("SRAM: Check %#.5x byte... ", length); //fflush(stdout);
+ DBG_P(1, "SRAM: Check %#.5x byte... ", length);
while (length--) {
if ((rval = z80_read(addr)) != wval) {
if (errors == 0) {
@@ -482,7 +411,7 @@ static uint32_t z80_sram_cmp(uint32_t addr, int length, uint8_t wval, int inc)
addr++;
wval += inc;
}
- printf("Done.\n");
+ DBG_P(1, "Done.\n");
return addr;
}
@@ -574,28 +503,137 @@ static void do_10ms(void)
}
}
-void wait_for_z80_init_done(void)
+static
+void do_msg_init(int len, uint8_t* msg)
+{
+ uint8_t sub_fct;
+
+ if (len > 0) {
+ len--;
+ switch (sub_fct = *msg++) {
+ case 0:
+ case 1:
+ case 2:
+ if (len == 3) {
+ uint32_t fifoadr = 0;
+ while (len--)
+ fifoadr = (fifoadr << 8) + msg[len];
+ if (sub_fct == 0)
+ z80_init_msg_fifo(fifoadr);
+ else
+ z80_memfifo_init(sub_fct - 1, fifoadr);
+ } else {
+ /* garbage from z180 */
+ }
+ break;
+ default:
+ /* garbage from z180 */
+ break;
+ }
+ }
+}
+
+static
+void do_msg_char(int len, uint8_t* msg)
+{
+ uint8_t sub_fct;
+
+ if (len > 0) {
+ len--;
+ switch (sub_fct = *msg++) {
+ case 1: /* console output */
+ while (len--)
+ putchar(*msg++);
+ break;
+ }
+ }
+}
+
+static
+void do_message(int len, uint8_t *msg)
+{
+ uint8_t sub_fct;
+
+ if (len > 0) {
+ len--;
+ switch (*msg++) {
+ case 0: /* init functions */
+ do_msg_init(len, msg);
+ break;
+ case 1: /* character i/o functions */
+ do_msg_char(len, msg);
+ break;
+ default:
+ /* no more functions definded yet*/
+ break;
+ }
+ } else {
+ /* shoudn't happen */
+ }
+}
+
+
+#define CTRBUF_LEN 20
+
+static void check_msg_fifo(void)
{
- uint8_t buf, out_i, in_i, mask;
- int to;
-
- timeout_1s = 10;
- to = 0;
- while (timeout_1s) {
- if (to != timeout_1s) {
- buf = z80_get_byte(tx_fifo - 0);
- out_i = z80_get_byte(tx_fifo - 1);
- in_i = z80_get_byte(tx_fifo - 2);
- mask = z80_get_byte(tx_fifo - 3);
- printf(" %.2x %.2x %.2x %.2x\n", buf, out_i, in_i, mask);
- to = timeout_1s;
-
- if ((out_i == 0) && (mask == 0x7f))
- timeout_1s = 0;
+ int ch;
+ static int 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)
+{
+
+DBG_P(1, "Loading z80 memory... \n");
+
+ unsigned sec = 0;
+ uint32_t sec_base = hdrom_start;
+
+ 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)
@@ -604,19 +642,20 @@ int main(void)
//uint32_t rc;
//uint8_t startval = 0;
//int count;
- int stat, ch;
- uint8_t c;
+ int state = 0;
+ int ch;
clock_setup();
gpio_setup();
tim3_setup();
setvbuf(stdout, NULL, _IONBF, 0);
- usart_setup();
+ serial_setup();
printf("\n(STM32F100+HD64180)_stamp Tester\n");
- z80_setup_io_infifo();
+ DBG_P(1, "z80_setup_bus... ");
+ z80_setup_msg_fifo();
z80_setup_bus();
- printf("z80_setup_bus done.\n");
+ DBG_P(1, "done.\n");
/*
* If the RTC is pre-configured just allow access, don't reconfigure.
@@ -626,158 +665,74 @@ int main(void)
rtc_auto_awake(LSE, 0x7fff);
systick_setup();
- ///* Setup the RTC interrupt. */
- //nvic_setup();
-
- /* Enable the RTC interrupt to occur off the SEC flag. */
- //rtc_interrupt_enable(RTC_SEC);
- printf("get bus...");
+ DBG_P(1, "Get bus... ");
z80_busreq(LOW);
z80_reset(HIGH);
z80_request_bus();
- printf(" got it!\n");
+ DBG_P(1, "got it!\n");
z80_memset(0, 0x76, 0x80000);
//z80_sram_fill(0, 512 * 1024, 0x76, 0);
z80_sram_cmp(0, 512 * 1024, 0x76, 0);
- z80_write_block((unsigned char *) hdrom, 0, hdrom_length);
+ z80_load_mem();
z80_reset(LOW);
- printf("bus released!\n");
+ DBG_P(1, "Bus released!\n");
z80_release_bus();
z80_reset(HIGH);
- printf(" reset released!\n");
+ DBG_P(1, "Reset released!\n");
- wait_for_z80_init_done();
- z80_memfifo_init();
ledset(0, BLINK1, 50);
while (1) {
-// static int tickstat = 0;
-
+
if (Stat & S_10MS_TO) {
Stat &= ~S_10MS_TO;
do_10ms();
}
-
-// if (get_key_long(KEY0))
-// ledset(1, PULSE, 100);
-
if (get_key_short(KEY0)) {
z80_reset_pulse();
- wait_for_z80_init_done();
- z80_memfifo_init();
}
-
-/*
- switch (tickstat) {
-
+ if ((ch = serial_getc()) >= 0) {
+ switch (state) {
case 0:
- if (BBIO_PERIPH(GPIOA+IDR, 0))
- {
- tickstat = 1;
-
- LED_GREEN_ON();
- LED_GREEN_OFF();
- LED_GREEN_ON();
- delay_systicks(12);
- LED_GREEN_OFF();
- }
+ if (ch == ESCCHAR) {
+ state = 1;
+ /* TODO: Timer starten */
+ } else
+ z80_memfifo_putc(fifo_out, ch);
break;
- default:
- if (!BBIO_PERIPH(GPIOA+IDR, 0))
- tickstat = 0;
- }
-*/
+ case 1:
+ switch (ch) {
- //BBIO_PERIPH(LED_PORT+0x0C, 9) = BBIO_PERIPH(GPIOA+0x08, 0);
-
- //BBIO_PERIPH(LED_PORT+0x0C, 9) = !z80_stat_halt();
-
- //BBIO_PERIPH(LED_PORT+0x0C, 9) = (~key_state & KEY0) != 0;
-
-
-/*
- stat = z80_fifo_is_not_full(rx_fifo);
- if(stat) {
- z80_fifo_putc(rx_fifo, 'y');
- if (++count == 154) {
- putchar('\n');
- putchar('\r');
- count = 0;
- }
-
- }
-*/
-
- stat = usart_get_flag(USART_CONSOLE, USART_SR_RXNE);
- if (stat) {
- c = usart_recv(USART_CONSOLE) & 0xff;
- switch (c) {
- case 'H':
+ case 'h': /* test: green led on */
tim3_set(-1);
break;
- case 'L':
+ case 'l': /* test: green led off */
tim3_set(0);
break;
- case 'P':
- tim3_set(24000000/1000000 * 5); /* 5 us */
+ case 'p': /* test: pulse on led pin */
+ tim3_set(24000000 / 1000000 * 5); /* 5 us */
+ break;
+ case 'r':
+ z80_reset_pulse();
break;
- default:
- z80_memfifo_putc(fifo_out, c);
- }
- }
- if (timeout_1s == 0) {
-
- while (!z80_memfifo_is_empty(fifo_in)) {
-// LED_GREEN_ON();
- c = z80_memfifo_getc(fifo_in);
- putchar(c);
-// LED_GREEN_OFF();
+ case ESCCHAR:
+ default:
+ z80_memfifo_putc(fifo_out, ch);
+ }
+ state = 0;
+ break;
}
-
- timeout_1s = 1;
}
-
- while ((ch = z80_io_infifo_getc()) >= 0) {
- static int linepos;
- if (linepos == 0)
- printf("\n");
- printf(" 0x%.2X ", ch);
- linepos = (linepos + 1) % 16;
- }
+ check_msg_fifo();
}
return 0;
}
-
-#if 0
-
-static char ds[30];
-int dsi = 0;
-
-ds[dsi++] = key_state1 & 1 ? '1' : '0';
-ds[dsi++] = key_in_last & 1 ? '1' : '0';
-ds[dsi++] = key_in & 1 ? '1' : '0';
-ds[dsi++] = ' ';
-ds[dsi++] = key_state1 & 1 ? '1' : '0';
-ds[dsi++] = key_in_last & 1 ? '1' : '0';
-
-ds[dsi++] = ' ';
-ds[dsi++] = ' ';
-ds[dsi++] = key_state & 1 ? '1' : '0';
-ds[dsi++] = ct1 & 1 ? '0' : '1';
-ds[dsi++] = ct0 & 1 ? '0' : '1';
-ds[dsi++] = ' ';
-ds[dsi++] = key_state & 1 ? '1' : '0';
-//ds[dsi++] = '\r';
-//ds[dsi++] = '\n';
-ds[dsi++] = 0;
-puts(ds);
-#endif
diff --git a/stm32/z80-if.c b/stm32/z80-if.c
index a9ce884..409c32a 100644
--- a/stm32/z80-if.c
+++ b/stm32/z80-if.c
@@ -57,13 +57,17 @@ 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)
@@ -433,60 +437,78 @@ void z80_write_block(uint8_t *src, uint32_t dest, uint32_t length)
019E' tx.buf_end equ $-1 ; last byte
*/
-#define fifo_bufsize_mask -3
-#define fifo_index_in -2
-#define fifo_index_out -1
-#if 1
+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[2];
+ } fifo_dsc[NUM_FIFOS];
-void z80_memfifo_init(void)
+
+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[fifo_in].base = tx_fifo;
- fifo_dsc[fifo_in].idx_out = z80_read(tx_fifo+fifo_index_out);
- fifo_dsc[fifo_in].idx_in = z80_read(tx_fifo+fifo_index_in);
- fifo_dsc[fifo_in].mask = z80_read(tx_fifo+fifo_bufsize_mask);
-
- fifo_dsc[fifo_out].base = rx_fifo;
- fifo_dsc[fifo_out].idx_out = z80_read(rx_fifo+fifo_index_out);
- fifo_dsc[fifo_out].idx_in = z80_read(rx_fifo+fifo_index_in);
- fifo_dsc[fifo_out].mask = z80_read(rx_fifo+fifo_bufsize_mask);
+
+ 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();
}
-#endif
-int z80_memfifo_is_empty(fifo_t f)
+
+int z80_memfifo_is_empty(const fifo_t f)
{
- uint32_t adr = fifo_dsc[f].base+fifo_index_in;
- uint8_t idx;
-
- z80_request_bus();
- idx = z80_read(adr);
- z80_release_bus();
+ 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 idx == fifo_dsc[f].idx_out;
+ return rc;
}
-int z80_memfifo_is_full(fifo_t f)
+int z80_memfifo_is_full(const fifo_t f)
{
- int rc;
-
- 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();
+ 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(fifo_t f)
+uint8_t z80_memfifo_getc(const fifo_t f)
{
uint8_t rc, idx;
@@ -497,7 +519,7 @@ uint8_t z80_memfifo_getc(fifo_t f)
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_write(fifo_dsc[f].base+FIFO_INDEX_OUT, fifo_dsc[f].idx_out);
z80_release_bus();
return rc;
@@ -515,23 +537,23 @@ void z80_memfifo_putc(fifo_t f, uint8_t val)
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_write(fifo_dsc[f].base+FIFO_INDEX_IN, fifo_dsc[f].idx_in);
z80_release_bus();
}
/*--------------------------------------------------------------------------*/
-//volatile uint8_t io_infifo[256];
-
static struct {
- uint8_t idx_out,
- idx_in;
+ uint32_t base;
+ //uint8_t idx_out, idx_in;
uint16_t count;
uint8_t buf[256];
- } io_infifo;
+ } msg_fifo;
/*--------------------------------------------------------------------------*/
+#if 0
+
static void tim1_setup(void)
{
RCC_APB2RSTR |= RCC_APB2RSTR_TIM1RST;
@@ -556,6 +578,8 @@ static void tim1_setup(void)
TIM1_SMCR |= TIM_SMCR_SMS_TM;
}
+#endif
+
/*--------------------------------------------------------------------------*/
static void tim1_ch4_setup(void)
@@ -588,7 +612,7 @@ static void dma1_ch4_setup(void)
| DMA_CCR_MINC
| DMA_CCR_CIRC;
- DMA1_CMAR4 = (uint32_t) io_infifo.buf;
+ DMA1_CMAR4 = (uint32_t) msg_fifo.buf;
#if (DB_SHIFT == 0) || (DB_SHIFT == 8)
DMA1_CPAR4 = DB_PORT + IDR + DB_SHIFT/8;
@@ -596,14 +620,17 @@ static void dma1_ch4_setup(void)
#error "Databus not byte aligned!"
#endif
- DMA1_CNDTR4 = io_infifo.count = NELEMS(io_infifo.buf);
+ 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_io_infifo(void)
+void z80_setup_msg_fifo(void)
{
gpio_set_mode(P_BUSACK, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, GPIO_BUSACK | GPIO_IOCS1);
@@ -613,16 +640,33 @@ void z80_setup_io_infifo(void)
}
-int z80_io_infifo_getc(void)
+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 (io_infifo.count != DMA1_CNDTR4) {
- c = io_infifo.buf[NELEMS(io_infifo.buf) - io_infifo.count--];
- if (io_infifo.count == 0)
- io_infifo.count = NELEMS(io_infifo.buf);
+ 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
index 09ef901..d7c030d 100644
--- a/stm32/z80-if.h
+++ b/stm32/z80-if.h
@@ -18,16 +18,15 @@ void z80_busreq(level_t level);
void z80_write_block(uint8_t *src, uint32_t dest, uint32_t length);
int z80_stat_halt(void);
-#define rx_fifo 0x7c0f7
-#define tx_fifo 0x7c11a
-typedef enum {fifo_in, fifo_out} fifo_t;
+typedef enum fifo_t {fifo_in, fifo_out, NUM_FIFOS} fifo_t;
-void z80_memfifo_init(void);
-int z80_memfifo_is_empty(fifo_t f);
-int z80_memfifo_is_full(fifo_t f);
-uint8_t z80_memfifo_getc(fifo_t f);
+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_io_infifo(void);
-int z80_io_infifo_getc(void);
+void z80_setup_msg_fifo(void);
+void z80_init_msg_fifo(uint32_t addr);
+int z80_msg_fifo_getc(void);