Keir Fraser 3 năm trước cách đây
mục cha
commit
cd8571260f

+ 11 - 2
Rules.mk

@@ -1,4 +1,5 @@
-TOOL_PREFIX = arm-none-eabi-
+TOOL_PREFIX = riscv32-unknown-elf-
+#arm-none-eabi-
 CC = $(TOOL_PREFIX)gcc
 OBJCOPY = $(TOOL_PREFIX)objcopy
 LD = $(TOOL_PREFIX)ld
@@ -15,18 +16,26 @@ FLAGS  = -g -Os -nostdlib -std=gnu99 -iquote $(ROOT)/inc
 FLAGS += -Wall -Werror -Wno-format -Wdeclaration-after-statement
 FLAGS += -Wstrict-prototypes -Wredundant-decls -Wnested-externs
 FLAGS += -fno-common -fno-exceptions -fno-strict-aliasing
-FLAGS += -mlittle-endian -mthumb -mfloat-abi=soft
+FLAGS += -mlittle-endian
+#-mthumb -mfloat-abi=soft
 FLAGS += -Wno-unused-value -ffunction-sections
 
 ifeq ($(mcu),stm32f1)
 FLAGS += -mcpu=cortex-m3 -DSTM32F1=1 -DMCU=1
 stm32f1=y
+arch=arm
 else ifeq ($(mcu),stm32f7)
 FLAGS += -mcpu=cortex-m7 -DSTM32F7=7 -DMCU=7
 stm32f7=y
+arch=arm
 else ifeq ($(mcu),at32f4)
 FLAGS += -mcpu=cortex-m4 -DAT32F4=4 -DMCU=4
 at32f4=y
+arch=arm
+else ifeq ($(mcu),gd32vf1)
+FLAGS += -march=rv32imac -DGD32VF1=2 -DMCU=2
+gd32vf1=y
+arch=rv32
 endif
 
 ifneq ($(debug),y)

+ 3 - 0
inc/decls.h

@@ -27,6 +27,9 @@
 #elif MCU == AT32F4
 #include "mcu/at32/f4_regs.h"
 #include "mcu/at32/f4.h"
+#elif MCU == GD32VF1
+#include "mcu/gd32v/f1_regs.h"
+#include "mcu/gd32v/f1.h"
 #endif
 #include "intrinsics.h"
 

+ 12 - 2
inc/intrinsics.h

