From 68c706bcb3a029795d7889b2bdc7f76e6a64a514 Mon Sep 17 00:00:00 2001 From: ALTracer <11005378+ALTracer@users.noreply.github.com> Date: Sun, 9 Feb 2025 13:42:21 +0300 Subject: [PATCH 1/5] bluepillplus: New platform for WeActStudio.BluePill-Plus * Uses PB2 LED, USB FS device with external 1.5k pullup * BMD bootloader also uses PA0 button and boot magic flags --- cross-file/bluepillplus.ini | 24 +++ meson_options.txt | 1 + src/platforms/bluepillplus/gd32f303cc.ld | 29 ++++ src/platforms/bluepillplus/meson.build | 85 ++++++++++ src/platforms/bluepillplus/platform.c | 161 ++++++++++++++++++ src/platforms/bluepillplus/platform.h | 190 ++++++++++++++++++++++ src/platforms/bluepillplus/stm32f103cb.ld | 29 ++++ src/platforms/bluepillplus/usbdfu.c | 142 ++++++++++++++++ 8 files changed, 661 insertions(+) create mode 100644 cross-file/bluepillplus.ini create mode 100644 src/platforms/bluepillplus/gd32f303cc.ld create mode 100644 src/platforms/bluepillplus/meson.build create mode 100644 src/platforms/bluepillplus/platform.c create mode 100644 src/platforms/bluepillplus/platform.h create mode 100644 src/platforms/bluepillplus/stm32f103cb.ld create mode 100644 src/platforms/bluepillplus/usbdfu.c diff --git a/cross-file/bluepillplus.ini b/cross-file/bluepillplus.ini new file mode 100644 index 00000000000..6ad0e808965 --- /dev/null +++ b/cross-file/bluepillplus.ini @@ -0,0 +1,24 @@ +# This a cross-file for the bluepillplus probe, providing sane default options for it. + +[binaries] +c = 'arm-none-eabi-gcc' +cpp = 'arm-none-eabi-g++' +ld = 'arm-none-eabi-gcc' +ar = 'arm-none-eabi-ar' +nm = 'arm-none-eabi-nm' +strip = 'arm-none-eabi-strip' +objcopy = 'arm-none-eabi-objcopy' +objdump = 'arm-none-eabi-objdump' +size = 'arm-none-eabi-size' + +[host_machine] +system = 'bare-metal' +cpu_family = 'arm' +cpu = 'arm' +endian = 'little' + +[project options] +probe = 'bluepillplus' +targets = 'cortexm,lpc,nrf,nxp,renesas,rp,sam,stm,ti' +rtt_support = false +bmd_bootloader = true diff --git a/meson_options.txt b/meson_options.txt index 612c2f53ec9..53c3931ada9 100644 --- a/meson_options.txt +++ b/meson_options.txt @@ -8,6 +8,7 @@ option( 'blackpill-f401ce', 'blackpill-f411ce', 'bluepill', + 'bluepillplus', 'ctxlink', 'f072', 'f3', diff --git a/src/platforms/bluepillplus/gd32f303cc.ld b/src/platforms/bluepillplus/gd32f303cc.ld new file mode 100644 index 00000000000..d5dc031bde5 --- /dev/null +++ b/src/platforms/bluepillplus/gd32f303cc.ld @@ -0,0 +1,29 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2025 1BitSquared + * Written by ALTracer <11005378+ALTracer@users.noreply.github.com> + * + * 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 . + */ + +/* Define memory regions. */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K +} + +/* Include the platform common linker script. */ +INCLUDE ../common/blackmagic.ld diff --git a/src/platforms/bluepillplus/meson.build b/src/platforms/bluepillplus/meson.build new file mode 100644 index 00000000000..581fcb5b2eb --- /dev/null +++ b/src/platforms/bluepillplus/meson.build @@ -0,0 +1,85 @@ +# This file is part of the Black Magic Debug project. +# +# Copyright (C) 2024 1BitSquared +# Written by ALTracer <11005378+ALTracer@users.noreply.github.com> +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# 1. Redistributions of source code must retain the above copyright notice, this +# list of conditions and the following disclaimer. +# +# 2. Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# 3. Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +# FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +# DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +# SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +probe_bluepillplus_includes = include_directories('.') + +probe_bluepillplus_sources = files('platform.c') + +probe_bluepillplus_dfu_sources = files('usbdfu.c') + +probe_bluepillplus_args = [ + '-DDFU_SERIAL_LENGTH=9', + '-DBLACKMAGIC', +] + +trace_protocol = get_option('trace_protocol') +probe_bluepillplus_args += [f'-DSWO_ENCODING=@trace_protocol@'] +probe_bluepillplus_dependencies = [platform_stm32_swo] +if trace_protocol in ['1', '3'] + probe_bluepillplus_dependencies += platform_stm32_swo_manchester +endif +if trace_protocol in ['2', '3'] + probe_bluepillplus_dependencies += platform_stm32_swo_uart +endif + +probe_bluepillplus_common_link_args = [ + '-L@0@'.format(meson.current_source_dir()), + '-T@0@'.format('stm32f103cb.ld'), +] + +probe_bluepillplus_link_args = [ + '-Wl,-Ttext=0x8002000', +] + +probe_host = declare_dependency( + include_directories: probe_bluepillplus_includes, + sources: probe_bluepillplus_sources, + compile_args: probe_bluepillplus_args, + link_args: probe_bluepillplus_common_link_args + probe_bluepillplus_link_args, + dependencies: [platform_common, platform_stm32f1, probe_bluepillplus_dependencies], +) + +probe_bootloader = declare_dependency( + include_directories: [platform_common_includes, probe_bluepillplus_includes], + sources: probe_bluepillplus_dfu_sources, + compile_args: probe_bluepillplus_args, + link_args: probe_bluepillplus_common_link_args, + dependencies: platform_stm32f1_dfu, +) + +summary( + { + 'Name': 'Black Magic Probe (BluePill-Plus)', + 'Platform': 'STM32F1', + 'Bootloader': 'Black Magic Debug Bootloader', + 'Load Address': '0x8002000', + }, + section: 'Probe', +) diff --git a/src/platforms/bluepillplus/platform.c b/src/platforms/bluepillplus/platform.c new file mode 100644 index 00000000000..e029c1b62cf --- /dev/null +++ b/src/platforms/bluepillplus/platform.c @@ -0,0 +1,161 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2025 1BitSquared + * Written by ALTracer <11005378+ALTracer@users.noreply.github.com> + * + * 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 WeActStudio.BluePill-Plus implementation. */ + +#include "general.h" +#include "platform.h" +#include "usb.h" +#include "aux_serial.h" + +#include +#include +#include + +volatile uint32_t magic[2] __attribute__((section(".noinit"))); + +static void platform_detach_usb(void); + +void platform_request_boot(void) +{ + magic[0] = BOOTMAGIC0; + magic[1] = BOOTMAGIC1; + SCB_VTOR = 0; + platform_detach_usb(); + scb_reset_system(); +} + +void platform_init(void) +{ + /* Enable peripherals */ + rcc_periph_clock_enable(RCC_GPIOA); + rcc_periph_clock_enable(RCC_GPIOB); + rcc_periph_clock_enable(RCC_GPIOC); + rcc_periph_clock_enable(RCC_AFIO); + rcc_periph_clock_enable(RCC_CRC); + rcc_periph_clock_enable(RCC_USB); +#if SWO_ENCODING == 1 || SWO_ENCODING == 3 + /* Make sure to power up the timer used for trace */ + rcc_periph_clock_enable(SWO_TIM_CLK); +#endif +#if SWO_ENCODING == 2 || SWO_ENCODING == 3 + /* Enable relevant USART and DMA early in platform init */ + rcc_periph_clock_enable(SWO_UART_CLK); + rcc_periph_clock_enable(SWO_DMA_CLK); +#endif + + rcc_clock_setup_pll(&rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]); + + gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_INPUT_FLOAT, TMS_PIN); + gpio_set_mode(TCK_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_INPUT_FLOAT, 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_OUTPUT_2_MHZ, GPIO_CNF_INPUT_FLOAT, TDO_PIN); + platform_nrst_set_val(false); + + gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, LED_IDLE_RUN); + + /* Relocate interrupt vector table here */ + SCB_VTOR = (uintptr_t)&vector_table; + + platform_timing_init(); + platform_detach_usb(); + blackmagic_usb_init(); + aux_serial_init(); + /* By default, do not drive the SWD bus too fast. */ + platform_max_frequency_set(2000000); +} + +void platform_nrst_set_val(bool assert) +{ + if (assert) { + gpio_set_mode(NRST_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, NRST_PIN); + gpio_clear(NRST_PORT, NRST_PIN); + } else { + gpio_set_mode(NRST_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, NRST_PIN); + gpio_set(NRST_PORT, NRST_PIN); + } +} + +bool platform_nrst_get_val(void) +{ + return gpio_get(NRST_PORT, NRST_PIN) == 0; +} + +void platform_target_clk_output_enable(bool enable) +{ + if (enable) { + gpio_set_mode(TCK_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, TCK_PIN); + SWDIO_MODE_DRIVE(); + } else { + SWDIO_MODE_FLOAT(); + gpio_set_mode(TCK_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_INPUT_FLOAT, TCK_PIN); + } +} + +const char *platform_target_voltage(void) +{ + return "Unknown"; +} + +bool platform_spi_init(const spi_bus_e bus) +{ + (void)bus; + return false; +} + +bool platform_spi_deinit(const spi_bus_e bus) +{ + (void)bus; + return false; +} + +bool platform_spi_chip_select(const uint8_t device_select) +{ + (void)device_select; + return false; +} + +uint8_t platform_spi_xfer(const spi_bus_e bus, const uint8_t value) +{ + (void)bus; + return value; +} + +int platform_hwversion(void) +{ + return 0; +} + +void platform_detach_usb(void) +{ + /* + * Disconnect USB after reset: + * Pull USB_DP low. Device will reconnect automatically + * when USB is set up later, as Pull-Up is hard wired + */ + rcc_periph_clock_enable(RCC_USB); + rcc_periph_reset_pulse(RST_USB); + + rcc_periph_clock_enable(RCC_GPIOA); + gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12); + gpio_clear(GPIOA, GPIO12); + for (volatile uint32_t counter = 10000; counter > 0; --counter) + continue; +} diff --git a/src/platforms/bluepillplus/platform.h b/src/platforms/bluepillplus/platform.h new file mode 100644 index 00000000000..aa6a1b19b88 --- /dev/null +++ b/src/platforms/bluepillplus/platform.h @@ -0,0 +1,190 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2025 1BitSquared + * Written by ALTracer <11005378+ALTracer@users.noreply.github.com> + * + * 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 provides the platform specific declarations for the WeActStudio.BluePill-Plus implementation. */ + +#ifndef PLATFORMS_BLUEPILLPLUS_PLATFORM_H +#define PLATFORMS_BLUEPILLPLUS_PLATFORM_H + +#include "gpio.h" +#include "timing.h" +#include "timing_stm32.h" + +#if ENABLE_DEBUG == 1 +#define PLATFORM_HAS_DEBUG +extern bool debug_bmp; +#endif + +#define PLATFORM_IDENT "(BluePill-Plus) " +#define PLATFORM_HAS_TRACESWO + +/* + * Important pin mappings for STM32 implementation: + * * JTAG/SWD + * * PB6: TDI + * * PB7: TDO/SWO + * * PB8: TCK/SWCLK + * * PB9: TMS/SWDIO + * * PA6: TRST + * * PA5: nRST + * * USB USART + * * PA2: USART TX + * * PA3: USART RX + * * +3V3 + * * PA1: power pin + * * Force DFU mode button: + * * PA0: user button KEY + */ + +#define TDI_PORT GPIOB +#define TDI_PIN GPIO7 + +#define TDO_PORT GPIOB +#define TDO_PIN GPIO7 + +#define TCK_PORT GPIOB +#define TCK_PIN GPIO8 +#define SWCLK_PORT TCK_PORT +#define SWCLK_PIN TCK_PIN + +#define TMS_PORT GPIOB +#define TMS_PIN GPIO9 +#define SWDIO_PORT TMS_PORT +#define SWDIO_PIN TMS_PIN + +#define SWD_CR GPIO_CRH(SWDIO_PORT) +#define SWD_CR_MULT (1U << ((9U - 8U) << 2U)) + +#define SWDIO_MODE_FLOAT() \ + do { \ + uint32_t cr = SWD_CR; \ + cr &= ~(0xfU * SWD_CR_MULT); \ + cr |= (0x4U * SWD_CR_MULT); \ + SWD_CR = cr; \ + } while (0) +#define SWDIO_MODE_DRIVE() \ + do { \ + uint32_t cr = SWD_CR; \ + cr &= ~(0xfU * SWD_CR_MULT); \ + cr |= (0x1U * SWD_CR_MULT); \ + SWD_CR = cr; \ + } while (0) + +#define TMS_SET_MODE() gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN); + +#define NRST_PORT GPIOA +#define NRST_PIN GPIO6 +#define TRST_PORT GPIOA +#define TRST_PIN GPIO5 + +/* USB FS device and interrupt priorities */ +#define USB_DRIVER st_usbfs_v1_usb_driver +#define USB_IRQ NVIC_USB_LP_CAN_RX0_IRQ +#define USB_ISR(x) usb_lp_can_rx0_isr(x) + +#define IRQ_PRI_USB (1U << 4U) +#define IRQ_PRI_USBUSART (2U << 4U) +#define IRQ_PRI_USBUSART_DMA (2U << 4U) +#define IRQ_PRI_SWO_DMA (0U << 4U) +#define IRQ_PRI_SWO_TIM (0U << 4U) + +/* USART selection: dedicate the faster USART1/PA10 for SWO(NRZ), leaving USART2 for Aux serial */ +#define USBUSART USART2 +#define USBUSART_CR1 USART2_CR1 +#define USBUSART_DR USART2_DR +#define USBUSART_IRQ NVIC_USART2_IRQ +#define USBUSART_CLK RCC_USART2 +#define USBUSART_ISR(x) usart2_isr(x) +#define USBUSART_PORT GPIOA +#define USBUSART_TX_PIN GPIO2 +#define USBUSART_RX_PIN GPIO3 + +#define UART_PIN_SETUP() \ + do { \ + gpio_set_mode(USBUSART_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USBUSART_TX_PIN); \ + gpio_set_mode(USBUSART_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, USBUSART_RX_PIN); \ + gpio_set(USBUSART_PORT, USBUSART_RX_PIN); \ + } while (0) + +#define USBUSART_DMA_TX_CHAN DMA_CHANNEL7 +#define USBUSART_DMA_TX_IRQ NVIC_DMA1_CHANNEL7_IRQ +#define USBUSART_DMA_TX_ISR(x) dma1_channel7_isr(x) +#define USBUSART_DMA_RX_CHAN DMA_CHANNEL6 +#define USBUSART_DMA_RX_IRQ NVIC_DMA1_CHANNEL6_IRQ +#define USBUSART_DMA_RX_ISR(x) dma1_channel6_isr(x) +#define USBUSART_DMA_BUS DMA1 +#define USBUSART_DMA_CLK RCC_DMA1 + +#ifdef PLATFORM_HAS_TRACESWO +/* On F103, only USART1 is on AHB2 and can reach 4.5MBaud at 72 MHz. */ +#define SWO_UART USART1 +#define SWO_UART_DR USART1_DR +#define SWO_UART_CLK RCC_USART1 +#define SWO_UART_PORT GPIOA +#define SWO_UART_RX_PIN GPIO10 + +/* 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_CHANNEL5 +#define SWO_DMA_IRQ NVIC_DMA1_CHANNEL5_IRQ +#define SWO_DMA_ISR(x) dma1_channel5_isr(x) + +/* Use TIM4 Input 2 (from PB7/TDO) */ +#define SWO_TIM_CLK_EN() +#define SWO_TIM TIM4 +#define SWO_TIM_CLK RCC_TIM4 +#define SWO_TIM_IRQ NVIC_TIM4_IRQ +#define SWO_TIM_ISR(x) tim4_isr(x) +#define SWO_IC_IN TIM_IC_IN_TI2 +#define SWO_IC_RISING TIM_IC1 +#define SWO_CC_RISING TIM4_CCR1 +#define SWO_ITR_RISING TIM_DIER_CC1IE +#define SWO_STATUS_RISING TIM_SR_CC1IF +#define SWO_IC_FALLING TIM_IC2 +#define SWO_CC_FALLING TIM4_CCR2 +#define SWO_STATUS_FALLING TIM_SR_CC2IF +#define SWO_STATUS_OVERFLOW (TIM_SR_CC1OF | TIM_SR_CC2OF) +#define SWO_TRIG_IN TIM_SMCR_TS_TI2FP2 + +#define SWO_PORT GPIOB +#define SWO_PIN GPIO7 +#endif /* PLATFORM_HAS_TRACESWO */ + +/* One active-low button labeled "KEY" */ +#define USER_BUTTON_PORT GPIOA +#define USER_BUTTON_PIN GPIO0 + +/* PB2/BOOT1 has an active-high LED (blue) */ +#define LED_PORT GPIOB +#define LED_IDLE_RUN GPIO2 +#define LED_PORT_ERROR GPIOB +#define LED_ERROR GPIO10 +#define LED_PORT_UART GPIOB +#define LED_UART GPIO11 + +#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_ERROR, LED_ERROR, state); + +#define BOOTMAGIC0 UINT32_C(0xb007da7a) +#define BOOTMAGIC1 UINT32_C(0xbaadfeed) + +#endif /* PLATFORMS_BLUEPILLPLUS_PLATFORM_H */ diff --git a/src/platforms/bluepillplus/stm32f103cb.ld b/src/platforms/bluepillplus/stm32f103cb.ld new file mode 100644 index 00000000000..5105a5075a5 --- /dev/null +++ b/src/platforms/bluepillplus/stm32f103cb.ld @@ -0,0 +1,29 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2025 1BitSquared + * Written by ALTracer <11005378+ALTracer@users.noreply.github.com> + * + * 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 . + */ + +/* Define memory regions. */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K +} + +/* Include the platform common linker script. */ +INCLUDE ../common/blackmagic.ld diff --git a/src/platforms/bluepillplus/usbdfu.c b/src/platforms/bluepillplus/usbdfu.c new file mode 100644 index 00000000000..54b3942ef93 --- /dev/null +++ b/src/platforms/bluepillplus/usbdfu.c @@ -0,0 +1,142 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2025 1BitSquared + * Written by ALTracer <11005378+ALTracer@users.noreply.github.com> + * + * 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 "platform.h" +#include "usbdfu.h" +#include +#include +#include +#include +#include + +uintptr_t app_address = 0x08002000U; +volatile uint32_t magic[2] __attribute__((section(".noinit"))); +static int dfu_activity_counter; + +static void sys_tick_init(void); +static void platform_detach_usb(void); + +void dfu_detach(void) +{ + platform_detach_usb(); + scb_reset_system(); +} + +int main(void) +{ + /* BluePill-Plus board has an active-high button on PA0. Pull it down */ + rcc_periph_clock_enable(RCC_GPIOA); + gpio_set_mode(USER_BUTTON_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, USER_BUTTON_PIN); + gpio_clear(USER_BUTTON_PORT, USER_BUTTON_PIN); + /* Force detach USB device, this also provides the delay to charge button through pullup */ + platform_detach_usb(); + + bool force_bootloader = false; + /* Reason 1: sticky flag variable matches magic */ + if (magic[0] == BOOTMAGIC0 && magic[1] == BOOTMAGIC1) + force_bootloader = true; + /* Reason 2: button is activated by user */ + if (gpio_get(USER_BUTTON_PORT, USER_BUTTON_PIN)) + force_bootloader = true; + + if (force_bootloader) { + magic[0] = 0; + magic[1] = 0; + } else { + dfu_jump_app_if_valid(); + } + + /* Enable peripherals */ + rcc_periph_clock_enable(RCC_GPIOB); + rcc_periph_clock_enable(RCC_USB); + gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, LED_IDLE_RUN); + rcc_clock_setup_pll(&rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]); + + /* Run heartbeat on blue LED */ + sys_tick_init(); + + dfu_protect(false); + dfu_init(&USB_DRIVER); + dfu_main(); +} + +void platform_detach_usb(void) +{ + /* + * Disconnect USB after reset: + * Pull USB_DP low. Device will reconnect automatically + * when USB is set up later, as Pull-Up is hard wired + */ + rcc_periph_clock_enable(RCC_USB); + rcc_periph_reset_pulse(RST_USB); + + rcc_periph_clock_enable(RCC_GPIOA); + gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12); + gpio_clear(GPIOA, GPIO12); + for (volatile uint32_t counter = 10000; counter > 0; --counter) + continue; +} + +void dfu_event(void) +{ + static bool idle_state = false; + /* Ask systick to pause blinking for 1 second */ + dfu_activity_counter = 10; + /* Blink it ourselves */ + SET_IDLE_STATE(idle_state); + idle_state = !idle_state; +} + +static void sys_tick_init(void) +{ + /* Use SysTick at 10Hz to blink the blue LED */ + systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); + systick_set_reload(rcc_ahb_frequency / 8U / 10U); + /* SYSTICK_IRQ with low priority */ + nvic_set_priority(NVIC_SYSTICK_IRQ, 14U << 4U); + systick_interrupt_enable(); + /* Start the heartbeat timer */ + systick_counter_enable(); +} + +void sys_tick_handler(void) +{ + static int count = 0; + if (dfu_activity_counter > 0) { + dfu_activity_counter--; + return; + } + + switch (count) { + case 0: + /* Reload downcounter */ + count = 10; + SET_IDLE_STATE(false); + break; + case 1: + count--; + /* Blink like a very slow PWM */ + SET_IDLE_STATE(true); + break; + default: + count--; + break; + } +} From df2c48cad455d5313b1091ce0f923907db06cb48 Mon Sep 17 00:00:00 2001 From: ALTracer <11005378+ALTracer@users.noreply.github.com> Date: Sun, 9 Feb 2025 14:20:21 +0300 Subject: [PATCH 2/5] bluepillplus: Add a platform README --- src/platforms/bluepillplus/README.md | 98 ++++++++++++++++++++++++++++ 1 file changed, 98 insertions(+) create mode 100644 src/platforms/bluepillplus/README.md diff --git a/src/platforms/bluepillplus/README.md b/src/platforms/bluepillplus/README.md new file mode 100644 index 00000000000..63dc2130461 --- /dev/null +++ b/src/platforms/bluepillplus/README.md @@ -0,0 +1,98 @@ +# Black Magic Debug Probe Firmware for WeAct Studio BluePill-Plus boards + +This platform allows using various BluePill-Plus boards as a Black Magic Probe. + +[BluePill-Plus](https://github.com/WeActStudio/BluePill-Plus) is based on STM32F103CB or GD32F303CC; + +[BluePill-Plus-GD32](https://github.com/WeActStudio/WeActStudio.BluePill-Plus-GD32) is based on GD32F103CB. SoC runs at up to 108 MHz, but because of USB FS device clock restrictions 96 MHz is used. + +[BluePill-Plus-APM32](https://github.com/WeActStudio/WeActStudio.BluePill-Plus-APM32) is based on APM32F103CB (untested). + +[BluePill-Plus-CH32](https://github.com/WeActStudio/WeActStudio.BluePill-Plus-CH32) is based on CH32F103C8 (CM3) or CH32V103C8 or CH32V203C8 (RISC-V) and unsupported (flash too small, non-Cortex-M). + +| SoC | Core |Clock, MHz|SRAM, KiB|Flash, KiB| +|-------------|------------|----------|---------|----------| +| STM32F103CB | Cortex-M3 | 72 | 20 | 128 (2WS)| +| GD32F103CB | Cortex-M3 | 96 | 20 | 128 (0WS)| +| GD32F303CC | Cortex-M4F | 120 | 48 | 256 (0WS)| +| APM32F103CB | Cortex-M3 | 96 | 20 | 128 (0WS)| + +## Pinout + +| Function | Pinout | Cluster | +| --------------- | ------ | --------- | +| TDI | PB6 | JTAG/SWD | +| TDO/TRACESWO | PB7 | JTAG/SWD | +| TCK/SWCLK | PB8 | JTAG/SWD | +| TMS/SWDIO | PB9 | JTAG/SWD | +| nRST | PA5 | JTAG/SWD | +| TRST (optional) | PA6 | JTAG/SWD | +| UART TX | PA2 | USB USART | +| UART RX | PA3 | USB USART | +| LED idle run | PB2 | LED | +| LED error | PB10 | LED | +| LED UART | PB11 | LED | +| User button KEY | PA0 | | + +USB Full-Speed PHY is on PA11/PA12 with a fixed 1.5 kOhm external pull-up resistor. + +SWJ-DP is on PA13/14/15/PB3/4, those pins are kept in default function (Inception debug possible). + +TODO: add support for onboard SPI flash on PA4/5/6/7 (SPI1) and PB12/13/14/15 (SPI2). + +## Instructions for build system + +0. Clone the repo and libopencm3 submodule, install toolchains, meson, etc. + +```sh +git clone https://github.com/blackmagic-debug/blackmagic.git --depth=2000 +cd blackmagic +``` + +1. Create a build configuration for specific platform (WeActStudio BluePill-Plus) with specific options + +```sh +meson setup build --cross-file=cross-file/bluepillplus.ini +``` + +2. Compile the firmware and bootloader + +```sh +ninja -C build +ninja -C build boot-bin +``` + +3. Flash the BMD bootloader into first 8 KiB of memory if it's empty, using USART1, or only flash the BMD Firmware at an offset, using USB DFU. + +For other firmware upgrade instructions see the [Firmware Upgrade](https://black-magic.org/upgrade.html) section. + +### Using the BMD Bootloader +If you flashed the bootloader using the above instructions, it may be invoked using the following: +- Force the F1 into BMD bootloader mode: + - Hold down KEY + - Tap NRST + - Release KEY + +The BMD bootloader also recognizes RCC Reset reason when nRST is pressed, and `dfu-util --detach` (implemented via magic flags in main SRAM). + +Once activated the BMD bootloader may be used to flash the device using 'bmputil,' available [here](https://github.com/blackmagic-debug/bmputil). + +## Performance + +System clock is set to 72 MHz, expecting a 8 MHz HSE crystal. On GD32 chips, 96 and 120 MHz are also an option. + +Because of low expectations to signal integrity or quality wiring, default SWD frequency is reduced to 2 MHz, but in practice 6 MHz is possible, JTAG is slower. + +Aux serial runs via USART2 DMA on APB1 (Pclk = 36 MHz) at 549..2250000 baud. + +TraceSWO Async capture runs via USART1 DMA on APB2 (Pclk = 72 MHz) at 1098..4500000 baud. + +SPI ports are set to Pclk/8 each (use with `bmpflash`). As SPI1 pins may conflict with certain functions, and platform code does not bother restoring them, please soft-reset the probe when done with SPI operations. + +## More details + +* ST MaskROM is the read-only System Memory bootloader which starts up per BOOT0-triggered SYSCFG mem-remap. It talks USART AN2606 so you can use stm32flash etc. However, it does not implement USB DFU, which is why a BMD bootloader is provided here. +* BMD bootloader is the port of BMP bootloader which + a) has a fixed compatible PLL config; + b) understands buttons, drives LED, does not touch other GPIOs, talks USB DfuSe, ~~has MS OS descriptors for automatic driver installation on Windows~~, uses same libopencm3 code so you can verify hardware config via a smaller binary; + c) erases and writes to internal Flash ~2x faster than MaskROM USART at 460800 baud (verify?) without an external USB-UART bridge dongle. From a96208d910d44e1860b4b71c314c47bb3950ccad Mon Sep 17 00:00:00 2001 From: ALTracer <11005378+ALTracer@users.noreply.github.com> Date: Sun, 9 Feb 2025 16:34:10 +0300 Subject: [PATCH 3/5] bluepillplus: Add chip detection and faster PLL configs * Rely on DBGMCU_IDCODE and SCB_CPUID --- src/platforms/bluepillplus/platform.c | 88 ++++++++++++++++++++++++++- 1 file changed, 87 insertions(+), 1 deletion(-) diff --git a/src/platforms/bluepillplus/platform.c b/src/platforms/bluepillplus/platform.c index e029c1b62cf..cd0fd07b7e6 100644 --- a/src/platforms/bluepillplus/platform.c +++ b/src/platforms/bluepillplus/platform.c @@ -28,11 +28,66 @@ #include #include #include +#include volatile uint32_t magic[2] __attribute__((section(".noinit"))); static void platform_detach_usb(void); +#define RCC_CFGR_USBPRE_SHIFT 22 +#define RCC_CFGR_USBPRE_MASK (0x3 << RCC_CFGR_USBPRE_SHIFT) +#define RCC_CFGR_USBPRE_PLL_CLK_DIV1_5 0x0 +#define RCC_CFGR_USBPRE_PLL_CLK_NODIV 0x1 +#define RCC_CFGR_USBPRE_PLL_CLK_DIV2_5 0x2 +#define RCC_CFGR_USBPRE_PLL_CLK_DIV2 0x3 + +static const struct rcc_clock_scale rcc_hse_config_hse8_120mhz = { + /* hse8, pll to 120 */ + .pll_mul = RCC_CFGR_PLLMUL_PLL_CLK_MUL15, + .pll_source = RCC_CFGR_PLLSRC_HSE_CLK, + .hpre = RCC_CFGR_HPRE_NODIV, + .ppre1 = RCC_CFGR_PPRE_DIV2, + .ppre2 = RCC_CFGR_PPRE_NODIV, + .adcpre = RCC_CFGR_ADCPRE_DIV8, + .flash_waitstates = 5, /* except WSEN is 0 and WSCNT don't care */ + .prediv1 = RCC_CFGR2_PREDIV_NODIV, + .usbpre = RCC_CFGR_USBPRE_PLL_CLK_DIV1_5, /* libopencm3_stm32f1 hack */ + .ahb_frequency = 120000000, + .apb1_frequency = 60000000, + .apb2_frequency = 120000000, +}; + +static const struct rcc_clock_scale rcc_hse_config_hse8_96mhz = { + /* hse8, pll to 96 */ + .pll_mul = RCC_CFGR_PLLMUL_PLL_CLK_MUL12, + .pll_source = RCC_CFGR_PLLSRC_HSE_CLK, + .hpre = RCC_CFGR_HPRE_NODIV, + .ppre1 = RCC_CFGR_PPRE_DIV2, + .ppre2 = RCC_CFGR_PPRE_NODIV, + .adcpre = RCC_CFGR_ADCPRE_DIV8, + .flash_waitstates = 3, /* except WSEN is 0 and WSCNT don't care */ + .prediv1 = RCC_CFGR2_PREDIV_NODIV, + .usbpre = RCC_CFGR_USBPRE_PLL_CLK_NODIV, /* libopencm3_stm32f1 hack */ + .ahb_frequency = 96000000, + .apb1_frequency = 48000000, + .apb2_frequency = 96000000, +}; + +/* Set USB CK48M prescaler on GD32F30x before enabling RCC_APB1ENR_USBEN */ +static void rcc_set_usbpre_gd32f30x(uint32_t usbpre) +{ +#if 1 + /* NuttX style */ + uint32_t regval = RCC_CFGR; + regval &= ~RCC_CFGR_USBPRE_MASK; + regval |= (usbpre << RCC_CFGR_USBPRE_SHIFT); + RCC_CFGR = regval; +#else + /* libopencm3 style */ + RCC_CFGR = (RCC_CFGR & ~RCC_CFGR_USBPRE_MASK) | (usbpre << RCC_CFGR_USBPRE_SHIFT); +#endif +} + void platform_request_boot(void) { magic[0] = BOOTMAGIC0; @@ -61,7 +116,38 @@ void platform_init(void) rcc_periph_clock_enable(SWO_DMA_CLK); #endif - rcc_clock_setup_pll(&rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]); + /* Detect platform chip */ + const uint32_t device_id = DBGMCU_IDCODE & DBGMCU_IDCODE_DEV_ID_MASK; + const uint32_t cpu_id = SCB_CPUID & SCB_CPUID_PARTNO; + /* STM32F103CB: 0x410 (Medium density) is readable as 0x000 (errata) without debugger. So default to 72 MHz. */ + const struct rcc_clock_scale *clock = &rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]; + /* + * Pick one of 72/96/120 MHz PLL configs. + * Disable USBD clock (after bootloaders) + * then change USBDPSC[1:0] the CK_USBD prescaler + * and finally enable PLL. + */ + if ((device_id == 0x410 || device_id == 0x000) && cpu_id == 0xc230 && SCB_CPUID == 0x411fc231) { + /* STM32F103CB: 0x410 (Medium density), 0x411fc231 (Cortex-M3 r1p1) */ + clock = &rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]; + } + if (device_id == 0x410 && cpu_id == 0xc230 && SCB_CPUID == 0x412fc231) { + /* GD32F103CB: 0x410 (Medium Density), 0x412fc231 (Cortex-M3 r2p1) */ + clock = &rcc_hse_config_hse8_96mhz; + rcc_periph_clock_disable(RCC_USB); + /* Set 96/2=48MHz USB divisor before enabling PLL */ + rcc_set_usbpre_gd32f30x(RCC_CFGR_USBPRE_PLL_CLK_DIV2); + } + if (device_id == 0x414 && cpu_id == 0xc240 && SCB_CPUID == 0x410fc241) { + /* GD32F303CC: 0x414 (High density) 0x410fc241 (Cortex-M4F r0p1) */ + clock = &rcc_hse_config_hse8_120mhz; + rcc_periph_clock_disable(RCC_USB); + /* Set 120/2.5=48MHz USB divisor before enabling PLL */ + rcc_set_usbpre_gd32f30x(RCC_CFGR_USBPRE_PLL_CLK_DIV2_5); + } + + /* Enable PLL */ + rcc_clock_setup_pll(clock); gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_INPUT_FLOAT, TMS_PIN); gpio_set_mode(TCK_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_INPUT_FLOAT, TCK_PIN); From ee436a5823bb3cb6004c2e3d233b9afce0f44c0f Mon Sep 17 00:00:00 2001 From: ALTracer <11005378+ALTracer@users.noreply.github.com> Date: Sun, 9 Feb 2025 17:28:32 +0300 Subject: [PATCH 4/5] bluepillplus: Add chip detection via CoreSight ROM tables --- src/platforms/bluepillplus/platform.c | 130 +++++++++++++++++++------- 1 file changed, 98 insertions(+), 32 deletions(-) diff --git a/src/platforms/bluepillplus/platform.c b/src/platforms/bluepillplus/platform.c index cd0fd07b7e6..1b424455333 100644 --- a/src/platforms/bluepillplus/platform.c +++ b/src/platforms/bluepillplus/platform.c @@ -88,6 +88,102 @@ static void rcc_set_usbpre_gd32f30x(uint32_t usbpre) #endif } +/* ROM table CIDR values */ +#define CIDR0_OFFSET 0xff0U /* DBGCID0 */ +#define CIDR1_OFFSET 0xff4U /* DBGCID1 */ +#define CIDR2_OFFSET 0xff8U /* DBGCID2 */ +#define CIDR3_OFFSET 0xffcU /* DBGCID3 */ + +#define PIDR0_OFFSET 0xfe0U /* DBGPID0 */ +#define PIDR1_OFFSET 0xfe4U /* DBGPID1 */ +#define PIDR2_OFFSET 0xfe8U /* DBGPID2 */ +#define PIDR3_OFFSET 0xfecU /* DBGPID3 */ +#define PIDR4_OFFSET 0xfd0U /* DBGPID4 */ +#define PIDR5_OFFSET 0xfd4U /* DBGPID5 (Reserved) */ +#define PIDR6_OFFSET 0xfd8U /* DBGPID6 (Reserved) */ +#define PIDR7_OFFSET 0xfdcU /* DBGPID7 (Reserved) */ + +#define ROMTABLE_BASE 0xe00ff000U + +static uint64_t coresight_romtable_pidr(void) +{ + uint8_t pidr[8] = {0}; + uint64_t pid64 = 0; + + /* Pack bytes from sparse Product ID registers */ + pidr[0] = *(const uint32_t *)(ROMTABLE_BASE + PIDR0_OFFSET); + pidr[1] = *(const uint32_t *)(ROMTABLE_BASE + PIDR1_OFFSET); + pidr[2] = *(const uint32_t *)(ROMTABLE_BASE + PIDR2_OFFSET); + pidr[3] = *(const uint32_t *)(ROMTABLE_BASE + PIDR3_OFFSET); + pidr[4] = *(const uint32_t *)(ROMTABLE_BASE + PIDR4_OFFSET); + + memcpy(&pid64, pidr, 8); + return pid64; +} + +static uint32_t coresight_romtable_cidr_check(void) +{ + uint8_t cidr[4] = {0}; + uint32_t cid32 = 0; + /* Pack bytes from sparse Component ID registers */ + cidr[0] = *(const uint32_t *)(ROMTABLE_BASE + CIDR0_OFFSET); + cidr[1] = *(const uint32_t *)(ROMTABLE_BASE + CIDR1_OFFSET); + cidr[2] = *(const uint32_t *)(ROMTABLE_BASE + CIDR2_OFFSET); + cidr[3] = *(const uint32_t *)(ROMTABLE_BASE + CIDR3_OFFSET); + + memcpy(&cid32, cidr, 4); + return cid32; +} + +static void platform_detect_variant(void) +{ + /* Detect platform chip */ + const uint32_t device_id = DBGMCU_IDCODE & DBGMCU_IDCODE_DEV_ID_MASK; + const uint32_t cpu_id = SCB_CPUID & SCB_CPUID_PARTNO; + const uint64_t romtable_pidr = coresight_romtable_pidr(); + const uint32_t romtable_cidr = coresight_romtable_cidr_check(); + /* STM32F103CB: 0x410 (Medium density) is readable as 0x000 (errata) without debugger. So default to 72 MHz. */ + const struct rcc_clock_scale *clock = &rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]; + /* + * Pick one of 72/96/120 MHz PLL configs. + * Disable USBD clock (after bootloaders) + * then change USBDPSC[1:0] the CK_USBD prescaler + * and finally enable PLL. + */ + if ((device_id == 0x410 || device_id == 0x000) && cpu_id == 0xc230 && SCB_CPUID == 0x411fc231U) { + /* STM32F103CB: 0x410 (Medium density), 0x411fc231 (Cortex-M3 r1p1) */ + if (romtable_cidr == 0xb105100dU && romtable_pidr == 0xa0410) { + /* STM32F103: Manufacturer 020 Partno 410 (PIDR = 0x00000a0410) */ + clock = &rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]; + } + } + + if (device_id == 0x410 && cpu_id == 0xc230 && SCB_CPUID == 0x412fc231U) { + /* GD32F103CB: 0x410 (Medium Density), 0x412fc231 (Cortex-M3 r2p1) */ + if (romtable_cidr == 0xb105100dU && romtable_pidr == 0x07000d1f64ULL) { + /* GD32F103: Manufacturer 751 Partno f64 (PIDR = 0x07000d1f64) */ + clock = &rcc_hse_config_hse8_96mhz; + rcc_periph_clock_disable(RCC_USB); + /* Set 96/2=48MHz USB divisor before enabling PLL */ + rcc_set_usbpre_gd32f30x(RCC_CFGR_USBPRE_PLL_CLK_DIV2); + } + } + + if (device_id == 0x414 && cpu_id == 0xc240 && SCB_CPUID == 0x410fc241) { + /* GD32F303CC: High density, 0x410fc241 (Cortex-M4F r0p1) */ + if (romtable_cidr == 0xb105100dU && romtable_pidr == 0x07000d1050ULL) { + /* GD32F303: Manufacturer 751 Partno 050 (PIDR = 0x07000d1050) */ + clock = &rcc_hse_config_hse8_120mhz; + rcc_periph_clock_disable(RCC_USB); + /* Set 120/2.5=48MHz USB divisor before enabling PLL */ + rcc_set_usbpre_gd32f30x(RCC_CFGR_USBPRE_PLL_CLK_DIV2_5); + } + } + + /* Enable PLL */ + rcc_clock_setup_pll(clock); +} + void platform_request_boot(void) { magic[0] = BOOTMAGIC0; @@ -116,38 +212,8 @@ void platform_init(void) rcc_periph_clock_enable(SWO_DMA_CLK); #endif - /* Detect platform chip */ - const uint32_t device_id = DBGMCU_IDCODE & DBGMCU_IDCODE_DEV_ID_MASK; - const uint32_t cpu_id = SCB_CPUID & SCB_CPUID_PARTNO; - /* STM32F103CB: 0x410 (Medium density) is readable as 0x000 (errata) without debugger. So default to 72 MHz. */ - const struct rcc_clock_scale *clock = &rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]; - /* - * Pick one of 72/96/120 MHz PLL configs. - * Disable USBD clock (after bootloaders) - * then change USBDPSC[1:0] the CK_USBD prescaler - * and finally enable PLL. - */ - if ((device_id == 0x410 || device_id == 0x000) && cpu_id == 0xc230 && SCB_CPUID == 0x411fc231) { - /* STM32F103CB: 0x410 (Medium density), 0x411fc231 (Cortex-M3 r1p1) */ - clock = &rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]; - } - if (device_id == 0x410 && cpu_id == 0xc230 && SCB_CPUID == 0x412fc231) { - /* GD32F103CB: 0x410 (Medium Density), 0x412fc231 (Cortex-M3 r2p1) */ - clock = &rcc_hse_config_hse8_96mhz; - rcc_periph_clock_disable(RCC_USB); - /* Set 96/2=48MHz USB divisor before enabling PLL */ - rcc_set_usbpre_gd32f30x(RCC_CFGR_USBPRE_PLL_CLK_DIV2); - } - if (device_id == 0x414 && cpu_id == 0xc240 && SCB_CPUID == 0x410fc241) { - /* GD32F303CC: 0x414 (High density) 0x410fc241 (Cortex-M4F r0p1) */ - clock = &rcc_hse_config_hse8_120mhz; - rcc_periph_clock_disable(RCC_USB); - /* Set 120/2.5=48MHz USB divisor before enabling PLL */ - rcc_set_usbpre_gd32f30x(RCC_CFGR_USBPRE_PLL_CLK_DIV2_5); - } - - /* Enable PLL */ - rcc_clock_setup_pll(clock); + /* Detect which chip we're running on, and set Hclk as legally fast as possible */ + platform_detect_variant(); gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_INPUT_FLOAT, TMS_PIN); gpio_set_mode(TCK_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_INPUT_FLOAT, TCK_PIN); From 1d39692acb525e685269cd9469813b4b94c62339 Mon Sep 17 00:00:00 2001 From: ALTracer <11005378+ALTracer@users.noreply.github.com> Date: Thu, 7 Sep 2023 19:11:04 +0300 Subject: [PATCH 5/5] bluepillplus: Add support for SPI1 * WeActStudio.BluePill-Plus boards have a DNF SOIC-8 footprint for 25-series SPI NOR flash, wired to PA4/5/6/7. * Add the pin mappings regardless of the platform flavour. --- src/platforms/bluepillplus/platform.c | 60 +++++++++++++++++++++++---- src/platforms/bluepillplus/platform.h | 9 ++++ 2 files changed, 61 insertions(+), 8 deletions(-) diff --git a/src/platforms/bluepillplus/platform.c b/src/platforms/bluepillplus/platform.c index 1b424455333..874562f2492 100644 --- a/src/platforms/bluepillplus/platform.c +++ b/src/platforms/bluepillplus/platform.c @@ -29,6 +29,7 @@ #include #include #include +#include volatile uint32_t magic[2] __attribute__((section(".noinit"))); @@ -268,26 +269,69 @@ const char *platform_target_voltage(void) bool platform_spi_init(const spi_bus_e bus) { - (void)bus; - return false; + uint32_t controller = 0; + if (bus == SPI_BUS_INTERNAL) { + /* Set up onboard flash SPI GPIOs: PA5/6/7 as SPI1 in AF5, PA4 as nCS output push-pull */ + gpio_set_mode(OB_SPI_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, + OB_SPI_SCLK | OB_SPI_MISO | OB_SPI_MOSI); + gpio_set_mode(OB_SPI_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, OB_SPI_CS); + /* Deselect the targeted peripheral chip */ + gpio_set(OB_SPI_PORT, OB_SPI_CS); + + rcc_periph_clock_enable(RCC_SPI1); + rcc_periph_reset_pulse(RST_SPI1); + controller = OB_SPI; + } else + return false; + + /* Set up hardware SPI: master, PCLK/8, Mode 0, 8-bit MSB first */ + spi_init_master(controller, SPI_CR1_BAUDRATE_FPCLK_DIV_8, SPI_CR1_CPOL_CLK_TO_0_WHEN_IDLE, + SPI_CR1_CPHA_CLK_TRANSITION_1, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST); + spi_enable(controller); + return true; } bool platform_spi_deinit(const spi_bus_e bus) { - (void)bus; - return false; + if (bus == SPI_BUS_INTERNAL) { + spi_disable(OB_SPI); + /* Gate SPI1 APB clock */ + rcc_periph_clock_disable(RCC_SPI1); + /* Unmap GPIOs */ + gpio_set_mode( + OB_SPI_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, OB_SPI_SCLK | OB_SPI_MISO | OB_SPI_MOSI | OB_SPI_CS); + return true; + } else + return false; } bool platform_spi_chip_select(const uint8_t device_select) { - (void)device_select; - return false; + const uint8_t device = device_select & 0x7fU; + const bool select = !(device_select & 0x80U); + uint32_t port; + uint16_t pin; + switch (device) { + case SPI_DEVICE_INT_FLASH: + port = OB_SPI_CS_PORT; + pin = OB_SPI_CS; + break; + default: + return false; + } + gpio_set_val(port, pin, select); + return true; } uint8_t platform_spi_xfer(const spi_bus_e bus, const uint8_t value) { - (void)bus; - return value; + switch (bus) { + case SPI_BUS_INTERNAL: + return spi_xfer(OB_SPI, value); + break; + default: + return 0U; + } } int platform_hwversion(void) diff --git a/src/platforms/bluepillplus/platform.h b/src/platforms/bluepillplus/platform.h index aa6a1b19b88..930ed926951 100644 --- a/src/platforms/bluepillplus/platform.h +++ b/src/platforms/bluepillplus/platform.h @@ -168,6 +168,15 @@ extern bool debug_bmp; #define SWO_PIN GPIO7 #endif /* PLATFORM_HAS_TRACESWO */ +/* SPI1: PA4/5/6/7 to onboard w25q64 */ +#define OB_SPI SPI1 +#define OB_SPI_PORT GPIOA +#define OB_SPI_SCLK GPIO5 +#define OB_SPI_MISO GPIO6 +#define OB_SPI_MOSI GPIO7 +#define OB_SPI_CS_PORT GPIOA +#define OB_SPI_CS GPIO4 + /* One active-low button labeled "KEY" */ #define USER_BUTTON_PORT GPIOA #define USER_BUTTON_PIN GPIO0