From 920ced062eb0f50f26467868cda0d7fb0fd72413 Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Tue, 12 Mar 2013 12:24:10 +0100 Subject: SWLINK: Add variant for the STM8S Discovery board --- src/platforms/stlink/Connector | 7 ++ src/platforms/swlink/Connectors | 19 ++++ src/platforms/swlink/Makefile.inc | 36 +++++++ src/platforms/swlink/Readme | 15 +++ src/platforms/swlink/platform.c | 158 ++++++++++++++++++++++++++++++ src/platforms/swlink/platform.h | 199 ++++++++++++++++++++++++++++++++++++++ src/platforms/swlink/usbdfu.c | 94 ++++++++++++++++++ 7 files changed, 528 insertions(+) create mode 100644 src/platforms/stlink/Connector create mode 100644 src/platforms/swlink/Connectors create mode 100644 src/platforms/swlink/Makefile.inc create mode 100644 src/platforms/swlink/Readme create mode 100644 src/platforms/swlink/platform.c create mode 100644 src/platforms/swlink/platform.h create mode 100644 src/platforms/swlink/usbdfu.c (limited to 'src/platforms') diff --git a/src/platforms/stlink/Connector b/src/platforms/stlink/Connector new file mode 100644 index 0000000..0f6a89c --- /dev/null +++ b/src/platforms/stlink/Connector @@ -0,0 +1,7 @@ +== SWD Connector CN2 -- +1 VDD_TARGET VDD from application +2 SWCLK SWD clock +3 GND Ground +4 SWDIO SWD data input/output +5 NRST RESET of target MCU +6 SWO Reserved diff --git a/src/platforms/swlink/Connectors b/src/platforms/swlink/Connectors new file mode 100644 index 0000000..1e29af7 --- /dev/null +++ b/src/platforms/swlink/Connectors @@ -0,0 +1,19 @@ + CN5 JTAG Conn + -------------- + + JRST - o o - GND + JTDI - o o - JTMS/SWDIO + JTCK/SWCLK - o o - JTDO + o - +3v3 + + + CN7 SWIM Conn + -------------- + + o - VDD - (V_target) - Unconnected/Floating if Jtag-PCB is broken away from STM8-Board + o - USART1_RX - (SWIM_IN) + STM8-Board <-- o - GND + o - USART1_TX - (SWIM_RST) + + | + v \ No newline at end of file diff --git a/src/platforms/swlink/Makefile.inc b/src/platforms/swlink/Makefile.inc new file mode 100644 index 0000000..df0b648 --- /dev/null +++ b/src/platforms/swlink/Makefile.inc @@ -0,0 +1,36 @@ +CROSS_COMPILE ?= arm-none-eabi- +CC = $(CROSS_COMPILE)gcc +OBJCOPY = $(CROSS_COMPILE)objcopy + +CFLAGS += -mcpu=cortex-m3 -mthumb \ + -DSTM32F1 -DDISCOVERY_SWLINK -I../libopencm3/include \ + -I platforms/stm32 +LDFLAGS_BOOT = -lopencm3_stm32f1 -Wl,--defsym,_stack=0x20005000 \ + -Wl,-T,platforms/stm32/stlink.ld -nostartfiles -lc -lnosys \ + -Wl,-Map=mapfile -mthumb -mcpu=cortex-m3 -Wl,-gc-sections \ + -L../libopencm3/lib +LDFLAGS = $(LDFLAGS_BOOT) -Wl,-Ttext=0x8002000 + +VPATH += platforms/stm32 + +SRC += cdcacm.c \ + platform.c \ + usbuart.c \ + +all: blackmagic.bin blackmagic_dfu.bin blackmagic_dfu.hex + +blackmagic.bin: blackmagic + $(OBJCOPY) -O binary $^ $@ + +blackmagic_dfu: usbdfu.o dfucore.o dfu_f1.o + $(CC) $^ -o $@ $(LDFLAGS_BOOT) + +blackmagic_dfu.bin: blackmagic_dfu + $(OBJCOPY) -O binary $^ $@ + +blackmagic_dfu.hex: blackmagic_dfu + $(OBJCOPY) -O ihex $^ $@ + +host_clean: + -rm blackmagic.bin blackmagic_dfu blackmagic_dfu.bin blackmagic_dfu.hex + diff --git a/src/platforms/swlink/Readme b/src/platforms/swlink/Readme new file mode 100644 index 0000000..b4b3c2c --- /dev/null +++ b/src/platforms/swlink/Readme @@ -0,0 +1,15 @@ +Blackmagic for the STM8S Discovery Board +======================================== + +The board is a ST-Link V1 Board, but with access to JTAG pins accessible +on CN5. This allows easy reprogramming and reuse of the JTAG header. +Programmatical it seems indistinguishable from a e.g. STM32VL +Discovery. So here avariant that uses CN5 for JTAG/SWD_TRACESWO and CN7 for +UART. + +Force Bootloader entry is done with shorting CN7 Pin3/4 so PB6 read low while +pulled up momentary by PB6. + +Reuse SWIM Pins for Uart (USART1) +RX: CN7 Pin2 ->SWIM_IN (PB7)/USART1_RX / SWIM_IN(PB9) +TX: CN7 Pin4 -> SWIM_RST_IN(PB6)/USART1_TX diff --git a/src/platforms/swlink/platform.c b/src/platforms/swlink/platform.c new file mode 100644 index 0000000..33d4f12 --- /dev/null +++ b/src/platforms/swlink/platform.c @@ -0,0 +1,158 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2011 Black Sphere Technologies Ltd. + * Written by Gareth McMullin + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program 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 General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +/* This file implements the platform specific functions for the ST-Link + * implementation. + */ + +#include +#include +#include +#include +#include +#include +#include + +#include "platform.h" +#include "jtag_scan.h" +#include + +#include + +uint8_t running_status; +volatile uint32_t timeout_counter; + +jmp_buf fatal_error_jmpbuf; + +int platform_init(void) +{ + uint32_t data; + rcc_clock_setup_in_hse_8mhz_out_72mhz(); + + /* Enable peripherals */ + rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN); + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN); + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN); + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN); + + /* Unmap JTAG Pins so we can reuse as GPIO */ + data = AFIO_MAPR; + data &= ~AFIO_MAPR_SWJ_MASK; + data |= AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF; + AFIO_MAPR = data; + /* Setup JTAG GPIO ports */ + gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_10_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN); + gpio_set_mode(TCK_PORT, GPIO_MODE_OUTPUT_10_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, TCK_PIN); + gpio_set_mode(TDI_PORT, GPIO_MODE_OUTPUT_10_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, TDI_PIN); + + gpio_set_mode(TDO_PORT, GPIO_MODE_INPUT, + GPIO_CNF_INPUT_FLOAT, TDO_PIN); + + gpio_set(NRST_PORT,NRST_PIN); + gpio_set_mode(NRST_PORT, GPIO_MODE_INPUT, + GPIO_CNF_INPUT_PULL_UPDOWN, NRST_PIN); + + gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, led_idle_run); + + /* Remap TIM2 TIM2_REMAP[1] + * TIM2_CH1_ETR -> PA15 (TDI, set as output above) + * TIM2_CH2 -> PB3 (TDO) + */ + data = AFIO_MAPR; + data &= ~AFIO_MAPR_TIM2_REMAP_FULL_REMAP; + data |= AFIO_MAPR_TIM2_REMAP_PARTIAL_REMAP1; + AFIO_MAPR = data; + + /* Setup heartbeat timer */ + systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8); + systick_set_reload(900000); /* Interrupt us at 10 Hz */ + SCB_SHPR(11) &= ~((15 << 4) & 0xff); + SCB_SHPR(11) |= ((14 << 4) & 0xff); + systick_interrupt_enable(); + systick_counter_enable(); + + usbuart_init(); + + SCB_VTOR = 0x2000; // Relocate interrupt vector table here + + cdcacm_init(); + + jtag_scan(NULL); + + return 0; +} + +void platform_delay(uint32_t delay) +{ + timeout_counter = delay; + while(timeout_counter); +} + +void sys_tick_handler(void) +{ + if(running_status) + gpio_toggle(LED_PORT, led_idle_run); + + if(timeout_counter) + timeout_counter--; +} + +const char *morse_msg; + +void morse(const char *msg, char repeat) +{ + (void)repeat; + morse_msg = msg; +} + +const char *platform_target_voltage(void) +{ + return "unknown"; +} + +void disconnect_usb(void) +{ + /* Disconnect USB cable by resetting USB Device and pulling USB_DP low*/ + rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN); + rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN); + rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN); + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN); + gpio_clear(GPIOA, GPIO12); + gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12); +} + +void assert_boot_pin(void) +{ + uint32_t crl = GPIOA_CRL; + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN); + /* Enable Pull on GPIOA1. We don't rely on the external pin + * really pulled, but only on the value of the CNF register + * changed from the reset value + */ + crl &= 0xffffff0f; + crl |= 0x80; + GPIOA_CRL = crl; +} +void setup_vbus_irq(void){}; diff --git a/src/platforms/swlink/platform.h b/src/platforms/swlink/platform.h new file mode 100644 index 0000000..469499f --- /dev/null +++ b/src/platforms/swlink/platform.h @@ -0,0 +1,199 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2011 Black Sphere Technologies Ltd. + * Written by Gareth McMullin + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program 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 General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +/* This file implements the platform specific functions for the STM32 + * implementation. + */ +#ifndef __PLATFORM_H +#define __PLATFORM_H + +#include +#include + +#include +#include + +#include "gdb_packet.h" + +#define INLINE_GPIO +#define CDCACM_PACKET_SIZE 64 +#define BOARD_IDENT "Black Magic Probe (SWLINK), (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")" +#define BOARD_IDENT_DFU "Black Magic (Upgrade), STM8S Discovery, (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")" +#define DFU_IDENT "Black Magic Firmware Upgrade (SWLINK)" +#define DFU_IFACE_STRING "@Internal Flash /0x08000000/8*001Ka,56*001Kg" + +extern usbd_device *usbdev; +#define CDCACM_GDB_ENDPOINT 1 +#define CDCACM_UART_ENDPOINT 3 + +/* Pin mappings: + * + * nTRST = PB1 + * TDI = PA3 + * TMS = PA4 (input for SWDP) + * TCK = PA5 + * TDO = PA6 (input) + * nSRST = PA7 (input) + * + * USB cable pull-up: PA8 + * USB VBUS detect: PB13 -- New on mini design. + * Enable pull up for compatibility. + * Force DFU mode button: PB9 Low + */ + +/* Hardware definitions... */ +#define TMS_PORT GPIOA +#define TCK_PORT GPIOA +#define TDI_PORT GPIOA +#define TDO_PORT GPIOB +#define NRST_PORT GPIOB +#define TMS_PIN GPIO13 +#define TCK_PIN GPIO14 +#define TDI_PIN GPIO15 +#define TDO_PIN GPIO3 +#define NRST_PIN GPIO4 + +#define SWDIO_PORT TMS_PORT +#define SWCLK_PORT TCK_PORT +#define SWDIO_PIN TMS_PIN +#define SWCLK_PIN TCK_PIN + +#define LED_PORT GPIOA +/* Use PC14 for a "dummy" uart led. So we can observere at least with scope*/ +#define LED_PORT_UART GPIOC +#define LED_UART GPIO14 + +#define TMS_SET_MODE() \ + gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ, \ + GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN); +#define SWDIO_MODE_FLOAT() \ + gpio_set_mode(SWDIO_PORT, GPIO_MODE_INPUT, \ + GPIO_CNF_INPUT_FLOAT, SWDIO_PIN); +#define SWDIO_MODE_DRIVE() \ + gpio_set_mode(SWDIO_PORT, GPIO_MODE_OUTPUT_50_MHZ, \ + GPIO_CNF_OUTPUT_PUSHPULL, SWDIO_PIN); + +#define UART_PIN_SETUP() do \ + { \ + AFIO_MAPR |= AFIO_MAPR_USART1_REMAP; \ + gpio_set_mode(USBUSART_PORT, GPIO_MODE_OUTPUT_2_MHZ, \ + GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USBUSART_TX_PIN); \ + } while (0) + +#define USB_DRIVER stm32f103_usb_driver +#define USB_IRQ NVIC_USB_LP_CAN_RX0_IRQ +#define USB_ISR usb_lp_can_rx0_isr +/* Interrupt priorities. Low numbers are high priority. + * For now USART1 preempts USB which may spin while buffer is drained. + * TIM2 is used for traceswo capture and must be highest priority. + */ +#define IRQ_PRI_USB (2 << 4) +#define IRQ_PRI_USBUSART (1 << 4) +#define IRQ_PRI_USB_VBUS (14 << 4) +#define IRQ_PRI_TRACE (0 << 4) + +#define USBUSART USART1 +#define USBUSART_CR1 USART1_CR1 +#define USBUSART_IRQ NVIC_USART1_IRQ +#define USBUSART_APB_ENR RCC_APB2ENR +#define USBUSART_CLK_ENABLE RCC_APB2ENR_USART1EN +#define USBUSART_PORT GPIOB +#define USBUSART_TX_PIN GPIO6 +#define USBUSART_ISR usart1_isr + +#define TRACE_TIM TIM2 +#define TRACE_TIM_CLK_EN() rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM2EN) +#define TRACE_IRQ NVIC_TIM2_IRQ +#define TRACE_ISR tim2_isr +#define TRACE_IC_IN TIM_IC_IN_TI2 +#define TRACE_TRIG_IN TIM_SMCR_TS_IT1FP2 + +#define DEBUG(...) + +extern uint8_t running_status; +extern volatile uint32_t timeout_counter; + +extern jmp_buf fatal_error_jmpbuf; + +extern const char *morse_msg; + +#define gpio_set_val(port, pin, val) do { \ + if(val) \ + gpio_set((port), (pin)); \ + else \ + gpio_clear((port), (pin)); \ +} while(0) + +#define led_idle_run GPIO8 +#define SET_RUN_STATE(state) {running_status = (state);} +#define SET_IDLE_STATE(state) {gpio_set_val(LED_PORT, led_idle_run, state);} + +#define PLATFORM_SET_FATAL_ERROR_RECOVERY() {setjmp(fatal_error_jmpbuf);} +#define PLATFORM_FATAL_ERROR(error) { \ + if(running_status) gdb_putpacketz("X1D"); \ + else gdb_putpacketz("EFF"); \ + running_status = 0; \ + target_list_free(); \ + longjmp(fatal_error_jmpbuf, (error)); \ +} + +int platform_init(void); +void morse(const char *msg, char repeat); +const char *platform_target_voltage(void); +void platform_delay(uint32_t delay); + +/* */ +void cdcacm_init(void); +/* Returns current usb configuration, or 0 if not configured. */ +int cdcacm_get_config(void); +int cdcacm_get_dtr(void); + +/* */ +void uart_usb_buf_drain(uint8_t ep); + +/* Use newlib provided integer only stdio functions */ +#define sscanf siscanf +#define sprintf siprintf +#define vasprintf vasiprintf + +#ifdef INLINE_GPIO +static inline void _gpio_set(u32 gpioport, u16 gpios) +{ + GPIO_BSRR(gpioport) = gpios; +} +#define gpio_set _gpio_set + +static inline void _gpio_clear(u32 gpioport, u16 gpios) +{ + GPIO_BRR(gpioport) = gpios; +} +#define gpio_clear _gpio_clear + +static inline u16 _gpio_get(u32 gpioport, u16 gpios) +{ + return (u16)GPIO_IDR(gpioport) & gpios; +} +#define gpio_get _gpio_get +#endif + +#endif + +void disconnect_usb(void); +void assert_boot_pin(void); diff --git a/src/platforms/swlink/usbdfu.c b/src/platforms/swlink/usbdfu.c new file mode 100644 index 0000000..29c3809 --- /dev/null +++ b/src/platforms/swlink/usbdfu.c @@ -0,0 +1,94 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2013 Gareth McMullin + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program 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 General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +#include +#include +#include +#include +#include + +#include "usbdfu.h" + +void dfu_detach(void) +{ + /* Disconnect USB cable by resetting USB Device + and pulling USB_DP low*/ + rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN); + rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN); + rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN); + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN); + gpio_clear(GPIOA, GPIO12); + gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12); + scb_reset_system(); +} + +int main(void) +{ + /* Check the force bootloader pin*/ + uint16_t pin_b; + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN); + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN); +/* Switch PB5 (SWIM_RST_IN) up */ + gpio_set(GPIOB, GPIO5); + gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, GPIO5); + gpio_set(GPIOB, GPIO5); + pin_b = gpio_get(GPIOB, GPIO6); +/* Check state on PB6 ((SWIM_RST) and release PB5*/ + pin_b = gpio_get(GPIOB, GPIO6); + gpio_set_mode(GPIOB, GPIO_MODE_INPUT, + GPIO_CNF_INPUT_FLOAT, GPIO5); + if(((GPIOA_CRL & 0x40) == 0x40) && pin_b) + dfu_jump_app_if_valid(); + + dfu_protect_enable(); + + rcc_clock_setup_in_hse_8mhz_out_72mhz(); + systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8); + systick_set_reload(900000); + + /* Handle USB disconnect/connect */ + /* Just in case: Disconnect USB cable by resetting USB Device + * and pulling USB_DP low + * Device will reconnect automatically as Pull-Up is hard wired*/ + rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN); + rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN); + rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN); + rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN); + gpio_clear(GPIOA, GPIO12); + gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12); + + /* Handle LED*/ + gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, GPIO8); + + systick_interrupt_enable(); + systick_counter_enable(); + + dfu_init(&stm32f103_usb_driver); + + dfu_main(); +} + +void sys_tick_handler(void) +{ + gpio_toggle(GPIOA, GPIO8); +} -- cgit v1.2.3