From 55a3132d1cfaa0047f5c5c4c45ec89dcb577a046 Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Sat, 10 Jul 2021 17:11:13 +0200 Subject: [PATCH] platforms/f3: Introduced a new platform for the STM32F3 series --- src/platforms/f3/Makefile.inc | 29 ++++++ src/platforms/f3/Readme | 20 ++++ src/platforms/f3/platform.c | 117 +++++++++++++++++++++++ src/platforms/f3/platform.h | 163 ++++++++++++++++++++++++++++++++ src/platforms/f3/stm32f303xc.ld | 30 ++++++ 5 files changed, 359 insertions(+) create mode 100644 src/platforms/f3/Makefile.inc create mode 100644 src/platforms/f3/Readme create mode 100644 src/platforms/f3/platform.c create mode 100644 src/platforms/f3/platform.h create mode 100644 src/platforms/f3/stm32f303xc.ld diff --git a/src/platforms/f3/Makefile.inc b/src/platforms/f3/Makefile.inc new file mode 100644 index 0000000..66351c5 --- /dev/null +++ b/src/platforms/f3/Makefile.inc @@ -0,0 +1,29 @@ +CROSS_COMPILE ?= arm-none-eabi- +CC = $(CROSS_COMPILE)gcc +OBJCOPY = $(CROSS_COMPILE)objcopy + +CFLAGS += -Istm32/include -mcpu=cortex-m4 -mthumb \ + -mfloat-abi=hard -mfpu=fpv4-sp-d16 \ + -DSTM32F3 -I../libopencm3/include \ + -DDFU_SERIAL_LENGTH=13 -Iplatforms/stm32 + +LDFLAGS = --specs=nano.specs -lopencm3_stm32f3 \ + -Wl,-T,platforms/f3-if/stm32f303xc.ld -nostartfiles -lc -lnosys \ + -Wl,-Map=mapfile -mthumb -mcpu=cortex-m4 -Wl,-gc-sections \ + -mfloat-abi=hard -mfpu=fpv4-sp-d16 \ + -L../libopencm3/lib + +VPATH += platforms/stm32 + +SRC += cdcacm.c \ + traceswodecode.c\ + traceswo.c \ + usbuart.c \ + serialno.c \ + timing.c \ + timing_stm32.c \ + +all: blackmagic.bin + +host_clean: + -$(Q)$(RM) blackmagic.bin diff --git a/src/platforms/f3/Readme b/src/platforms/f3/Readme new file mode 100644 index 0000000..14b9c60 --- /dev/null +++ b/src/platforms/f3/Readme @@ -0,0 +1,20 @@ +Connections: +==================== + +BOOT0: Pull low to force system bootloader entry with reset +PA2/PA3 eventual connected to the STLINK/ STM32F103C8 + +PA0: TDI +PA1: TMS/SWDIO +PA5: NRST +PA6: TDO/TRACESWO +PA7: TCK/SWCLK + +PA9: USB_DETACH_N + +PA2: UART_RX +PA3: UART_TX + +Reflash: +==================== +dfu-util -a0 -s 0x08000000 -D blackmagic.bin \ No newline at end of file diff --git a/src/platforms/f3/platform.c b/src/platforms/f3/platform.c new file mode 100644 index 0000000..6e3a53f --- /dev/null +++ b/src/platforms/f3/platform.c @@ -0,0 +1,117 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2017 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 . + */ + +/* This file implements the platform specific functions for the STM32F3-IF + * implementation. + */ + +#include "general.h" +#include "cdcacm.h" +#include "usbuart.h" +#include "morse.h" + +#include +#include +#include +#include +#include +#include +#include + +extern uint32_t _ebss[]; + +void platform_init(void) +{ + volatile uint32_t *magic = (uint32_t *) &_ebss; + /* If RCC_CFGR is not at it's reset value, the bootloader was executed + * and SET_ADDRESS got us to this place. On F3, without further efforts, + * application does not start in that case. + * So issue an reset to allow a clean start! + */ + if (RCC_CFGR) + scb_reset_system(); + SYSCFG_MEMRM &= ~3; + /* Buttom is BOOT0, so buttom is already evaluated!*/ + if (((magic[0] == BOOTMAGIC0) && (magic[1] == BOOTMAGIC1))) { + magic[0] = 0; + magic[1] = 0; + /* Jump to the built in bootloader by mapping System flash. + As we just come out of reset, no other deinit is needed!*/ + SYSCFG_MEMRM |= 1; + scb_reset_core(); + } + + rcc_clock_setup_pll(&rcc_hse8mhz_configs[RCC_CLOCK_HSE8_72MHZ]); + + /* Enable peripherals */ + rcc_periph_clock_enable(RCC_GPIOA); + rcc_periph_clock_enable(RCC_GPIOB); + rcc_periph_clock_enable(RCC_CRC); + rcc_periph_clock_enable(RCC_USB); + + /* 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_mode_setup(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO12); + gpio_clear(GPIOA, GPIO12); + gpio_set_output_options(GPIOA, GPIO_OTYPE_OD, GPIO_OSPEED_2MHZ, GPIO12); + rcc_periph_reset_pulse(RST_USB); + + GPIOA_OSPEEDR &= ~0xF00C; + GPIOA_OSPEEDR |= 0x5004; /* Set medium speed on PA1, PA6 and PA7*/ + gpio_mode_setup(JTAG_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, + TMS_PIN | TCK_PIN |TDI_PIN); + gpio_mode_setup(TDO_PORT, GPIO_MODE_INPUT, GPIO_PUPD_NONE, TDO_PIN); + gpio_mode_setup(LED_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, + LED_UART | LED_IDLE_RUN | LED_ERROR | LED_BOOTLOADER); + gpio_mode_setup(SRST_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, SRST_PIN); + gpio_set(SRST_PORT, SRST_PIN); + gpio_set_output_options(SRST_PORT, GPIO_OTYPE_OD, + GPIO_OSPEED_2MHZ, SRST_PIN); + platform_timing_init(); + /* Set up USB Pins and alternate function*/ + gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO11 | GPIO12); + gpio_set_af(GPIOA, GPIO_AF14, GPIO11 | GPIO12); + cdcacm_init(); + usbuart_init(); +} + +void platform_srst_set_val(bool assert) +{ + gpio_set_val(SRST_PORT, SRST_PIN, !assert); +} + +bool platform_srst_get_val(void) +{ + return (gpio_get(SRST_PORT, SRST_PIN)) ? false : true; +} + +const char *platform_target_voltage(void) +{ + return "ABSENT!"; +} + +void platform_request_boot(void) +{ + /* Bootloader cares for reenumeration */ + uint32_t *magic = (uint32_t *) &_ebss; + magic[0] = BOOTMAGIC0; + magic[1] = BOOTMAGIC1; + scb_reset_system(); +} diff --git a/src/platforms/f3/platform.h b/src/platforms/f3/platform.h new file mode 100644 index 0000000..7a1a788 --- /dev/null +++ b/src/platforms/f3/platform.h @@ -0,0 +1,163 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2017 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 . + */ + +/* 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 + +#ifdef ENABLE_DEBUG +# define PLATFORM_HAS_DEBUG +# define USBUART_DEBUG +#endif + +#define PLATFORM_IDENT "(F3-IF) " + +/* Important pin mappings for STM32 implementation: + * + * LED0 = PB5 (Green LED : Running) + * LED1 = PB6 (Orange LED : Idle) + * LED2 = PB7 (Red LED : Error) + * + * TDI = PA0 + * TMS = PA1 (input for SWDP) + * TCK = PA7/SWCLK + * TDO = PA6 (input for TRACESWO + * nSRST = PA5 + * + * Force DFU mode button: BOOT0 + */ + +/* Hardware definitions... */ +#define JTAG_PORT GPIOA +#define TDI_PORT JTAG_PORT +#define TMS_PORT JTAG_PORT +#define TCK_PORT JTAG_PORT +#define TDO_PORT JTAG_PORT +#define TDI_PIN GPIO0 +#define TMS_PIN GPIO1 +#define TCK_PIN GPIO7 +#define TDO_PIN GPIO6 + +#define SWDIO_PORT JTAG_PORT +#define SWCLK_PORT JTAG_PORT +#define SWDIO_PIN TMS_PIN +#define SWCLK_PIN TCK_PIN + +#define SRST_PORT GPIOA +#define SRST_PIN GPIO5 + +#define LED_PORT GPIOB +#define LED_PORT_UART GPIOB +#define LED_UART GPIO6 +#define LED_IDLE_RUN GPIO5 +#define LED_ERROR GPIO7 +/* PORTB does not stay active in system bootloader!*/ +#define LED_BOOTLOADER GPIO6 + +#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 USB_DRIVER st_usbfs_v1_usb_driver +#define USB_IRQ NVIC_USB_LP_CAN1_RX0_IRQ +#define USB_ISR usb_lp_can1_rx0_isr + +/* 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 USBUSART USART2 +#define USBUSART_CR1 USART2_CR1 +#define USBUSART_TDR USART2_TDR +#define USBUSART_RDR USART2_RDR +#define USBUSART_IRQ NVIC_USART2_EXTI26_IRQ +#define USBUSART_CLK RCC_USART2 +#define USBUSART_TX_PORT GPIOA +#define USBUSART_TX_PIN GPIO3 +#define USBUSART_RX_PORT GPIOA +#define USBUSART_RX_PIN GPIO2 +#define USBUSART_ISR(x) usart2_exti26_isr(x) + +#define USBUSART_DMA_BUS DMA1 +#define USBUSART_DMA_CLK RCC_DMA1 +#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) + +/* TX/RX on the REV 0/1 boards are swapped against ftdijtag.*/ +#define UART_PIN_SETUP() do { \ + gpio_mode_setup(USBUSART_TX_PORT, GPIO_MODE_AF, GPIO_PUPD_PULLUP, \ + USBUSART_TX_PIN | USBUSART_RX_PIN); \ + gpio_set_af(USBUSART_TX_PORT, GPIO_AF7, \ + USBUSART_TX_PIN | USBUSART_RX_PIN); \ + USART2_CR2 |= USART_CR2_SWAP; \ + } while(0) + +#define TRACE_TIM TIM3 +#define TRACE_TIM_CLK_EN() rcc_periph_clock_enable(RCC_TIM3) +#define TRACE_IRQ NVIC_TIM3_IRQ +#define TRACE_ISR tim3_isr + +#ifdef ENABLE_DEBUG +extern bool debug_bmp; +int usbuart_debug_write(const char *buf, size_t len); +# define DEBUG printf +#else +# 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(state) {gpio_set_val(LED_PORT, LED_ERROR, state);} + +static inline int platform_hwversion(void) +{ + return 0; +} + +/* Use newlib provided integer only stdio functions */ +#define sscanf siscanf +#define sprintf siprintf +#define vasprintf vasiprintf +#define snprintf sniprintf + +#endif diff --git a/src/platforms/f3/stm32f303xc.ld b/src/platforms/f3/stm32f303xc.ld new file mode 100644 index 0000000..f22ce01 --- /dev/null +++ b/src/platforms/f3/stm32f303xc.ld @@ -0,0 +1,30 @@ +/* + * This file is part of the libopencm3 project. + * + * Copyright (C) 2015 Karl Palsson + * + * This library is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This library 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 Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this library. If not, see . + */ + +/* Linker script for the STM32F303xC chip. */ + +/* Define memory regions. */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 40K +} + +/* Include the common ld script. */ +INCLUDE cortex-m-generic.ld