diff --git a/UsingSWO b/UsingSWO index e582df53..36517ead 100644 --- a/UsingSWO +++ b/UsingSWO @@ -25,13 +25,13 @@ the it is a pretty long run before it becomes a problem). Note that the baudrate equation means there are only certain speeds available. The highest half dozen are; - -1 4.50 Mbps -2 2.25 Mbps -3 1.50 Mbps -4 1.125 Mbps -5 0.900 Mbps -6 0.750 Mbps +SWO uses USART1(stlink) USART2(swlink) +1 4.50 Mbps 2.25 Mbps +2 2.25 Mbps 1.125 Mbps +3 1.50 Mbps 0.75 Mbps +4 1.125 Mbps 0.5635 Mbps +5 0.900 Mbps 0.45 Mbps +6 0.750 Mbps 0.375 Mbps ...the USART will cope with some timing slip, but it's advisible to stay as close to these values as you can. As the speed comes down the spread between @@ -50,13 +50,14 @@ An example for a STM32F103 for the UART (NRZ) data format that we use; AFIO->MAPR |= (2 << 24); // Disable JTAG to release TRACESWO DBGMCU->CR |= DBGMCU_CR_TRACE_IOEN; // Enable IO trace pins - *((volatile unsigned *)(0xE0040010)) = 31; // Output bits at 72000000/(31+1)=2.25MHz. - *((volatile unsigned *)(0xE00400F0)) = 2; // Use Async mode (1 for RZ/Manchester) - *((volatile unsigned *)(0xE0040304)) = 0; // Disable formatter + TPI->ACPR = 31; // Output bits at 72000000/(31+1)=2.25MHz. + TPI->SPPR = 2; // Use Async mode (1 for RZ/Manchester) + TPI-FFCR = 0; // Disable formatter /* Configure instrumentation trace macroblock */ ITM->LAR = 0xC5ACCE55; - ITM->TCR = 0x00010005; + ITM->TCR = 1 << ITM_TCR_TraceBusID_Pos | ITM_TCR_SYNCENA_Msk | + ITM_TCR_ITMENA_Msk; ITM->TER = 0xFFFFFFFF; // Enable all stimulus ports Code for the STM32L476 might look like: @@ -234,7 +235,7 @@ can pick this up. Success has been had with CP2102 dongles at up to 921600 baud. To use this mode just connect SWO to the RX pin of your dongle, and start -swolisten with parmeters representing the speed and port. An example; +swolisten with parameters representing the speed and port. An example; >./swolisten -p /dev/cu.SLAB_USBtoUART -v -b swo/ -s 921600 @@ -251,4 +252,4 @@ Further information SWO is a wide field. Read e.g. the blogs around SWD on http://shadetail.com/blog/swo-starting-the-steroids/ An open source program suite for SWO under active development is -https://github.com/mubes/orbuculum \ No newline at end of file +https://github.com/mubes/orbuculum diff --git a/scripts/stm32_mem.py b/scripts/stm32_mem.py index 732685c3..805f2481 100755 --- a/scripts/stm32_mem.py +++ b/scripts/stm32_mem.py @@ -79,32 +79,45 @@ def stm32_manifest(dev): sleep(status.bwPollTimeout / 1000.0) if status.bState == dfu.STATE_DFU_MANIFEST: break + def stm32_scan(args, test): devs = dfu.finddevs() + bmp_devs = [] bmp = 0 if not devs: - if test == True: - return + if test == True: + return + print "No DFU devices found!" exit(-1) for dev in devs: - try: - dfudev = dfu.dfu_device(*dev) - except: - return 0 + try: + dfudev = dfu.dfu_device(*dev) + except: + # Exceptions are raised when current user doesn't have permissions + # for the specified USB device, but the device scan needs to + # continue + continue + man = dfudev.handle.getString(dfudev.dev.iManufacturer, 30) - if man == "Black Sphere Technologies": bmp = bmp + 1 - if bmp == 0 : - if test == True: - return + if man == "Black Sphere Technologies": + bmp = bmp + 1 + bmp_devs.append(dev) + + if bmp == 0: + if test == True: + return + print "No compatible device found\n" exit(-1) - if bmp > 1 and not args.serial_target : - if test == True: - return + + if bmp > 1 and not args.serial_target: + if test == True: + return + print "Found multiple devices:\n" - for dev in devs: + for dev in bmp_devs: dfudev = dfu.dfu_device(*dev) man = dfudev.handle.getString(dfudev.dev.iManufacturer, 30) product = dfudev.handle.getString(dfudev.dev.iProduct, 96) @@ -113,25 +126,31 @@ def stm32_scan(args, test): print "Manufacturer:\t %s" % man print "Product:\t %s" % product print "Serial:\t\t %s\n" % serial_no + print "Select device with serial number!" exit (-1) - for dev in devs: + for dev in bmp_devs: dfudev = dfu.dfu_device(*dev) man = dfudev.handle.getString(dfudev.dev.iManufacturer, 30) product = dfudev.handle.getString(dfudev.dev.iProduct, 96) serial_no = dfudev.handle.getString(dfudev.dev.iSerialNumber, 30) if args.serial_target: - if man == "Black Sphere Technologies" and serial_no == args.serial_target: break + if man == "Black Sphere Technologies" and serial_no == args.serial_target: + break else: - if man == "Black Sphere Technologies": break + if man == "Black Sphere Technologies": + break + print "Device ID:\t %04x:%04x" % (dfudev.dev.idVendor, dfudev.dev.idProduct) print "Manufacturer:\t %s" % man print "Product:\t %s" % product print "Serial:\t\t %s" % serial_no - if args.serial_target and serial_no != args.serial_target: + + if args.serial_target and serial_no != args.serial_target: print "Serial number doesn't match!\n" exit(-2) + return dfudev if __name__ == "__main__": diff --git a/src/platforms/hydrabus/Readme.md b/src/platforms/hydrabus/Readme.md index 1eb824bb..60544679 100644 --- a/src/platforms/hydrabus/Readme.md +++ b/src/platforms/hydrabus/Readme.md @@ -27,7 +27,7 @@ make PROBE_HOST=hydrabus How to Flash the firmware with Windows ======================================== * After build: - * 1) Download files from https://github.com/bvernoux/hydrafw/tree/master/update_fw_dfu_usb_hydrafw + * 1) Download files from https://github.com/hydrabus/hydrafw/tree/master/utils/windows_dfu_util * 2) Force the F4 into system bootloader mode by jumpering "BOOT0" to "3V3" and "PB2/BOOT1" to "GND" and reset (RESET button). System bootloader should appear. * 3) Run the command `DfuSeCommand.exe -c --de 0 -d --fn .\src\blackmagic.dfu` diff --git a/src/platforms/swlink/Makefile.inc b/src/platforms/swlink/Makefile.inc index aeee95ac..19941ab5 100644 --- a/src/platforms/swlink/Makefile.inc +++ b/src/platforms/swlink/Makefile.inc @@ -26,13 +26,19 @@ SRC += cdcacm.c \ serialno.c \ timing.c \ timing_stm32.c \ + traceswoasync.c \ + platform_common.c \ -all: blackmagic.bin blackmagic_dfu.bin blackmagic_dfu.hex +all: blackmagic.bin blackmagic_dfu.bin blackmagic_dfu.hex dfu_upgrade.bin dfu_upgrade.hex -blackmagic_dfu: usbdfu.o dfucore.o dfu_f1.o +blackmagic_dfu: usbdfu.o dfucore.o dfu_f1.o platform_common.o @echo " LD $@" $(Q)$(CC) $^ -o $@ $(LDFLAGS_BOOT) +dfu_upgrade: dfu_upgrade.o dfucore.o dfu_f1.o platform_common.o + @echo " LD $@" + $(Q)$(CC) $^ -o $@ $(LDFLAGS) + host_clean: -$(Q)$(RM) blackmagic.bin blackmagic_dfu blackmagic_dfu.bin blackmagic_dfu.hex diff --git a/src/platforms/swlink/README.md b/src/platforms/swlink/README.md new file mode 100644 index 00000000..70856622 --- /dev/null +++ b/src/platforms/swlink/README.md @@ -0,0 +1,72 @@ +# Blackmagic for STM8S Discovery and STM32F103 Minimum System Development Board + +## External connections: + +| Function | PIN | STM8S-DISCO | BLUEPILL | +| ----------- | ----- | ----------- | ----------- | +| JTMS/SWDIO | PA13 | CN5/5 | P2/2 | +| JTCK/SWCLK | PA14 | CN5/4 | P2/3 | +| JTDI | PA15 | CN5/6 | P4/11 (38) | +| JTDO | PB3 | CN5/3 | P4/10 (39) | +| SRST | PB4 | CN5/8 | P4/9 (40) | +| UART1_TX | PB6 | CN7/4 | P4/7 (42) | +| UART1_RX | PB7 | CN7/2 | P4/6 (43) | +| SWO/RX2 | PA3 | NA(*1) | P3/7 (13) | + +*1: Wire JTDO/PB3 (U2/39) to USART2_RX/PA3 (U2/13) to expose SWO for Stlink +on STM8S-Disco on CN5/3 + +### Force Bootloader Entry: + STM8S Discovery: Jumper CN7/4 to CN7/3 to read PB6 low. + Bluepill: Jumper Boot1 to '1' to read PB2 high. + +### References: +[STM8S UM0817 User manual + ](https://www.st.com/resource/en/user_manual/cd00250600.pdf) + +[Blue Pill Schematics 1 + ](https://jeelabs.org/img/2016/STM32F103C8T6-DEV-BOARD-SCH.pdf) : + Use first number! + +[Blue Pill Schematics 2 + ](https://wiki.stm32duino.com/images/a/ae/Bluepillpinout.gif) : + Use second number! + +Distinguish boards by checking the SWIM_IN connection PB9/PB10 seen on +STM8S Discovery. + +## STM8S Discovery + +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 a variant that uses CN5 for JTAG/SWD and CN7 for +UART. + +Force Bootloader entry is done with shorting CN7 Pin3/4 so PB6 read low while +pulled up momentary by PB6. As PB6 is USBUART TX, this pin is idle +high. Setting the jumper while BMP is running means shorting the GPIO with +output high to ground. Do not do that for extended periods. Un- and repower +soon after setting the jump. Best is to short only when unplugged. + +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 + +## STM32F103 Minimum System Development Board (aka Blue Pill) + +This board has the SWD pins of the onboard F103 accessible on one side. +Reuse these pins. There are also jumpers for BOOT0 and BOOT1(PB2). Reuse +Boot1 as "Force Bootloader entry" jumpered high when booting. Boot1 +has 100 k Ohm between MCU and header pin and can not be used as output. + +All other port pins are have header access with headers not yet soldered. + +This platform can be used for any STM32F103x[8|B] board when JTAG/SWD are +accessible, with the LED depending on actual board layout routed to some +wrong pin and force boot not working. + +## Other STM32F103x[8|B] boards +If the needed JTAG connections are accessible, you can use this swlink variant. +Depending on board layout, LED and force bootloader entry may be routed to +wrong pins. diff --git a/src/platforms/swlink/Readme b/src/platforms/swlink/Readme deleted file mode 100644 index b4b3c2ce..00000000 --- a/src/platforms/swlink/Readme +++ /dev/null @@ -1,15 +0,0 @@ -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/dfu_upgrade.c b/src/platforms/swlink/dfu_upgrade.c new file mode 100644 index 00000000..c34123a7 --- /dev/null +++ b/src/platforms/swlink/dfu_upgrade.c @@ -0,0 +1,68 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2018 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de) + * + * 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" +#include "general.h" +#include "platform.h" + +uint32_t app_address = 0x08000000; +extern uint32_t _stack; +static uint32_t rev; + +void dfu_detach(void) +{ + platform_request_boot(); + scb_reset_core(); +} + +int main(void) +{ + rev = detect_rev(); + rcc_clock_setup_in_hse_8mhz_out_72mhz(); + systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); + systick_set_reload(900000); + + dfu_protect(UPD_MODE); + + systick_interrupt_enable(); + systick_counter_enable(); + + dfu_init(&st_usbfs_v1_usb_driver, UPD_MODE); + + dfu_main(); +} + +void dfu_event(void) +{ +} + +void sys_tick_handler(void) +{ + if (rev == 0) { + gpio_toggle(GPIOA, GPIO8); + } else { + gpio_toggle(GPIOC, GPIO13); + } +} diff --git a/src/platforms/swlink/platform.c b/src/platforms/swlink/platform.c index 91150858..42dfd0b8 100644 --- a/src/platforms/swlink/platform.c +++ b/src/platforms/swlink/platform.c @@ -18,8 +18,9 @@ * along with this program. If not, see . */ -/* This file implements the platform specific functions for the ST-Link - * implementation. +/* This file implements the platform specific functions for ST-Link + * on the STM8S discovery and STM32F103 Minimum System Development Board, also + * known as bluepill. */ #include "general.h" @@ -34,6 +35,17 @@ #include #include +uint32_t led_error_port; +uint16_t led_error_pin; +static uint8_t rev; + +static void adc_init(void); + +int platform_hwversion(void) +{ + return rev; +} + void platform_init(void) { uint32_t data; @@ -44,10 +56,8 @@ void platform_init(void) #endif rcc_clock_setup_in_hse_8mhz_out_72mhz(); + rev = detect_rev(); /* Enable peripherals */ - rcc_periph_clock_enable(RCC_USB); - rcc_periph_clock_enable(RCC_GPIOA); - rcc_periph_clock_enable(RCC_GPIOB); rcc_periph_clock_enable(RCC_AFIO); rcc_periph_clock_enable(RCC_CRC); @@ -67,12 +77,24 @@ void platform_init(void) 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); + switch (rev) { + case 0: + /* LED GPIO already set in detect_rev()*/ + led_error_port = GPIOA; + led_error_pin = GPIO8; + adc_init(); + break; + case 1: + led_error_port = GPIOC; + led_error_pin = GPIO13; + /* Enable MCO Out on PA8*/ + RCC_CFGR &= ~(0xf << 24); + RCC_CFGR |= (RCC_CFGR_MCO_HSE << 24); + gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ, + GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO8); + break; + } + platform_srst_set_val(false); /* Remap TIM2 TIM2_REMAP[1] * TIM2_CH1_ETR -> PA15 (TDI, set as output above) @@ -95,33 +117,80 @@ void platform_init(void) usbuart_init(); } -void platform_srst_set_val(bool assert) { (void)assert; } -bool platform_srst_get_val(void) { return false; } +void platform_srst_set_val(bool assert) +{ + /* We reuse JSRST as SRST.*/ + if (assert) { + gpio_set_mode(JRST_PORT, GPIO_MODE_OUTPUT_50_MHZ, + GPIO_CNF_OUTPUT_OPENDRAIN, JRST_PIN); + /* Wait until requested value is active.*/ + while (gpio_get(JRST_PORT, JRST_PIN)) + gpio_clear(JRST_PORT, JRST_PIN); + } else { + gpio_set_mode(JRST_PORT, GPIO_MODE_INPUT, + GPIO_CNF_INPUT_PULL_UPDOWN, JRST_PIN); + /* Wait until requested value is active.*/ + while (!gpio_get(JRST_PORT, JRST_PIN)) + gpio_set(JRST_PORT, JRST_PIN); + } +} + +bool platform_srst_get_val(void) +{ + return gpio_get(JRST_PORT, JRST_PIN) == 0; +} + +static void adc_init(void) +{ + rcc_periph_clock_enable(RCC_ADC1); + /* PA0 measures CN7 Pin 1 VDD divided by two.*/ + gpio_set_mode(GPIOA, GPIO_MODE_INPUT, + GPIO_CNF_INPUT_ANALOG, GPIO0); + adc_power_off(ADC1); + adc_disable_scan_mode(ADC1); + adc_set_single_conversion_mode(ADC1); + adc_disable_external_trigger_regular(ADC1); + adc_set_right_aligned(ADC1); + adc_set_sample_time_on_all_channels(ADC1, ADC_SMPR_SMP_28DOT5CYC); + + adc_power_on(ADC1); + + /* Wait for ADC starting up. */ + for (int i = 0; i < 800000; i++) /* Wait a bit. */ + __asm__("nop"); + + adc_reset_calibration(ADC1); + adc_calibrate(ADC1); +} const char *platform_target_voltage(void) { - return "unknown"; + static char ret[] = "0.0V"; + const uint8_t channel = 0; + switch (rev) { + case 0: + adc_set_regular_sequence(ADC1, 1, (uint8_t*)&channel); + adc_start_conversion_direct(ADC1); + /* Wait for end of conversion. */ + while (!adc_eoc(ADC1)); + /* Referencevoltage is 3.3 Volt, measured voltage is half of + * actual voltag. */ + uint32_t val_in_100mV = (adc_read_regular(ADC1) * 33 * 2) / 4096; + ret[0] = '0' + val_in_100mV / 10; + ret[2] = '0' + val_in_100mV % 10; + return ret; + } + return "ABSENT!"; } -void platform_request_boot(void) +void set_idle_state(int state) { - /* Disconnect USB cable by resetting USB Device and pulling USB_DP low*/ - rcc_periph_reset_pulse(RST_USB); - rcc_periph_clock_enable(RCC_USB); - rcc_periph_clock_enable(RCC_GPIOA); - gpio_clear(GPIOA, GPIO12); - gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12); - - /* Assert bootloader pin */ - uint32_t crl = GPIOA_CRL; - rcc_periph_clock_enable(RCC_GPIOA); - /* 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; + switch (rev) { + case 0: + gpio_set_val(GPIOA, GPIO8, state); + break; + case 1: + gpio_set_val(GPIOC, GPIO13, (!state)); + break; + } } - diff --git a/src/platforms/swlink/platform.h b/src/platforms/swlink/platform.h index 436dd247..bbccac9f 100644 --- a/src/platforms/swlink/platform.h +++ b/src/platforms/swlink/platform.h @@ -3,6 +3,7 @@ * * Copyright (C) 2011 Black Sphere Technologies Ltd. * Written by Gareth McMullin + * Copyright (C) 2018 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de) * * 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 @@ -29,35 +30,41 @@ #include "timing_stm32.h" #include "version.h" -#define BOARD_IDENT "Black Magic Probe (SWLINK), (Firmware " FIRMWARE_VERSION ")" -#define BOARD_IDENT_DFU "Black Magic (Upgrade), STM8S Discovery, (Firmware " FIRMWARE_VERSION ")" -#define BOARD_IDENT_UPD "Black Magic (DFU Upgrade), STM8S Discovery, (Firmware " FIRMWARE_VERSION ")" -#define DFU_IDENT "Black Magic Firmware Upgrade (SWLINK)" -#define UPD_IFACE_STRING "@Internal Flash /0x08000000/8*001Kg" +#ifdef ENABLE_DEBUG +# define PLATFORM_HAS_DEBUG +# define USBUART_DEBUG +#endif + +#define BOARD_IDENT "Black Magic Probe (SWLINK), (Firmware " FIRMWARE_VERSION ")" +#define BOARD_IDENT_DFU "Black Magic (Upgrade), SWLINK, (Firmware " FIRMWARE_VERSION ")" +#define BOARD_IDENT_UPD "Black Magic (DFU Upgrade), SWLINK, (Firmware " FIRMWARE_VERSION ")" +#define DFU_IDENT "Black Magic Firmware Upgrade (SWLINK)" +#define UPD_IFACE_STRING "@Internal Flash /0x08000000/8*001Kg" /* Hardware definitions... */ #define TMS_PORT GPIOA #define TCK_PORT GPIOA #define TDI_PORT GPIOA #define TDO_PORT GPIOB -#define NRST_PORT GPIOB +#define JRST_PORT GPIOB #define TMS_PIN GPIO13 #define TCK_PIN GPIO14 #define TDI_PIN GPIO15 #define TDO_PIN GPIO3 -#define NRST_PIN GPIO4 +#define JRST_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 -#define LED_IDLE_RUN GPIO8 /* 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 PLATFORM_HAS_TRACESWO 1 +#define NUM_TRACE_PACKETS (128) /* This is an 8K buffer */ + # define SWD_CR GPIO_CRH(SWDIO_PORT) # define SWD_CR_MULT (1 << ((13 - 8) << 2)) @@ -93,7 +100,7 @@ #define IRQ_PRI_USBUSART (1 << 4) #define IRQ_PRI_USBUSART_TIM (3 << 4) #define IRQ_PRI_USB_VBUS (14 << 4) -#define IRQ_PRI_TRACE (0 << 4) +#define IRQ_PRI_SWO_DMA (0 << 4) #define USBUSART USART1 #define USBUSART_CR1 USART1_CR1 @@ -115,8 +122,6 @@ #define TRACE_TRIG_IN TIM_SMCR_TS_IT1FP2 #ifdef ENABLE_DEBUG -# define PLATFORM_HAS_DEBUG -# define USBUART_DEBUG extern bool debug_bmp; int usbuart_debug_write(const char *buf, size_t len); # define DEBUG printf @@ -124,14 +129,29 @@ int usbuart_debug_write(const char *buf, size_t len); # define DEBUG(...) #endif -#define SET_RUN_STATE(state) {running_status = (state);} -#define SET_IDLE_STATE(state) {gpio_set_val(LED_PORT, LED_IDLE_RUN, state);} -#define SET_ERROR_STATE(x) +/* On F103, only USART1 is on AHB2 and can reach 4.5 MBaud at 72 MHz. + * USART1 is already used. sp maximum speed is 2.25 MBaud. */ +#define SWO_UART USART2 +#define SWO_UART_DR USART2_DR +#define SWO_UART_CLK RCC_USART2 +#define SWO_UART_PORT GPIOA +#define SWO_UART_RX_PIN GPIO3 -static inline int platform_hwversion(void) -{ - return 0; -} +/* This DMA channel is set by the USART in use */ +#define SWO_DMA_BUS DMA1 +#define SWO_DMA_CLK RCC_DMA1 +#define SWO_DMA_CHAN DMA_CHANNEL6 +#define SWO_DMA_IRQ NVIC_DMA1_CHANNEL6_IRQ +#define SWO_DMA_ISR(x) dma1_channel6_isr(x) + +#define LED_PORT GPIOC +#define LED_IDLE_RUN GPIO15 +#define SET_RUN_STATE(state) +#define SET_ERROR_STATE(state) +extern void set_idle_state(int state); +#define SET_IDLE_STATE(state) set_idle_state(state) + +extern uint8_t detect_rev(void); /* Use newlib provided integer only stdio functions */ #define sscanf siscanf diff --git a/src/platforms/swlink/platform_common.c b/src/platforms/swlink/platform_common.c new file mode 100644 index 00000000..e5c08e59 --- /dev/null +++ b/src/platforms/swlink/platform_common.c @@ -0,0 +1,89 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2018 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de) + * + * 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 + +uint8_t detect_rev() +{ + /* Test connectivity between PB9 and PB10 needed for + * original ST software to implement SWIM. + * + * Return 0 for Stlink on STM8S Disco and 1 for Bluepill + */ + uint8_t rev = 0; + /* Enable Peripherals used by both debugger and DFU.*/ + rcc_periph_clock_enable(RCC_GPIOA); + rcc_periph_clock_enable(RCC_GPIOB); + rcc_periph_clock_enable(RCC_USB); + gpio_set_mode(GPIOB, GPIO_MODE_INPUT, + GPIO_CNF_INPUT_PULL_UPDOWN, GPIO9); + gpio_set(GPIOB, GPIO9); + gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, GPIO10); + while (!gpio_get(GPIOB, GPIO10)) + gpio_set(GPIOB, GPIO10); + while (gpio_get(GPIOB, GPIO10)) + gpio_clear(GPIOB, GPIO10); + /* Read PB9 as soon as we read PB10 low.*/ + if (gpio_get(GPIOB, GPIO9)) + rev = 1; + /* Release PB9/10 */ + gpio_set_mode(GPIOB, GPIO_MODE_INPUT, + GPIO_CNF_INPUT_FLOAT, GPIO9 | GPIO10); + gpio_set(GPIOB, GPIO9); + switch (rev) { + case 0: + gpio_clear(GPIOA, GPIO8); + gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, GPIO8); + break; + case 1: + rcc_periph_clock_enable(RCC_GPIOC); + gpio_set(GPIOC, GPIO13); /* LED on Blupill is active low!*/ + gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, GPIO13); + break; + } + /* Disconnect USB after reset: + * Pull USB_DP low. Device will reconnect automatically + * when USB is set up later, as Pull-Up is hard wired*/ + gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12); + gpio_clear(GPIOA, GPIO12); + rcc_periph_reset_pulse(RST_USB); + rcc_periph_clock_enable(RCC_USB); + + return rev; +} + +void platform_request_boot(void) +{ + uint32_t crl = GPIOA_CRL; + /* Assert bootloader marker. + * 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; + SCB_VTOR = 0; +} diff --git a/src/platforms/swlink/usbdfu.c b/src/platforms/swlink/usbdfu.c index daf73f32..527ad44c 100644 --- a/src/platforms/swlink/usbdfu.c +++ b/src/platforms/swlink/usbdfu.c @@ -24,8 +24,10 @@ #include #include "usbdfu.h" +#include "platform.h" uint32_t app_address = 0x08002000; +uint32_t rev; void dfu_detach(void) { @@ -43,20 +45,34 @@ void dfu_detach(void) int main(void) { /* Check the force bootloader pin*/ - uint16_t pin_b; - rcc_periph_clock_enable(RCC_GPIOA); - rcc_periph_clock_enable(RCC_GPIOB); -/* 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) + bool normal_boot = 0; + rev = detect_rev(); + switch (rev) { + case 0: + /* For Stlink on STM8S check that CN7 PIN 4 RESET# is + * forced to GND, Jumper CN7 PIN3/4 is plugged). + * Switch PB5 high. Read PB6 low means jumper plugged. + */ + gpio_set_mode(GPIOB, GPIO_MODE_INPUT, + GPIO_CNF_INPUT_PULL_UPDOWN, GPIO6); + gpio_set(GPIOB, GPIO6); + gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, GPIO5); + while (gpio_get(GPIOB, GPIO5)) + gpio_clear(GPIOB, GPIO5); + while (!gpio_get(GPIOB, GPIO5)) + gpio_set(GPIOB, GPIO5); + normal_boot = (gpio_get(GPIOB, GPIO6)); + break; + case 1: + /* Boot0/1 pins have 100k between Jumper and MCU + * and are jumperd to low by default. + * If we read PB2 high, force bootloader entry.*/ + gpio_set_mode(GPIOB, GPIO_MODE_INPUT, + GPIO_CNF_INPUT_FLOAT, GPIO2); + normal_boot = !(gpio_get(GPIOB, GPIO2)); + } + if(((GPIOA_CRL & 0x40) == 0x40) && normal_boot) dfu_jump_app_if_valid(); dfu_protect(DFU_MODE); @@ -65,21 +81,6 @@ int main(void) systick_set_clocksource(STK_CSR_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_periph_reset_pulse(RST_USB); - rcc_periph_clock_enable(RCC_USB); - rcc_periph_clock_enable(RCC_GPIOA); - 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(); @@ -94,5 +95,12 @@ void dfu_event(void) void sys_tick_handler(void) { - gpio_toggle(GPIOA, GPIO8); + switch (rev) { + case 0: + gpio_toggle(GPIOA, GPIO8); + break; + case 1: + gpio_toggle(GPIOC, GPIO13); + break; + } } diff --git a/src/target/adiv5.c b/src/target/adiv5.c index 8b061aec..5fdc52d5 100644 --- a/src/target/adiv5.c +++ b/src/target/adiv5.c @@ -354,7 +354,7 @@ static bool adiv5_component_probe(ADIv5_AP_t *ap, uint32_t addr) switch (pidr_pn_bits[i].arch) { case aa_cortexm: DEBUG("-> cortexm_probe\n"); - cortexm_probe(ap); + cortexm_probe(ap, false); break; case aa_cortexa: DEBUG("-> cortexa_probe\n"); @@ -456,6 +456,14 @@ void adiv5_dp_init(ADIv5_DP_t *dp) ADIV5_DP_CTRLSTAT_CDBGRSTACK); } + dp->dp_idcode = adiv5_dp_read(dp, ADIV5_DP_IDCODE); + if ((dp->dp_idcode & ADIV5_DP_VERSION_MASK) == ADIV5_DPv2) { + /* Read TargetID. Can be done with device in WFI, sleep or reset!*/ + adiv5_dp_write(dp, ADIV5_DP_SELECT, ADIV5_DP_BANK2); + dp->targetid = adiv5_dp_read(dp, ADIV5_DP_CTRLSTAT); + adiv5_dp_write(dp, ADIV5_DP_SELECT, ADIV5_DP_BANK0); + DEBUG("TARGETID %08" PRIx32 "\n", dp->targetid); + } /* Probe for APs on this DP */ for(int i = 0; i < 256; i++) { ADIv5_AP_t *ap = adiv5_new_ap(dp, i); @@ -478,11 +486,12 @@ void adiv5_dp_init(ADIv5_DP_t *dp) * AP should be unref'd if not valid. */ - /* The rest sould only be added after checking ROM table */ + /* The rest should only be added after checking ROM table */ probed |= adiv5_component_probe(ap, ap->base); if (!probed && (dp->idcode & 0xfff) == 0x477) { DEBUG("-> cortexm_probe forced\n"); - cortexm_probe(ap); + cortexm_probe(ap, true); + probed = true; } } adiv5_dp_unref(dp); diff --git a/src/target/adiv5.h b/src/target/adiv5.h index 2929a315..83d6294b 100644 --- a/src/target/adiv5.h +++ b/src/target/adiv5.h @@ -34,6 +34,16 @@ #define ADIV5_DP_SELECT ADIV5_DP_REG(0x8) #define ADIV5_DP_RDBUFF ADIV5_DP_REG(0xC) +#define ADIV5_DP_BANK0 0 +#define ADIV5_DP_BANK1 1 +#define ADIV5_DP_BANK2 2 +#define ADIV5_DP_BANK3 3 +#define ADIV5_DP_BANK4 4 + +#define ADIV5_DP_VERSION_MASK 0xf000 +#define ADIV5_DPv1 0x1000 +#define ADIV5_DPv2 0x2000 + /* AP Abort Register (ABORT) */ /* Bits 31:5 - Reserved */ #define ADIV5_DP_ABORT_ORUNERRCLR (1 << 4) @@ -112,6 +122,8 @@ typedef struct ADIv5_DP_s { int refcnt; uint32_t idcode; + uint32_t dp_idcode; /* Contains DPvX revision*/ + uint32_t targetid; /* Contains IDCODE for DPv2 devices.*/ uint32_t (*dp_read)(struct ADIv5_DP_s *dp, uint16_t addr); uint32_t (*error)(struct ADIv5_DP_s *dp); diff --git a/src/target/cortexm.c b/src/target/cortexm.c index 3010daa5..891b2bda 100644 --- a/src/target/cortexm.c +++ b/src/target/cortexm.c @@ -264,7 +264,7 @@ static bool cortexm_forced_halt(target *t) return true; } -bool cortexm_probe(ADIv5_AP_t *ap) +bool cortexm_probe(ADIv5_AP_t *ap, bool forced) { target *t; @@ -323,8 +323,10 @@ bool cortexm_probe(ADIv5_AP_t *ap) target_check_error(t); } - if (!cortexm_forced_halt(t)) - return false; + if (forced) + if (!cortexm_forced_halt(t)) + return false; + #define PROBE(x) \ do { if ((x)(t)) {target_halt_resume(t, 0); return true;} else target_check_error(t); } while (0) @@ -414,6 +416,8 @@ void cortexm_detach(target *t) /* Disable debug */ target_mem_write32(t, CORTEXM_DHCSR, CORTEXM_DHCSR_DBGKEY); + /* Add some clock cycles to get the CPU running again.*/ + target_mem_read32(t, 0); } enum { DB_DHCSR, DB_DCRSR, DB_DCRDR, DB_DEMCR }; diff --git a/src/target/cortexm.h b/src/target/cortexm.h index e6362f40..9c763b74 100644 --- a/src/target/cortexm.h +++ b/src/target/cortexm.h @@ -168,7 +168,7 @@ extern long cortexm_wait_timeout; #define CORTEXM_TOPT_INHIBIT_SRST (1 << 2) -bool cortexm_probe(ADIv5_AP_t *ap); +bool cortexm_probe(ADIv5_AP_t *ap, bool forced); ADIv5_AP_t *cortexm_ap(target *t); bool cortexm_attach(target *t); diff --git a/src/target/lpc11xx.c b/src/target/lpc11xx.c index eb9919b2..37e232f4 100644 --- a/src/target/lpc11xx.c +++ b/src/target/lpc11xx.c @@ -52,6 +52,7 @@ lpc11xx_probe(target *t) uint32_t idcode; /* read the device ID register */ + /* See UM10462 Rev. 5.5 Chapter 20.13.11 Table 377 */ idcode = target_mem_read32(t, LPC11XX_DEVICE_ID); switch (idcode) { case 0x041E502B: @@ -109,15 +110,26 @@ lpc11xx_probe(target *t) target_add_ram(t, 0x10000000, 0x1000); lpc11xx_add_flash(t, 0x00000000, 0x4000, 0x400); return true; - case 0x00008221: /* LPC822M101JHI33 */ - case 0x00008222: /* LPC822M101JDH20 */ - case 0x00008241: /* LPC824M201JHI33 */ - case 0x00008242: /* LPC824M201JDH20 */ + case 0x00008221: /* LPC822M101JHI33 */ + case 0x00008222: /* LPC822M101JDH20 */ + case 0x00008241: /* LPC824M201JHI33 */ + case 0x00008242: /* LPC824M201JDH20 */ t->driver = "LPC82x"; target_add_ram(t, 0x10000000, 0x2000); lpc11xx_add_flash(t, 0x00000000, 0x8000, 0x400); return true; - + case 0x0003D440: /* LPC11U34/311 */ + case 0x0001cc40: /* LPC11U34/421 */ + case 0x0001BC40: /* LPC11U35/401 */ + case 0x0000BC40: /* LPC11U35/501 */ + case 0x00019C40: /* LPC11U36/401 */ + case 0x00017C40: /* LPC11U37FBD48/401 */ + case 0x00007C44: /* LPC11U37HFBD64/401 */ + case 0x00007C40: /* LPC11U37FBD64/501 */ + t->driver = "LPC11U3x"; + target_add_ram(t, 0x10000000, 0x2000); + lpc11xx_add_flash(t, 0x00000000, 0x20000, 0x1000); + return true; } return false;