@@ -27,11 +27,14 @@ struct exception_frame {
 #define likely(x)     __builtin_expect(!!(x),1)
 #define unlikely(x)   __builtin_expect(!!(x),0)
 
+#define barrier() asm volatile ("" ::: "memory")
+#define cpu_relax() asm volatile ("nop" ::: "memory")
+
+#if defined(CORTEX_M3) || defined(CORTEX_M7)
+
 #define illegal() asm volatile (".short 0xde00");
 
-#define barrier() asm volatile ("" ::: "memory")
 #define cpu_sync() asm volatile("dsb; isb" ::: "memory")
-#define cpu_relax() asm volatile ("nop" ::: "memory")
 
 #define sv_call(imm) asm volatile ( "svc %0" : : "i" (imm) )
 
@@ -83,6 +86,13 @@ struct exception_frame {
 /* Cortex initialisation */
 void cortex_init(void);
 
+#elif defined(RISCV)
+
+#define IRQ_save(newpri) 0
+#define IRQ_restore(oldpri) ((void)oldpri)
+
+#endif
+
 #if defined(CORTEX_M7)
 
 /* Cache operations */

+ 20 - 0
inc/mcu/gd32v/f1.h

@@ -0,0 +1,20 @@
+
+#include "../stm32/f1.h"
+
+#undef CORTEX_M3
+#define RISCV 1
+
+#undef FLASH_PAGE_SIZE
+extern unsigned int FLASH_PAGE_SIZE;
+
+/* On reset, SYSCLK=HSI at 8MHz. SYSCLK runs at 1MHz. */
+void early_fatal(int blinks) __attribute__((noreturn));
+#define early_delay_ms(ms) (delay_ticks((ms)*1000))
+#define early_delay_us(us) (delay_ticks((us)*1))
+
+#undef SYSCLK_MHZ
+#define SYSCLK_MHZ 144
+#define AHB_MHZ (SYSCLK_MHZ / 1)  /* 144MHz */
+#define APB1_MHZ (SYSCLK_MHZ / 2) /* 72MHz */
+#define APB2_MHZ (SYSCLK_MHZ / 2) /* 72MHz */
+

+ 2 - 0
inc/mcu/gd32v/f1_regs.h

@@ -0,0 +1,2 @@
+
+#include "../stm32/f1_regs.h"

+ 4 - 4
src/Makefile

@@ -1,15 +1,15 @@
 OBJS += board.o
 OBJS += build_info.o
 OBJS += crc.o
-OBJS += vectors.o
+OBJS += $(arch)_vectors.o
 OBJS += main.o
 OBJS += string.o
-OBJS += cortex.o
+#OBJS += cortex.o
 OBJS += time.o
 OBJS += timer.o
 OBJS += util.o
-OBJS += floppy.o
-OBJS += testmode.o
+#OBJS += floppy.o
+#OBJS += testmode.o
 
 OBJS-$(debug) += console.o
 

+ 2 - 0
src/board.c

@@ -79,6 +79,8 @@ static void gpio_pull_up_pins(GPIO gpio, uint16_t mask)
 #include "mcu/stm32f7/board.c"
 #elif MCU == AT32F4
 #include "mcu/at32f4/board.c"
+#elif MCU == GD32VF1
+#include "mcu/gd32vf1/board.c"
 #endif
 
 void board_init(void)

+ 1 - 0
src/mcu/Makefile

@@ -1,3 +1,4 @@
 SUBDIRS-$(stm32f1) += stm32f1
 SUBDIRS-$(stm32f7) += stm32f7
 SUBDIRS-$(at32f4) += at32f4
+SUBDIRS-$(gd32vf1) += gd32vf1

+ 3 - 0
src/mcu/gd32vf1/Makefile

@@ -0,0 +1,3 @@
+OBJS += stm32.o
+OBJS += fpec.o
+OBJS += testmode.o

+ 161 - 0
src/mcu/gd32vf1/board.c

@@ -0,0 +1,161 @@
+/*
+ * gd32vf1/board.c
+ * 
+ * Board-specific setup and management.
+ * 
+ * Written & released by Keir Fraser <keir.xen@gmail.com>
+ * 
+ * This is free and unencumbered software released into the public domain.
+ * See the file COPYING for more details, or visit <http://unlicense.org>.
+ */
+
+#define gpio_led gpioc
+#define pin_led 13
+
+const static struct pin_mapping _msel_pins_std[] = {
+    { 10, _B, 11 },
+    { 14, _B, 10 },
+    {  0,  0,  0 }
+};
+
+const static struct pin_mapping _msel_pins_f1_plus[] = {
+    { 10, _B, 11 },
+    { 12, _B,  0 },
+    { 14, _B, 10 },
+    { 16, _B,  1 },
+    {  0,  0,  0 }
+};
+
+const static struct pin_mapping _user_pins_std[] = {
+    { 2, _B,  9, _OD },
+    { 0,  0,  0, _OD } };
+const static struct pin_mapping _user_pins_f1_plus[] = {
+    { 2, _B,  9, _PP },
+    { 4, _A,  3, _PP },
+    { 6, _A,  1, _PP },
+    { 0,  0,  0, _PP } };
+const static struct pin_mapping _user_pins_f1_plus_unbuffered[] = {
+    { 2, _B,  9, _OD },
+    { 4, _A,  3, _OD },
+    { 6, _A,  1, _OD },
+    { 0,  0,  0, _OD } };
+
+const static struct board_config _board_config[] = {
+    [F1SM_basic] = {
+        .flippy    = FALSE,
+        .user_pins = _user_pins_std,
+        .msel_pins = _msel_pins_std },
+    [F1SM_plus] = {
+        .flippy    = TRUE,
+        .user_pins = _user_pins_f1_plus,
+        .msel_pins = _msel_pins_f1_plus },
+    [F1SM_plus_unbuffered] = {
+        .flippy    = TRUE,
+        .user_pins = _user_pins_f1_plus_unbuffered,
+        .msel_pins = _msel_pins_f1_plus }
+};
+
+/* Blink the activity LED to indicate fatal error. */
+static void blink_fatal(int blinks)
+{
+    int i;
+    gpio_configure_pin(gpio_led, pin_led, GPO_pushpull(IOSPD_LOW, HIGH));
+    for (;;) {
+        for (i = 0; i < blinks; i++) {
+            gpio_write_pin(gpio_led, pin_led, LOW);
+            delay_ms(150);
+            gpio_write_pin(gpio_led, pin_led, HIGH);
+            delay_ms(150);
+        }
+        delay_ms(2000);
+    }
+}
+
+static void identify_board_config(void)
+{
+    uint16_t low, high;
+    uint8_t id = 0;
+    int i;
+
+    /* Pull PC[15:14] low, and check which are tied HIGH. */
+    for (i = 0; i < 2; i++)
+        gpio_configure_pin(gpioc, 14+i, GPI_pull_down);
+    delay_us(10);
+    high = (gpioc->idr >> 14) & 3;
+
+    /* Pull PC[15:14] high, and check which are tied LOW. */
+    for (i = 0; i < 2; i++)
+        gpio_configure_pin(gpioc, 14+i, GPI_pull_up);
+    delay_us(10);
+    low = (~gpioc->idr >> 14) & 3;
+
+    /* Each PCx pin defines a 'trit': 0=float, 1=low, 2=high. 
+     * We build a 2^3 ID space from the resulting two-trit ID. */
+    for (i = 0; i < 2; i++) {
+        id *= 3;
+        switch ((high&2) | (low>>1&1)) {
+        case 0: break;          /* float = 0 */
+        case 1: id += 1; break; /* LOW   = 1 */
+        case 2: id += 2; break; /* HIGH  = 2 */
+        case 3: blink_fatal(1); /* cannot be tied HIGH *and* LOW! */
+        }
+        high <<= 1;
+        low <<= 1;
+    }
+
+    /* Panic if the ID is unrecognised. */
+    if (id >= ARRAY_SIZE(_board_config))
+        blink_fatal(2);
+
+    gw_info.hw_submodel = id;
+    board_config = &_board_config[id];
+}
+
+static void mcu_board_init(void)
+{
+    uint16_t pu[] = {
+        [_A] = 0xe1fe, /* PA1-8,13-15 */
+        [_B] = 0x0e27, /* PB0-2,5,9-11 */
+        [_C] = 0xffff, /* PC0-15 */
+    };
+    const struct pin_mapping *mpin;
+    const struct pin_mapping *upin;
+
+    identify_board_config();
+
+    /* MSEL pins: do not default these pins to pull-up mode. */
+    for (mpin = board_config->msel_pins; mpin->pin_id != 0; mpin++)
+        pu[mpin->gpio_bank] &= ~(1u << mpin->gpio_pin);
+
+    /* User pins: do not default these pins to pull-up mode. */
+    for (upin = board_config->user_pins; upin->pin_id != 0; upin++)
+        pu[upin->gpio_bank] &= ~(1u << upin->gpio_pin);
+
+    /* Flippy TRK0_DISABLE output: Set inactive (LOW). */
+    if (board_config->flippy) {
+        gpio_configure_pin(gpioa, 2, GPO_pushpull(IOSPD_LOW, LOW));
+        pu[_A] &= ~(1u << 2); /* PA2 */
+    }
+
+    switch (gw_info.hw_submodel) {
+    case F1SM_plus:
+    case F1SM_plus_unbuffered:
+        /* Floppy pin 34 input line is externally pulled up. */
+        pu[_A] &= ~(1u << 8); /* PA8 */
+        break;
+    }
+
+    gpio_pull_up_pins(gpioa, pu[_A]);
+    gpio_pull_up_pins(gpiob, pu[_B]);
+    gpio_pull_up_pins(gpioc, pu[_C]);
+}
+
+/*
+ * Local variables:
+ * mode: C
+ * c-file-style: "Linux"
+ * c-basic-offset: 4
+ * tab-width: 4
+ * indent-tabs-mode: nil
+ * End:
+ */

+ 202 - 0
src/mcu/gd32vf1/floppy.c

@@ -0,0 +1,202 @@
+/*
+ * f1/floppy.c
+ * 
+ * Floppy interface control: STM32F103C8.
+ * 
+ * Written & released by Keir Fraser <keir.xen@gmail.com>
+ * 
+ * This is free and unencumbered software released into the public domain.
+ * See the file COPYING for more details, or visit <http://unlicense.org>.
+ */
+
+#define O_FALSE 1
+#define O_TRUE  0
+
+#define GPO_bus_pp GPO_pushpull(_2MHz,O_FALSE)
+#define AFO_bus_pp AFO_pushpull(_2MHz)
+#define GPO_bus_od GPO_opendrain(_2MHz,O_FALSE)
+#define AFO_bus_od AFO_opendrain(_2MHz)
+static unsigned int GPO_bus;
+static unsigned int AFO_bus;
+static unsigned int GPI_bus;
+
+/* Input pins */
+#define gpio_index  gpiob
+#define pin_index   6 /* PB6 */
+#define gpio_trk0   gpiob
+#define pin_trk0    7 /* PB7 */
+#define gpio_wrprot gpiob
+#define pin_wrprot  8 /* PB8 */
+
+/* Output pins. */
+#define gpio_dir   gpiob
+#define pin_dir    12 /* PB12 */
+#define gpio_step  gpiob
+#define pin_step   13 /* PB13 */
+#define gpio_wgate gpiob
+#define pin_wgate  14 /* PB14 */
+#define gpio_head  gpiob
+#define pin_head   15 /* PB15 */
+
+/* RDATA: Pin B3, Timer 2 Channel 2, DMA1 Channel 7. */
+#define gpio_rdata  gpiob
+#define pin_rdata   3
+#define tim_rdata   (tim2)
+#define dma_rdata   (dma1->ch7)
+
+/* WDATA: Pin B4, Timer 3 Channel 1, DMA1 Channel 3. */
+#define gpio_wdata  gpiob
+#define pin_wdata   4
+#define tim_wdata   (tim3)
+#define dma_wdata   (dma1->ch3)
+
+typedef uint16_t timcnt_t;
+
+#define irq_index 23
+void IRQ_23(void) __attribute__((alias("IRQ_INDEX_changed"))); /* EXTI9_5 */
+
+static unsigned int U_BUF_SZ;
+
+static void floppy_mcu_init(void)
+{
+    const struct pin_mapping *mpin;
+    const struct pin_mapping *upin;
+    unsigned int avail_kb;
+
+    avail_kb = sram_kb - ((((unsigned long)_ebss - 0x20000000) + 1023) >> 10);
+    for (U_BUF_SZ = 128; U_BUF_SZ > avail_kb; U_BUF_SZ >>= 1)
+        continue;
+    U_BUF_SZ <<= 10;
+
+    switch (gw_info.hw_submodel) {
+    case F1SM_basic:
+        /* Determine whether input pins must be internally pulled down. */
+        configure_pin(index, GPI_pull_down);
+        delay_us(10);
+        GPI_bus = (get_index() == LOW) ? GPI_pull_up : GPI_floating;
+        break;
+    case F1SM_plus:
+    case F1SM_plus_unbuffered:
+        GPI_bus = GPI_floating;
+        break;
+    }
+
+    printk("Floppy Inputs: %sternal Pullup\n",
+           (GPI_bus == GPI_pull_up) ? "In" : "Ex");
+
+    /* Remap timers to RDATA/WDATA pins. */
+    afio->mapr |= (AFIO_MAPR_TIM2_REMAP_PARTIAL_1
+                   | AFIO_MAPR_TIM3_REMAP_PARTIAL);
+
+    configure_pin(rdata, GPI_bus);
+
+    /* Configure user-modifiable pins. */
+    for (upin = board_config->user_pins; upin->pin_id != 0; upin++) {
+        gpio_configure_pin(gpio_from_id(upin->gpio_bank), upin->gpio_pin,
+                           upin->push_pull ? GPO_bus_pp : GPO_bus_od);
+    }
+
+    /* Configure the standard output types. */
+    GPO_bus = upin->push_pull ? GPO_bus_pp : GPO_bus_od;
+    AFO_bus = upin->push_pull ? AFO_bus_pp : AFO_bus_od;
+
+    /* Configure SELECT/MOTOR lines. */
+    for (mpin = board_config->msel_pins; mpin->pin_id != 0; mpin++) {
+        gpio_configure_pin(gpio_from_id(mpin->gpio_bank), mpin->gpio_pin,
+                           GPO_bus);
+    }
+
+    /* Set up EXTI mapping for INDEX: PB[15:0] -> EXT[15:0] */
+    afio->exticr1 = afio->exticr2 = afio->exticr3 = afio->exticr4 = 0x1111;
+}
+
+static void rdata_prep(void)
+{
+    /* RDATA Timer setup: 
+     * The counter runs from 0x0000-0xFFFF inclusive at SAMPLE rate.
+     *  
+     * Ch.2 (RDATA) is in Input Capture mode, sampling on every clock and with
+     * no input prescaling or filtering. Samples are captured on the falling 
+     * edge of the input (CCxP=1). DMA is used to copy the sample into a ring
+     * buffer for batch processing in the DMA-completion ISR. */
+    tim_rdata->psc = TIM_PSC-1;
+    tim_rdata->arr = 0xffff;
+    tim_rdata->ccmr1 = TIM_CCMR1_CC2S(TIM_CCS_INPUT_TI1);
+    tim_rdata->dier = TIM_DIER_CC2DE;
+    tim_rdata->cr2 = 0;
+    tim_rdata->egr = TIM_EGR_UG; /* update CNT, PSC, ARR */
+    tim_rdata->sr = 0; /* dummy write */
+
+    /* RDATA DMA setup: From the RDATA Timer's CCRx into a circular buffer. */
+    dma_rdata.par = (uint32_t)(unsigned long)&tim_rdata->ccr2;
+    dma_rdata.cr = (DMA_CR_PL_HIGH |
+                    DMA_CR_MSIZE_16BIT |
+                    DMA_CR_PSIZE_16BIT |
+                    DMA_CR_MINC |
+                    DMA_CR_CIRC |
+                    DMA_CR_DIR_P2M |
+                    DMA_CR_EN);
+
+    tim_rdata->ccer = TIM_CCER_CC2E | TIM_CCER_CC2P;
+}
+
+static void wdata_prep(void)
+{
+    /* WDATA Timer setup:
+     * The counter is incremented at SAMPLE rate. 
+     *  
+     * Ch.1 (WDATA) is in PWM mode 1. It outputs O_TRUE for 400ns and then 
+     * O_FALSE until the counter reloads. By changing the ARR via DMA we alter
+     * the time between (fixed-width) O_TRUE pulses, mimicking floppy drive 
+     * timings. */
+    tim_wdata->psc = TIM_PSC-1;
+    tim_wdata->ccmr1 = (TIM_CCMR1_CC1S(TIM_CCS_OUTPUT) |
+                        TIM_CCMR1_OC1M(TIM_OCM_PWM1));
+    tim_wdata->ccer = TIM_CCER_CC1E | ((O_TRUE==0) ? TIM_CCER_CC1P : 0);
+    tim_wdata->ccr1 = sample_ns(400);
+    tim_wdata->dier = TIM_DIER_UDE;
+    tim_wdata->cr2 = 0;
+}
+
+static void dma_wdata_start(void)
+{
+    dma_wdata.cr = (DMA_CR_PL_HIGH |
+                    DMA_CR_MSIZE_16BIT |
+                    DMA_CR_PSIZE_16BIT |
+                    DMA_CR_MINC |
+                    DMA_CR_CIRC |
+                    DMA_CR_DIR_M2P |
+                    DMA_CR_EN);
+}
+
+static uint8_t mcu_get_floppy_pin(unsigned int pin, uint8_t *p_level)
+{
+    switch (gw_info.hw_submodel) {
+    case F1SM_plus:
+    case F1SM_plus_unbuffered:
+        if (pin == 34) {
+            *p_level = gpio_read_pin(gpioa, 8);
+            return ACK_OKAY;
+        }
+        break;
+    }
+    return ACK_BAD_PIN;
+}
+
+static void flippy_trk0_sensor(bool_t level)
+{
+    if (board_config->flippy) {
+        gpio_write_pin(gpioa, 2, level);
+        delay_us(10);
+    }
+}
+
+/*
+ * Local variables:
+ * mode: C
+ * c-file-style: "Linux"
+ * c-basic-offset: 4
+ * tab-width: 4
+ * indent-tabs-mode: nil
+ * End:
+ */

+ 66 - 0
src/mcu/gd32vf1/fpec.c

@@ -0,0 +1,66 @@
+/*
+ * f1/fpec.c
+ * 
+ * STM32F10x Flash Memory Program/Erase Controller (FPEC).
+ * 
+ * Written & released by Keir Fraser <keir.xen@gmail.com>
+ * 
+ * This is free and unencumbered software released into the public domain.
+ * See the file COPYING for more details, or visit <http://unlicense.org>.
+ */
+
+static void fpec_wait_and_clear(void)
+{
+    while (flash->sr & FLASH_SR_BSY)
+        continue;
+    flash->sr = FLASH_SR_EOP | FLASH_SR_WRPRTERR | FLASH_SR_PGERR;
+    flash->cr = 0;
+}
+
+void fpec_init(void)
+{
+    /* Erases and writes require the HSI oscillator. */
+    rcc->cr |= RCC_CR_HSION;
+    while (!(rcc->cr & RCC_CR_HSIRDY))
+        cpu_relax();
+
+    /* Unlock the FPEC. */
+    if (flash->cr & FLASH_CR_LOCK) {
+        flash->keyr = 0x45670123;
+        flash->keyr = 0xcdef89ab;
+    }
+
+    fpec_wait_and_clear();
+}
+
+void fpec_page_erase(uint32_t flash_address)
+{
+    fpec_wait_and_clear();
+    flash->cr |= FLASH_CR_PER;
+    flash->ar = flash_address;
+    flash->cr |= FLASH_CR_STRT;
+    fpec_wait_and_clear();
+}
+
+void fpec_write(const void *data, unsigned int size, uint32_t flash_address)
+{
+    uint16_t *_f = (uint16_t *)flash_address;
+    const uint16_t *_d = data;
+
+    fpec_wait_and_clear();
+    for (; size != 0; size -= 2) {
+        flash->cr |= FLASH_CR_PG;
+        *_f++ = *_d++; 
+        fpec_wait_and_clear();
+   }
+}
+
+/*
+ * Local variables:
+ * mode: C
+ * c-file-style: "Linux"
+ * c-basic-offset: 4
+ * tab-width: 4
+ * indent-tabs-mode: nil
+ * End:
+ */

+ 116 - 0
src/mcu/gd32vf1/stm32.c

@@ -0,0 +1,116 @@
+/*
+ * f1/stm32.c
+ * 
+ * Core and peripheral registers.
+ * 
+ * Written & released by Keir Fraser <keir.xen@gmail.com>
+ * 
+ * This is free and unencumbered software released into the public domain.
+ * See the file COPYING for more details, or visit <http://unlicense.org>.
+ */
+
+unsigned int flash_kb;
+unsigned int sram_kb;
+
+static void clock_init(void)
+{
+    /* Flash controller: reads require 2 wait states at 72MHz. */
+    flash->acr = FLASH_ACR_PRFTBE | FLASH_ACR_LATENCY(2);
+
+    /* Start up the external oscillator. */
+    rcc->cr |= RCC_CR_HSEON;
+    while (!(rcc->cr & RCC_CR_HSERDY))
+        cpu_relax();
+
+    /* PLLs, scalers, muxes. */
+    rcc->cfgr = (RCC_CFGR_PLLMUL(9) |        /* PLL = 9*8MHz = 72MHz */
+                 RCC_CFGR_PLLSRC_PREDIV1 |
+                 RCC_CFGR_ADCPRE_DIV8 |
+                 RCC_CFGR_PPRE1_DIV2);
+
+    /* Enable and stabilise the PLL. */
+    rcc->cr |= RCC_CR_PLLON;
+    while (!(rcc->cr & RCC_CR_PLLRDY))
+        cpu_relax();
+
+    /* Switch to the externally-driven PLL for system clock. */
+    rcc->cfgr |= RCC_CFGR_SW_PLL;
+    while ((rcc->cfgr & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_PLL)
+        cpu_relax();
+
+    /* Internal oscillator no longer needed. */
+    rcc->cr &= ~RCC_CR_HSION;
+}
+
+static void gpio_init(GPIO gpio)
+{
+    /* Floating Input. Reference Manual states that JTAG pins are in PU/PD
+     * mode at reset, so ensure all PU/PD are disabled. */
+    gpio->crl = gpio->crh = 0x44444444u;
+}
+
+static void peripheral_init(void)
+{
+    /* Enable basic GPIO and AFIO clocks, all timers, and DMA. */
+    rcc->apb1enr = (RCC_APB1ENR_TIM2EN |
+                    RCC_APB1ENR_TIM3EN |
+                    RCC_APB1ENR_TIM4EN);
+    rcc->apb2enr = (RCC_APB2ENR_IOPAEN |
+                    RCC_APB2ENR_IOPBEN |
+                    RCC_APB2ENR_IOPCEN |
+                    RCC_APB2ENR_AFIOEN |
+                    RCC_APB2ENR_TIM1EN);
+    rcc->ahbenr = RCC_AHBENR_DMA1EN;
+
+    /* Turn off serial-wire JTAG and reclaim the GPIOs.
+     * We cannot use SW-DP because we use PA14 for entering firmware-update
+     * mode, and that requires us to disable SW-DP and enable PA14 pull up.
+     * After SW-DP is disabled it seems impossible to re-enable until reset. */
+    afio->mapr = AFIO_MAPR_SWJ_CFG_DISABLED;
+
+    /* All pins in a stable state. */
+    gpio_init(gpioa);
+    gpio_init(gpiob);
+    gpio_init(gpioc);
+}
+
+static void identify_mcu(void)
+{
+    flash_kb = *(volatile uint16_t *)0x1ffff7e0;
+    switch (flash_kb) {
+    case 16: sram_kb =  6; break; /* STM31F103x4 Low Density */
+    case 32: sram_kb = 10; break; /* STM32F103x6 Low Density */
+    default: sram_kb = 20; break; /* STM32F103xx Medium Density */
+    }
+}
+
+void stm32_init(void)
+{
+    cortex_init();
+    identify_mcu();
+    clock_init();
+    peripheral_init();
+    cpu_sync();
+}
+
+void gpio_configure_pin(GPIO gpio, unsigned int pin, unsigned int mode)
+{
+    gpio_write_pin(gpio, pin, mode >> 4);
+    mode &= 0xfu;
+    if (pin >= 8) {
+        pin -= 8;
+        gpio->crh = (gpio->crh & ~(0xfu<<(pin<<2))) | (mode<<(pin<<2));
+    } else {
+        gpio->crl = (gpio->crl & ~(0xfu<<(pin<<2))) | (mode<<(pin<<2));
+    }
+}
+
+/*
+ * Local variables:
+ * mode: C
+ * c-file-style: "Linux"
+ * c-basic-offset: 4
+ * tab-width: 4
+ * indent-tabs-mode: nil
+ * End:
+ */

+ 79 - 0
src/mcu/gd32vf1/testmode.c

@@ -0,0 +1,79 @@
+/*
+ * f1/testmode.c
+ * 
+ * Written & released by Keir Fraser <keir.xen@gmail.com>
+ * 
+ * This is free and unencumbered software released into the public domain.
+ * See the file COPYING for more details, or visit <http://unlicense.org>.
+ */
+
+const struct pin_mapping testmode_in_pins[] = {
+    {  8, _B,  6 },
+    { 26, _B,  7 },
+    { 28, _B,  8 },
+    { 30, _B,  3 },
+    { 34, _A,  8 },
+    {  0,  0,  0 }
+};
+
+const struct pin_mapping testmode_out_pins[] = {
+    { 18, _B, 12 },
+    { 20, _B, 13 },
+    { 22, _B,  4 },
+    { 24, _B, 14 },
+    { 32, _B, 15 },
+    { 33, _A,  2 },
+    {  0,  0,  0 }
+};
+
+void testmode_get_option_bytes(void *buf)
+{
+    memset(buf, 0, 32);
+    memcpy(buf, (void *)0x1ffff800, 16);
+}
+
+#define gpio_wdata  gpiob
+#define pin_wdata   4
+#define tim_wdata   (tim3)
+void testmode_wdat_osc_on(void)
+{
+    tim_wdata->psc = SYSCLK_MHZ/TIME_MHZ-1;
+    tim_wdata->ccmr1 = (TIM_CCMR1_CC1S(TIM_CCS_OUTPUT) |
+                        TIM_CCMR1_OC1M(TIM_OCM_PWM1));
+    tim_wdata->ccer = TIM_CCER_CC1E;
+    tim_wdata->ccr1 = time_us(1);
+    tim_wdata->arr = time_us(2)-1;
+    tim_wdata->dier = TIM_DIER_UDE;
+    tim_wdata->cr2 = 0;
+    tim_wdata->egr = TIM_EGR_UG;
+    tim_wdata->sr = 0;
+    tim_wdata->cr1 = TIM_CR1_CEN;
+    gpio_wdata->crl = gpio_wdata->crl | (8 << (pin_wdata<<2)); /* AFO */
+}
+void testmode_wdat_osc_off(void)
+{
+    gpio_wdata->crl = gpio_wdata->crl & ~(8 << (pin_wdata<<2)); /* GPO */
+    tim_wdata->ccer = 0;
+    tim_wdata->cr1 = 0;
+    tim_wdata->sr = 0;
+}
+
+uint8_t testmode_init(void)
+{
+    switch (gw_info.hw_submodel) {
+    case F1SM_plus:
+    case F1SM_plus_unbuffered:
+        return ACK_OKAY;
+    }
+    return ACK_BAD_COMMAND;
+}
+
+/*
+ * Local variables:
+ * mode: C
+ * c-file-style: "Linux"
+ * c-basic-offset: 4
+ * tab-width: 4
+ * indent-tabs-mode: nil
+ * End:
+ */

+ 42 - 0
src/rv32_vectors.S

@@ -0,0 +1,42 @@
+    
+  .section .vector_table
+
+.global vector_table
+vector_table:
+    /* Top of stack */
+    .word _thread_stacktop
+
+    /* Exceptions (1-15) */
+#define E(x) .word x; .weak x; .set x, EXC_unused;
+    E(EXC_reset)
+    E(EXC_nmi)
+    E(EXC_hard_fault)
+    E(EXC_memory_management_fault)
+    E(EXC_bus_fault)
+    E(EXC_usage_fault)
+    E(EXC_7)
+    E(EXC_8)
+    E(EXC_9)
+    E(EXC_10)
+    E(EXC_sv_call)
+    E(EXC_12)
+    E(EXC_13)
+    E(EXC_pend_sv)
+    E(EXC_systick)
+
+    /* Interrupts/IRQs (0-67) */
+#define I(n) E(IRQ_##n)
+    I( 0) I( 1) I( 2) I( 3) I( 4) I( 5) I( 6) I( 7) I( 8) I( 9)
+    I(10) I(11) I(12) I(13) I(14) I(15) I(16) I(17) I(18) I(19)
+    I(20) I(21) I(22) I(23) I(24) I(25) I(26) I(27) I(28) I(29)
+    I(30) I(31) I(32) I(33) I(34) I(35) I(36) I(37) I(38) I(39)
+    I(40) I(41) I(42) I(43) I(44) I(45) I(46) I(47) I(48) I(49)
+    I(50) I(51) I(52) I(53) I(54) I(55) I(56) I(57) I(58) I(59)
+    I(60) I(61) I(62) I(63) I(64) I(65) I(66) I(67)
+
+    .text
+.global EXC_unused
+EXC_unused:
+    //push {r4, r5, r6, r7, r8, r9, r10, r11, lr}
+    //mov  r0, sp
+    j    EXC_unexpected

+ 6 - 0
src/timer.c

@@ -27,6 +27,12 @@ void IRQ_50(void) __attribute__((alias("IRQ_timer")));
 #define tim tim5 /* 32-bit timer */
 #define tim_bits 32
 #define TIM_CR1_MCUBITS TIM_CR1_PMEN
+#elif MCU == GD32VF1
+void IRQ_50(void) __attribute__((alias("IRQ_timer")));
+#define TIMER_IRQ 50
+#define tim tim1
+#define tim_bits 16
+#define TIM_CR1_MCUBITS 0
 #endif
 
 /* IRQ only on counter overflow, one-time enable. */

+ 10 - 0
src/util.c

@@ -9,10 +9,15 @@
  * See the file COPYING for more details, or visit <http://unlicense.org>.
  */
 
+#if defined(CORTEX_M3) || defined(CORTEX_M7)
+#define FAST_ARM 1
+#endif
+
 void *memset(void *s, int c, size_t n)
 {
     char *p = s;
 
+#ifdef FAST_ARM
     /* Large aligned memset? */
     size_t n32 = n & ~31;
     if (n32 && !((uint32_t)p & 3)) {
@@ -20,6 +25,7 @@ void *memset(void *s, int c, size_t n)
         p += n32;
         n &= 31;
     }
+#endif
 
     /* Remainder/unaligned memset. */
     while (n--)
@@ -32,6 +38,7 @@ void *memcpy(void *dest, const void *src, size_t n)
     char *p = dest;
     const char *q = src;
 
+#ifdef FAST_ARM
     /* Large aligned copy? */
     size_t n32 = n & ~31;
     if (n32 && !(((uint32_t)p | (uint32_t)q) & 3)) {
@@ -40,6 +47,7 @@ void *memcpy(void *dest, const void *src, size_t n)
         q += n32;
         n &= 31;
     }
+#endif
 
     /* Remainder/unaligned copy. */
     while (n--)
@@ -47,6 +55,7 @@ void *memcpy(void *dest, const void *src, size_t n)
     return dest;
 }
 
+#ifdef FAST_ARM
 asm (
 ".global memcpy_fast, memset_fast\n"
 "memcpy_fast:\n"
@@ -75,6 +84,7 @@ asm (
 "    pop   {r4-r10}\n"
 "    bx    lr\n"
     );
+#endif
 
 void *memmove(void *dest, const void *src, size_t n)
 {