diff --git a/src/platforms/blackpill/Makefile.inc b/src/platforms/blackpill/Makefile.inc new file mode 100644 index 0000000..f0d2b8e --- /dev/null +++ b/src/platforms/blackpill/Makefile.inc @@ -0,0 +1,52 @@ +CROSS_COMPILE ?= arm-none-eabi- +BMP_BOOTLOADER ?= +CC = $(CROSS_COMPILE)gcc +OBJCOPY = $(CROSS_COMPILE)objcopy + +CFLAGS += -Istm32/include -mcpu=cortex-m4 -mthumb \ + -mfloat-abi=hard -mfpu=fpv4-sp-d16 \ + -DSTM32F4 -I../libopencm3/include \ + -Iplatforms/stm32 + +LINKER_SCRIPT=platforms/stm32/blackpillv2.ld + +LDFLAGS_BOOT = -lopencm3_stm32f4 \ + -Wl,-T,$(LINKER_SCRIPT) -nostartfiles -lc -lnosys \ + -Wl,-Map=mapfile -mthumb -mcpu=cortex-m4 -Wl,-gc-sections \ + -mfloat-abi=hard -mfpu=fpv4-sp-d16 \ + -L../libopencm3/lib + +ifeq ($(BMP_BOOTLOADER), 1) +$(info Load address 0x08004000 for BMPBootloader) +LDFLAGS = $(LDFLAGS_BOOT) -Wl,-Ttext=0x8004000 +CFLAGS += -DDFU_SERIAL_LENGTH=9 +else +LDFLAGS += $(LDFLAGS_BOOT) +CFLAGS += -DDFU_SERIAL_LENGTH=13 +endif + +VPATH += platforms/stm32 + +SRC += cdcacm.c \ + traceswodecode.c \ + traceswo.c \ + usbuart.c \ + serialno.c \ + timing.c \ + timing_stm32.c \ + +ifneq ($(BMP_BOOTLOADER), 1) +all: blackmagic.bin +else +all: blackmagic.bin blackmagic_dfu.bin blackmagic_dfu.hex +blackmagic_dfu: usbdfu.o dfucore.o dfu_f4.o serialno.o + $(CC) $^ -o $@ $(LDFLAGS_BOOT) + +blackmagic_dfu.bin: blackmagic_dfu + $(OBJCOPY) -O binary $^ $@ + +blackmagic_dfu.hex: blackmagic_dfu + $(OBJCOPY) -O ihex $^ $@ +endif +host_clean: + -$(Q)$(RM) blackmagic.bin diff --git a/src/platforms/blackpill/Readme.md b/src/platforms/blackpill/Readme.md new file mode 100644 index 0000000..5f1b61e --- /dev/null +++ b/src/platforms/blackpill/Readme.md @@ -0,0 +1,53 @@ +# Firmware BMP for STM32F401/stm32f411 MiniF4 aka BlackPillV2 boards + +Allows the use of BlackPillV2 as a Black Magic Probe + +https://github.com/WeActTC/MiniSTM32F4x1 + +## Connections: + +* JTAG/SWD + * PA1: TDI + * PA13: TMS/SWDIO + * PA14: TCK/SWCLK + * PB3: TDO/TRACESWO + * PB5: TRST + * PB4: SRST + +* USB USART + * PB6: USART1 TX (usbuart_xxx) + * PB7: USART1 RX (usbuart_xxx) + +* +3V3. + * PB8 - turn on IRLML5103 transistor + +How to Build +======================================== +``` +cd blackmagic +make clean +make PROBE_HOST=blackpill +``` + +How to Flash with dfu +======================================== +* After build: + * 1) `apt install 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) `dfu-util -a 0 --dfuse-address 0x08000000 -D blackmagic.bin` + +To exit from dfu mode press a "key" and "reset", release reset. BMP firmware should appear + + +10 pin male from pins +======================================== + +| PB3/TDO | PB7/RX | PB6/TX | X | PA1/TDI | +| -------- | ----------- | ---------- | ---------- | ------- | +| PB4/SRST | +3V3/PB8 SW | PA13/SWDIO | PA14/SWCLK | GND | + +SWJ frequency setting +==================================== +https://github.com/blackmagic-debug/blackmagic/pull/783#issue-529197718 + +`mon freq 900k` helps at most diff --git a/src/platforms/blackpill/platform.c b/src/platforms/blackpill/platform.c new file mode 100644 index 0000000..1e34c6b --- /dev/null +++ b/src/platforms/blackpill/platform.c @@ -0,0 +1,144 @@ +/* + * 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. + */ + +#include "general.h" +#include "cdcacm.h" +#include "usbuart.h" +#include "morse.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + + +jmp_buf fatal_error_jmpbuf; +extern char _ebss[]; + +void platform_init(void) +{ + volatile uint32_t *magic = (uint32_t *)_ebss; + /* Enable GPIO peripherals */ + rcc_periph_clock_enable(RCC_GPIOA); + rcc_periph_clock_enable(RCC_GPIOC); + rcc_periph_clock_enable(RCC_GPIOB); + + /* Check the USER button*/ + if (gpio_get(GPIOA, GPIO0) || + ((magic[0] == BOOTMAGIC0) && (magic[1] == BOOTMAGIC1))) + { + magic[0] = 0; + magic[1] = 0; + /* Assert blue LED as indicator we are in the bootloader */ + gpio_mode_setup(LED_PORT, GPIO_MODE_OUTPUT, + GPIO_PUPD_NONE, LED_BOOTLOADER); + gpio_set(LED_PORT, LED_BOOTLOADER); + /* Jump to the built in bootloader by mapping System flash. + As we just come out of reset, no other deinit is needed!*/ + rcc_periph_clock_enable(RCC_SYSCFG); + SYSCFG_MEMRM &= ~3; + SYSCFG_MEMRM |= 1; + scb_reset_core(); + } + rcc_clock_setup_pll(&rcc_hse_25mhz_3v3[RCC_CLOCK_3V3_84MHZ]); + + /* Enable peripherals */ + rcc_periph_clock_enable(RCC_OTGFS); + rcc_periph_clock_enable(RCC_CRC); + + /* Set up USB Pins and alternate function*/ + gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO9 | GPIO11 | GPIO12); + gpio_set_af(GPIOA, GPIO_AF10, GPIO9 | GPIO10 | GPIO11 | GPIO12); + + GPIOA_OSPEEDR &= 0x3C00000C; + GPIOA_OSPEEDR |= 0x28000008; + + gpio_mode_setup(JTAG_PORT, GPIO_MODE_OUTPUT, + GPIO_PUPD_NONE, + TCK_PIN | TDI_PIN); + gpio_mode_setup(JTAG_PORT, GPIO_MODE_INPUT, + GPIO_PUPD_NONE, TMS_PIN); + gpio_set_output_options(JTAG_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_2MHZ, + TCK_PIN | TDI_PIN | TMS_PIN); + gpio_mode_setup(TDO_PORT, GPIO_MODE_INPUT, + GPIO_PUPD_NONE, + TDO_PIN); + gpio_set_output_options(TDO_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_2MHZ, + TDO_PIN | TMS_PIN); + + gpio_mode_setup(LED_PORT, GPIO_MODE_OUTPUT, + GPIO_PUPD_NONE, + LED_IDLE_RUN | LED_ERROR | LED_BOOTLOADER); + + gpio_mode_setup(LED_PORT_UART, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, LED_UART); + +#ifdef PLATFORM_HAS_POWER_SWITCH + gpio_set(PWR_BR_PORT, PWR_BR_PIN); + gpio_mode_setup(PWR_BR_PORT, GPIO_MODE_OUTPUT, + GPIO_PUPD_NONE, + PWR_BR_PIN); +#endif + + platform_timing_init(); + usbuart_init(); + cdcacm_init(); + + // https://github.com/libopencm3/libopencm3/pull/1256#issuecomment-779424001 + OTG_FS_GCCFG |= OTG_GCCFG_NOVBUSSENS | OTG_GCCFG_PWRDWN; + OTG_FS_GCCFG &= ~(OTG_GCCFG_VBUSBSEN | OTG_GCCFG_VBUSASEN); +} + +void platform_srst_set_val(bool assert) { (void)assert; } +bool platform_srst_get_val(void) { return false; } + +const char *platform_target_voltage(void) +{ + return NULL; +} + +void platform_request_boot(void) +{ + uint32_t *magic = (uint32_t *)&_ebss; + magic[0] = BOOTMAGIC0; + magic[1] = BOOTMAGIC1; + scb_reset_system(); +} + +#ifdef PLATFORM_HAS_POWER_SWITCH +bool platform_target_get_power(void) +{ + return !gpio_get(PWR_BR_PORT, PWR_BR_PIN); +} + +void platform_target_set_power(bool power) +{ + gpio_set_val(PWR_BR_PORT, PWR_BR_PIN, !power); +} +#endif \ No newline at end of file diff --git a/src/platforms/blackpill/platform.h b/src/platforms/blackpill/platform.h new file mode 100644 index 0000000..3cf4067 --- /dev/null +++ b/src/platforms/blackpill/platform.h @@ -0,0 +1,194 @@ +/* + * 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 "gpio.h" +#include "timing.h" +#include "timing_stm32.h" + +#include + +#define PLATFORM_HAS_TRACESWO +#define PLATFORM_IDENT "(BlackPillV2) " +/* Important pin mappings for STM32 implementation: + * JTAG/SWD + * PA1: TDI
+ * PA13: TMS/SWDIO
+ * PA14: TCK/SWCLK
+ * PB3: TDO/TRACESWO
+ * PB5: TRST
+ * PB4: SRST
+ * USB USART + * PB6: USART1 TX + * PB7: USART1 RX + * +3V3 + * PB8 - turn on IRLML5103 transistor + * Force DFU mode button: PA0 + */ + +/* Hardware definitions... */ +#define JTAG_PORT GPIOA +#define TDI_PORT JTAG_PORT +#define TMS_PORT JTAG_PORT +#define TCK_PORT JTAG_PORT +#define TDO_PORT GPIOB +#define TDI_PIN GPIO1 +#define TMS_PIN GPIO13 +#define TCK_PIN GPIO14 +#define TDO_PIN GPIO3 + +#define SWDIO_PORT JTAG_PORT +#define SWCLK_PORT JTAG_PORT +#define SWDIO_PIN TMS_PIN +#define SWCLK_PIN TCK_PIN + +#define TRST_PORT GPIOB +#define TRST_PIN GPIO5 +#define SRST_PORT GPIOB +#define SRST_PIN GPIO4 + +#define PWR_BR_PORT GPIOB +#define PWR_BR_PIN GPIO8 + +#define LED_PORT GPIOC +#define LED_PORT_UART GPIOA +#define LED_UART GPIO1 +#define LED_IDLE_RUN GPIO15 +#define LED_ERROR GPIO14 +#define LED_BOOTLOADER GPIO13 + +#define USBUSART USART1 +#define USBUSART_CR1 USART1_CR1 +#define USBUSART_DR USART1_DR +#define USBUSART_IRQ NVIC_USART1_IRQ +#define USBUSART_CLK RCC_USART1 +#define USBUSART_PORT GPIOB +#define USBUSART_TX_PIN GPIO6 +#define USBUSART_RX_PIN GPIO7 +#define USBUSART_ISR(x) usart1_isr(x) +#define USBUSART_DMA_BUS DMA2 +#define USBUSART_DMA_CLK RCC_DMA2 +#define USBUSART_DMA_TX_CHAN DMA_STREAM7 +#define USBUSART_DMA_TX_IRQ NVIC_DMA2_STREAM7_IRQ +#define USBUSART_DMA_TX_ISR(x) dma2_stream7_isr(x) +#define USBUSART_DMA_RX_CHAN DMA_STREAM5 +#define USBUSART_DMA_RX_IRQ NVIC_DMA2_STREAM5_IRQ +#define USBUSART_DMA_RX_ISR(x) dma2_stream5_isr(x) +/* For STM32F4 DMA trigger source must be specified */ +#define USBUSART_DMA_TRG DMA_SxCR_CHSEL_4 + +#define BOOTMAGIC0 0xb007da7a +#define BOOTMAGIC1 0xbaadfeed + +#define TMS_SET_MODE() \ + gpio_mode_setup(TMS_PORT, GPIO_MODE_OUTPUT, \ + GPIO_PUPD_NONE, TMS_PIN); +#define SWDIO_MODE_FLOAT() \ + gpio_mode_setup(SWDIO_PORT, GPIO_MODE_INPUT, \ + GPIO_PUPD_NONE, SWDIO_PIN); + +#define SWDIO_MODE_DRIVE() \ + gpio_mode_setup(SWDIO_PORT, GPIO_MODE_OUTPUT, \ + GPIO_PUPD_NONE, SWDIO_PIN); +#define UART_PIN_SETUP() do { \ + gpio_mode_setup(USBUSART_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, \ + USBUSART_TX_PIN); \ + gpio_set_output_options(USBUSART_PORT, GPIO_OTYPE_PP, \ + GPIO_OSPEED_100MHZ, USBUSART_TX_PIN); \ + gpio_set_af(USBUSART_PORT, GPIO_AF7, USBUSART_TX_PIN); \ + gpio_mode_setup(USBUSART_PORT, GPIO_MODE_AF, GPIO_PUPD_PULLUP, \ + USBUSART_RX_PIN); \ + gpio_set_output_options(USBUSART_PORT, GPIO_OTYPE_OD, \ + GPIO_OSPEED_100MHZ, USBUSART_RX_PIN); \ + gpio_set_af(USBUSART_PORT, GPIO_AF7, USBUSART_RX_PIN); \ +} while(0) + +#define USB_DRIVER stm32f107_usb_driver +#define USB_IRQ NVIC_OTG_FS_IRQ +#define USB_ISR(x) otg_fs_isr(x) +/* Interrupt priorities. Low numbers are high priority. + * TIM3 is used for traceswo capture and must be highest priority. + */ +#define IRQ_PRI_USB (1 << 4) +#define IRQ_PRI_USBUSART (2 << 4) +#define IRQ_PRI_USBUSART_DMA (2 << 4) +#define IRQ_PRI_TRACE (0 << 4) + + +#define TRACE_TIM TIM3 +#define TRACE_TIM_CLK_EN() rcc_periph_clock_enable(RCC_TIM3) +#define TRACE_IRQ NVIC_TIM3_IRQ +#define TRACE_ISR(x) tim3_isr(x) + +#define gpio_set_val(port, pin, val) do { \ + if(val) \ + gpio_set((port), (pin)); \ + else \ + gpio_clear((port), (pin)); \ +} while(0) + +#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(state) {gpio_set_val(LED_PORT, LED_ERROR, state);} + +static inline int platform_hwversion(void) +{ + return 0; +} + +/* + * Use newlib provided integer only stdio functions + */ + +/* sscanf */ +#ifdef sscanf +#undef sscanf +#define sscanf siscanf +#else +#define sscanf siscanf +#endif +/* sprintf */ +#ifdef sprintf +#undef sprintf +#define sprintf siprintf +#else +#define sprintf siprintf +#endif +/* vasprintf */ +#ifdef vasprintf +#undef vasprintf +#define vasprintf vasiprintf +#else +#define vasprintf vasiprintf +#endif +/* snprintf */ +#ifdef snprintf +#undef snprintf +#define snprintf sniprintf +#else +#define snprintf sniprintf +#endif + +#endif diff --git a/src/platforms/blackpill/usbdfu.c b/src/platforms/blackpill/usbdfu.c new file mode 100644 index 0000000..cdc68d3 --- /dev/null +++ b/src/platforms/blackpill/usbdfu.c @@ -0,0 +1,73 @@ +/* + * 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" +#include "general.h" +#include "platform.h" + +uint32_t app_address = 0x08004000; +extern char _ebss[]; + +void dfu_detach(void) +{ + scb_reset_system(); +} + +int main(void) +{ + volatile uint32_t *magic = (uint32_t *)_ebss; + rcc_periph_clock_enable(RCC_GPIOA); + if (gpio_get(GPIOA, GPIO0) || + ((magic[0] == BOOTMAGIC0) && (magic[1] == BOOTMAGIC1))) { + magic[0] = 0; + magic[1] = 0; + } else { + dfu_jump_app_if_valid(); + } + rcc_clock_setup_pll(&rcc_hse_8mhz_3v3[RCC_CLOCK_3V3_168MHZ]); + + /* Assert blue LED as indicator we are in the bootloader */ + rcc_periph_clock_enable(RCC_GPIOD); + gpio_mode_setup(LED_PORT, GPIO_MODE_OUTPUT, + GPIO_PUPD_NONE, LED_BOOTLOADER); + gpio_set(LED_PORT, LED_BOOTLOADER); + + /* Enable peripherals */ + rcc_periph_clock_enable(RCC_OTGFS); + + /* Set up USB Pins and alternate function*/ + gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO11 | GPIO12); + gpio_set_af(GPIOA, GPIO_AF10, GPIO11 | GPIO12); + + dfu_protect(false); + dfu_init(&USB_DRIVER); + dfu_main(); + +} + +void dfu_event(void) +{ +} +