From 327ee49a67772cc7642133cf3f1ecf531e345954 Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Sun, 3 Feb 2013 14:22:14 +0100 Subject: [PATCH] usps_f407: add another platform --- src/platforms/stm32/usbdfu.c | 23 ++- src/platforms/usps_f407/Makefile.inc | 36 +++++ src/platforms/usps_f407/Readme | 22 +++ src/platforms/usps_f407/platform.c | 207 ++++++++++++++++++++++++++ src/platforms/usps_f407/platform.h | 208 +++++++++++++++++++++++++++ 5 files changed, 494 insertions(+), 2 deletions(-) create mode 100644 src/platforms/usps_f407/Makefile.inc create mode 100644 src/platforms/usps_f407/Readme create mode 100644 src/platforms/usps_f407/platform.c create mode 100644 src/platforms/usps_f407/platform.h diff --git a/src/platforms/stm32/usbdfu.c b/src/platforms/stm32/usbdfu.c index 3ffd4da..e42e00f 100644 --- a/src/platforms/stm32/usbdfu.c +++ b/src/platforms/stm32/usbdfu.c @@ -198,6 +198,8 @@ static const char *usb_strings[] = { "Black Magic (Upgrade) for STM32_CAN, (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")", #elif defined(F4DISCOVERY) "Black Magic (Upgrade) for F4Discovery, (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")", +#elif defined(USPS_F407) + "Black Magic (Upgrade) for USPS_F407, (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")", #else #warning "Unhandled board" #endif @@ -209,7 +211,7 @@ static const char *usb_strings[] = { "@Internal Flash /0x08000000/8*001Ka,56*001Kg" #elif defined(STM32_CAN) "@Internal Flash /0x08000000/4*002Ka,124*002Kg" -#elif defined(F4DISCOVERY) +#elif defined(F4DISCOVERY) || defined(USPS_F407) "@Internal Flash /0x08000000/1*016Ka,3*016Kg,1*064Kg,7*128Kg" #else #warning "Unhandled board" @@ -386,6 +388,15 @@ int main(void) #elif defined (F4DISCOVERY) rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPAEN); if(!gpio_get(GPIOA, GPIO0)) { +#elif defined (USPS_F407) + rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPBEN); + /* Pull up an look if external pulled low or if we restart with PB1 low*/ + GPIOB_PUPDR |= 4; + { + int i; + for(i=0; i<100000; i++) __asm__("NOP"); + } + if(gpio_get(GPIOB, GPIO1)) { #else rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN); if(gpio_get(GPIOB, GPIO12)) { @@ -426,7 +437,7 @@ int main(void) #endif /* Set up clock*/ -#if defined (F4DISCOVERY) +#if defined (F4DISCOVERY) || defined(USPS_F407) rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_168MHZ]); systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8); systick_set_reload(2100000); @@ -449,6 +460,7 @@ int main(void) gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12); #elif defined(F4DISCOVERY) +#elif defined(USPS_F407) #elif defined(STM32_CAN) #else rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN); @@ -466,6 +478,11 @@ int main(void) gpio_clear(GPIOD, GPIO12 | GPIO13 | GPIO14 |GPIO15); gpio_mode_setup(GPIOD, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO12 | GPIO13 | GPIO14 |GPIO15); +#elif defined(USPS_F407) + rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPBEN); + gpio_clear(GPIOB, GPIO2); + gpio_mode_setup(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, + GPIO2); #elif defined (STM32_CAN) gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO0); @@ -562,6 +579,8 @@ void sys_tick_handler() led2_state++; #elif defined (F4DISCOVERY) gpio_toggle(GPIOD, GPIO12); /* Green LED on/off */ +#elif defined (USPS_F407) + gpio_toggle(GPIOB, GPIO2); /* Green LED on/off */ #elif defined(STM32_CAN) gpio_toggle(GPIOB, GPIO0); /* LED2 on/off */ #else diff --git a/src/platforms/usps_f407/Makefile.inc b/src/platforms/usps_f407/Makefile.inc new file mode 100644 index 0000000..3bf262d --- /dev/null +++ b/src/platforms/usps_f407/Makefile.inc @@ -0,0 +1,36 @@ +CROSS_COMPILE ?= arm-none-eabi- +CC = $(CROSS_COMPILE)gcc +OBJCOPY = $(CROSS_COMPILE)objcopy + +CFLAGS += -Istm32/include -mcpu=cortex-m3 -mthumb \ + -DSTM32F4 -DUSPS_F407 -I../libopencm3/include + +LDFLAGS_BOOT = -lopencm3_stm32f4 -Wl,--defsym,_stack=0x20020000 \ + -Wl,-T,platforms/stm32/f4discovery.ld -nostartfiles -lc -lnosys \ + -Wl,-Map=mapfile -mthumb -mcpu=cortex-m3 -Wl,-gc-sections \ + -L../libopencm3/lib +LDFLAGS = $(LDFLAGS_BOOT) -Wl,-Ttext=0x8010000 + +VPATH += platforms/stm32 + +SRC += cdcacm.c \ + platform.c \ + traceswo.c \ + usbuart.c \ + +all: blackmagic.bin blackmagic_dfu.bin blackmagic_dfu.hex + +blackmagic.bin: blackmagic + $(OBJCOPY) -O binary $^ $@ + +blackmagic_dfu: usbdfu.o + $(CC) $^ -o $@ $(LDFLAGS_BOOT) + +blackmagic_dfu.bin: blackmagic_dfu + $(OBJCOPY) -O binary $^ $@ + +blackmagic_dfu.hex: blackmagic_dfu + $(OBJCOPY) -O ihex $^ $@ + +host_clean: + -rm blackmagic.bin blackmagic_dfu blackmagic_dfu.bin blackmagic_dfu.hex diff --git a/src/platforms/usps_f407/Readme b/src/platforms/usps_f407/Readme new file mode 100644 index 0000000..ce02015 --- /dev/null +++ b/src/platforms/usps_f407/Readme @@ -0,0 +1,22 @@ +Hardware +======== +Find eagle schematics at +https://github.com/UweBonnes/wiki_fuer_alex/tree/master/layout +The board can be used for F1/L1/F2 and F4 with some changed parts, +see the datasheet and hints in the schematic + +JTAG: Reuse the JTAG Connector, unconnect JTAG Tap and reuse JTAG pins +in inverse direction. +Forced boot request: Connect Jumper Wire X11-34/X11-40 to pull PC15 +to ground +System Bootloader: Jumper Boot0 to '1' + +Led: PB2 (Boot1) + +Application start address: +========================= + +Use 0x8010000 +- lower 3 16 k pages may be used for parameter storage +- Erasing a single 64 k Page is faster then erasing 2 16 k Pages + eventual the 64 k page diff --git a/src/platforms/usps_f407/platform.c b/src/platforms/usps_f407/platform.c new file mode 100644 index 0000000..4541787 --- /dev/null +++ b/src/platforms/usps_f407/platform.c @@ -0,0 +1,207 @@ +/* + * 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 +#include +#include +#include +#include +#include +#include +#include + +#include "platform.h" +#include "jtag_scan.h" +#include + +#include + +uint8_t running_status; +volatile uint32_t timeout_counter; + +jmp_buf fatal_error_jmpbuf; + +static void morse_update(void); + +int platform_init(void) +{ + rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_168MHZ]); + + /* Enable peripherals */ + rcc_peripheral_enable_clock(&RCC_AHB2ENR, RCC_AHB2ENR_OTGFSEN); + rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPAEN); + rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPBEN); + rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPCEN); + + /* Fix all flaoting pins*/ + gpio_mode_setup(GPIOA, GPIO_MODE_INPUT, GPIO_PUPD_PULLDOWN, + 0x1ff); + + gpio_mode_setup(GPIOB, GPIO_MODE_INPUT, GPIO_PUPD_PULLDOWN, + 0xffe2); + + gpio_mode_setup(GPIOC, GPIO_MODE_INPUT, GPIO_PUPD_PULLDOWN, + 0xf3ff); + + /* Set up USB Pins and alternate function*/ + gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, + GPIO9 | GPIO10| GPIO11 | GPIO12); + gpio_set_af(GPIOA, GPIO_AF10, GPIO9 | GPIO10| GPIO11 | GPIO12); + + /* Set TMS/TCK/TDI to high speed*/ + GPIOA_OSPEEDR &=~0xfc00; + GPIOA_OSPEEDR |= 0xa800; + 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 | TRST_PIN); + + gpio_mode_setup(LED_PORT, GPIO_MODE_OUTPUT, + GPIO_PUPD_NONE, + LED_UART ); + + /* Setup heartbeat timer */ + systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8); + systick_set_reload(168000000/(10*8)); /* Interrupt us at 10 Hz */ + SCB_SHPR(11) &= ~((15 << 4) & 0xff); + SCB_SHPR(11) |= ((14 << 4) & 0xff); + systick_interrupt_enable(); + systick_counter_enable(); + + usbuart_init(); + + SCB_VTOR = 0x10000; // Relocate interrupt vector table here + + cdcacm_init(); + + jtag_scan(NULL); + + return 0; +} + +void platform_delay(uint32_t delay) +{ + timeout_counter = delay; + while(timeout_counter); +} + +void sys_tick_handler(void) +{ + if(timeout_counter) + timeout_counter--; + + morse_update(); +} + + +/* Morse code patterns and lengths */ +static const struct { + uint16_t code; + uint8_t bits; +} morse_letter[] = { + { 0b00011101, 8}, // 'A' .- + { 0b000101010111, 12}, // 'B' -... + { 0b00010111010111, 14}, // 'C' -.-. + { 0b0001010111, 10}, // 'D' -.. + { 0b0001, 4}, // 'E' . + { 0b000101110101, 12}, // 'F' ..-. + { 0b000101110111, 12}, // 'G' --. + { 0b0001010101, 10}, // 'H' .... + { 0b000101, 6}, // 'I' .. + {0b0001110111011101, 16}, // 'J' .--- + { 0b000111010111, 12}, // 'K' -.- + { 0b000101011101, 12}, // 'L' .-.. + { 0b0001110111, 10}, // 'M' -- + { 0b00010111, 8}, // 'N' -. + { 0b00011101110111, 14}, // 'O' --- + { 0b00010111011101, 14}, // 'P' .--. + {0b0001110101110111, 16}, // 'Q' --.- + { 0b0001011101, 10}, // 'R' .-. + { 0b00010101, 8}, // 'S' ... + { 0b000111, 6}, // 'T' - + { 0b0001110101, 10}, // 'U' ..- + { 0b000111010101, 12}, // 'V' ...- + { 0b000111011101, 12}, // 'W' .-- + { 0b00011101010111, 14}, // 'X' -..- + {0b0001110111010111, 16}, // 'Y' -.-- + { 0b00010101110111, 14}, // 'Z' --.. +}; + + +const char *morse_msg; +static const char * volatile morse_ptr; +static char morse_repeat; + +void morse(const char *msg, char repeat) +{ + morse_msg = morse_ptr = msg; + morse_repeat = repeat; + SET_ERROR_STATE(0); +} + +static void morse_update(void) +{ + static uint16_t code; + static uint8_t bits; + + if(!morse_ptr) return; + + if(!bits) { + char c = *morse_ptr++; + if(!c) { + if(morse_repeat) { + morse_ptr = morse_msg; + c = *morse_ptr++; + } else { + morse_ptr = 0; + return; + } + } + if((c >= 'A') && (c <= 'Z')) { + c -= 'A'; + code = morse_letter[c].code; + bits = morse_letter[c].bits; + } else { + code = 0; bits = 4; + } + } + SET_ERROR_STATE(code & 1); + code >>= 1; bits--; +} + +const char *platform_target_voltage(void) +{ + return "ABSENT!"; +} + +void assert_boot_pin(void) +{ + /* Flag Bootloader Request by mimicing a pushed USER button*/ + gpio_mode_setup(GPIOB, GPIO_MODE_OUTPUT, + GPIO_PUPD_NONE, GPIO1); + gpio_clear(GPIOB, GPIO11); +} diff --git a/src/platforms/usps_f407/platform.h b/src/platforms/usps_f407/platform.h new file mode 100644 index 0000000..acdfd5c --- /dev/null +++ b/src/platforms/usps_f407/platform.h @@ -0,0 +1,208 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2011 Black Sphere Technologies Ltd. + * Written by Gareth McMullin + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +/* This file implements the platform specific functions for the STM32 + * implementation. + */ +#ifndef __PLATFORM_H +#define __PLATFORM_H + +#include +#include + +#include +#include + +#include "gdb_packet.h" + +#define INLINE_GPIO +#define CDCACM_PACKET_SIZE 64 +#define PLATFORM_HAS_TRACESWO +#define BOARD_IDENT "Black Magic Probe (USPS_F407), (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")" +#define DFU_IDENT "Black Magic Firmware Upgrade (USPS_F407)" + +extern usbd_device *usbdev; +#define CDCACM_GDB_ENDPOINT 1 +#define CDCACM_UART_ENDPOINT 3 + +/* Important pin mappings for STM32 implementation: + * + * LED0 = PB2 + + * TPWR = XXX (input) -- analogue on mini design ADC1, ch8 + * nTRST = PD0 + * SRST_OUT = PD1 + * TDI = PA1 + * TMS = PA3 (input for SWDP) + * TCK = PA8 + * TDO = PB4 (input) + * nSRST = PD2 (input) + * + * USB cable pull-up: PA8 + * USB VBUS detect: PB13 -- New on mini design. + * Enable pull up for compatibility. + * Force DFU mode button: PB1 + */ + +/* 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 TMS_PIN GPIO13 +#define TCK_PIN GPIO14 +#define TDI_PIN GPIO15 +#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 TDO_PORT +#define TRST_PIN GPIO4 +#define SRST_PORT GPIOB +#define SRST_PIN GPIO4 + +#define LED_PORT GPIOB +#define LED_PORT_UART GPIOB +#define LED_UART GPIO2 + +#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 stm32f107_usb_driver +#define USB_IRQ NVIC_OTG_FS_IRQ +#define USB_ISR otg_fs_isr +/* Interrupt priorities. Low numbers are high priority. + * For now USART1 preempts USB which may spin while buffer is drained. + * TIM3 is used for traceswo capture and must be highest priority. + */ +#define IRQ_PRI_USB (2 << 4) +#define IRQ_PRI_USBUSART (1 << 4) +#define IRQ_PRI_TRACE (0 << 4) + +#define USBUSART USART3 +#define USBUSART_CR1 USART3_CR1 +#define USBUSART_IRQ NVIC_USART3_IRQ +#define USBUSART_APB_ENR RCC_APB1ENR +#define USBUSART_CLK_ENABLE RCC_APB1ENR_USART3EN +#define USBUSART_TX_PORT GPIOC +#define USBUSART_TX_PIN GPIO10 +#define USBUSART_RX_PORT GPIOC +#define USBUSART_RX_PIN GPIO11 +#define USBUSART_ISR usart3_isr + +#define UART_PIN_SETUP() do { \ + gpio_mode_setup(USBUSART_TX_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, \ + USBUSART_TX_PIN); \ + gpio_mode_setup(USBUSART_RX_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, \ + USBUSART_RX_PIN); \ + gpio_set_af(USBUSART_TX_PORT, GPIO_AF7, USBUSART_TX_PIN); \ + gpio_set_af(USBUSART_RX_PORT, GPIO_AF7, USBUSART_RX_PIN); \ + } while(0) + +#define TRACE_TIM TIM3 +#define TRACE_TIM_CLK_EN() rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM3EN) +#define TRACE_IRQ NVIC_TIM3_IRQ +#define TRACE_ISR tim3_isr + +#define DEBUG(...) + +extern uint8_t running_status; +extern volatile uint32_t timeout_counter; + +extern jmp_buf fatal_error_jmpbuf; + +extern const char *morse_msg; + +#define gpio_set_val(port, pin, val) do { \ + if(val) \ + gpio_set((port), (pin)); \ + else \ + gpio_clear((port), (pin)); \ +} while(0) + +#define SET_RUN_STATE(state) {running_status = (state);} +#define SET_IDLE_STATE(state) +#define SET_ERROR_STATE(state) + +#define PLATFORM_SET_FATAL_ERROR_RECOVERY() {setjmp(fatal_error_jmpbuf);} +#define PLATFORM_FATAL_ERROR(error) { \ + if(running_status) gdb_putpacketz("X1D"); \ + else gdb_putpacketz("EFF"); \ + running_status = 0; \ + target_list_free(); \ + morse("TARGET LOST.", 1); \ + longjmp(fatal_error_jmpbuf, (error)); \ +} + +int platform_init(void); +void morse(const char *msg, char repeat); +const char *platform_target_voltage(void); +int platform_hwversion(void); +void platform_delay(uint32_t delay); + +/* */ +void cdcacm_init(void); +/* Returns current usb configuration, or 0 if not configured. */ +int cdcacm_get_config(void); +int cdcacm_get_dtr(void); + +/* */ +void uart_usb_buf_drain(uint8_t ep); + +/* Use newlib provided integer only stdio functions */ +#define sscanf siscanf +#define sprintf siprintf +#define vasprintf vasiprintf + +#ifdef INLINE_GPIO +static inline void _gpio_set(u32 gpioport, u16 gpios) +{ + GPIO_BSRR(gpioport) = gpios; +} +#define gpio_set _gpio_set + +static inline void _gpio_clear(u32 gpioport, u16 gpios) +{ + GPIO_BSRR(gpioport) = gpios<<16; +} +#define gpio_clear _gpio_clear + +static inline u16 _gpio_get(u32 gpioport, u16 gpios) +{ + return (u16)GPIO_IDR(gpioport) & gpios; +} +#define gpio_get _gpio_get +#endif + +#endif + +#define disconnect_usb() do {usbd_disconnect(usbdev,1); nvic_disable_irq(USB_IRQ);} while(0) +void assert_boot_pin(void); +#define setup_vbus_irq()