aboutsummaryrefslogtreecommitdiff
path: root/src/platforms/stlink
diff options
context:
space:
mode:
authorNicolas Schodet2015-05-11 11:44:13 +0200
committerNicolas Schodet2015-06-16 17:00:31 +0200
commitb877293fd8603270854876f8c7e6a6d46fb49c2c (patch)
tree580838207cb8a0b5d980a6b1d2cc5b3d5420fb90 /src/platforms/stlink
parent21b3aba640e492b49140cb9c994f97a61ca51d29 (diff)
parent482070c91b0cc5a5f16c02a30e26e306685566bb (diff)
Merge remote-tracking branch 'github/master' into dev2
Conflicts: src/main.c
Diffstat (limited to 'src/platforms/stlink')
-rw-r--r--src/platforms/stlink/Makefile.inc27
-rw-r--r--src/platforms/stlink/dfu_upgrade.c125
-rw-r--r--src/platforms/stlink/platform.c164
-rw-r--r--src/platforms/stlink/platform.h134
-rw-r--r--src/platforms/stlink/usbdfu.c55
5 files changed, 279 insertions, 226 deletions
diff --git a/src/platforms/stlink/Makefile.inc b/src/platforms/stlink/Makefile.inc
index 627b14b..fdee700 100644
--- a/src/platforms/stlink/Makefile.inc
+++ b/src/platforms/stlink/Makefile.inc
@@ -2,10 +2,12 @@ CROSS_COMPILE ?= arm-none-eabi-
CC = $(CROSS_COMPILE)gcc
OBJCOPY = $(CROSS_COMPILE)objcopy
+OPT_FLAGS = -Os
CFLAGS += -mcpu=cortex-m3 -mthumb \
-DSTM32F1 -DDISCOVERY_STLINK -I../libopencm3/include \
-I platforms/stm32
-LDFLAGS_BOOT = -lopencm3_stm32f1 -Wl,--defsym,_stack=0x20005000 \
+LDFLAGS_BOOT := $(LDFLAGS) --specs=nano.specs \
+ -lopencm3_stm32f1 -Wl,--defsym,_stack=0x20005000 \
-Wl,-T,platforms/stm32/stlink.ld -nostartfiles -lc -lnosys \
-Wl,-Map=mapfile -mthumb -mcpu=cortex-m3 -Wl,-gc-sections \
-L../libopencm3/lib
@@ -14,23 +16,20 @@ LDFLAGS = $(LDFLAGS_BOOT) -Wl,-Ttext=0x8002000
VPATH += platforms/stm32
SRC += cdcacm.c \
- platform.c \
- usbuart.c \
+ usbuart.c \
+ serialno.c \
+ timing.c \
-all: blackmagic.bin blackmagic_dfu.bin blackmagic_dfu.hex
-
-blackmagic.bin: blackmagic
- $(OBJCOPY) -O binary $^ $@
+all: blackmagic.bin blackmagic_dfu.bin blackmagic_dfu.hex dfu_upgrade.bin dfu_upgrade.hex
blackmagic_dfu: usbdfu.o dfucore.o dfu_f1.o
- $(CC) $^ -o $@ $(LDFLAGS_BOOT)
-
-blackmagic_dfu.bin: blackmagic_dfu
- $(OBJCOPY) -O binary $^ $@
+ @echo " LD $@"
+ $(Q)$(CC) $^ -o $@ $(LDFLAGS_BOOT)
-blackmagic_dfu.hex: blackmagic_dfu
- $(OBJCOPY) -O ihex $^ $@
+dfu_upgrade: dfu_upgrade.o dfucore.o dfu_f1.o
+ @echo " LD $@"
+ $(Q)$(CC) $^ -o $@ $(LDFLAGS)
host_clean:
- -rm blackmagic.bin blackmagic_dfu blackmagic_dfu.bin blackmagic_dfu.hex
+ -$(Q)$(RM) blackmagic.bin blackmagic_dfu blackmagic_dfu.bin blackmagic_dfu.hex dfu_upgrade dfu_upgrade.bin dfu_upgrade.hex
diff --git a/src/platforms/stlink/dfu_upgrade.c b/src/platforms/stlink/dfu_upgrade.c
new file mode 100644
index 0000000..4a3648a
--- /dev/null
+++ b/src/platforms/stlink/dfu_upgrade.c
@@ -0,0 +1,125 @@
+/*
+ * This file is part of the Black Magic Debug project.
+ *
+ * Copyright (C) 2013 Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * 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 <http://www.gnu.org/licenses/>.
+ */
+
+#include <string.h>
+#include <libopencm3/cm3/systick.h>
+#include <libopencm3/stm32/rcc.h>
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/cm3/scb.h>
+
+#include "usbdfu.h"
+uint32_t app_address = 0x08000000;
+
+static uint8_t rev;
+static uint16_t led_idle_run;
+static uint32_t led2_state = 0;
+
+void dfu_detach(void)
+{
+ /* 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);
+ /* Pull PB0 (T_NRST) low
+ */
+ rcc_periph_clock_enable(RCC_GPIOB);
+ gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_OPENDRAIN, GPIO0);
+ gpio_clear(GPIOB, GPIO0);
+ SCB_VTOR = 0;
+ scb_reset_core();
+}
+
+void stlink_set_rev(void)
+{
+ int i;
+
+ /* First, get Board revision by pulling PC13/14 up. Read
+ * 11 for ST-Link V1, e.g. on VL Discovery, tag as rev 0
+ * 10 for ST-Link V2, e.g. on F4 Discovery, tag as rev 1
+ */
+ rcc_periph_clock_enable(RCC_GPIOC);
+ gpio_set_mode(GPIOC, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_PULL_UPDOWN, GPIO14 | GPIO13);
+ gpio_set(GPIOC, GPIO14 | GPIO13);
+ for (i = 0; i < 100; i++)
+ rev = (~(gpio_get(GPIOC, GPIO14 | GPIO13)) >> 13) & 3;
+
+ switch (rev) {
+ case 0:
+ led_idle_run = GPIO8;
+ break;
+ default:
+ led_idle_run = GPIO9;
+ }
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, led_idle_run);
+}
+
+int main(void)
+{
+
+ rcc_clock_setup_in_hse_8mhz_out_72mhz();
+
+ stlink_set_rev();
+
+ systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8);
+ systick_set_reload(900000);
+
+ dfu_protect(UPD_MODE);
+
+ /* 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);
+
+ systick_interrupt_enable();
+ systick_counter_enable();
+
+ dfu_init(&stm32f103_usb_driver, UPD_MODE);
+
+ dfu_main();
+}
+
+void sys_tick_handler(void)
+{
+ if (rev == 0) {
+ gpio_toggle(GPIOA, led_idle_run);
+ } else {
+ if (led2_state & 1) {
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, led_idle_run);
+ gpio_set(GPIOA, led_idle_run);
+ } else {
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_ANALOG, led_idle_run);
+ }
+ led2_state++;
+ }
+}
diff --git a/src/platforms/stlink/platform.c b/src/platforms/stlink/platform.c
index 5eaf5fc..dd501a4 100644
--- a/src/platforms/stlink/platform.c
+++ b/src/platforms/stlink/platform.c
@@ -22,25 +22,20 @@
* implementation.
*/
-#include <libopencm3/stm32/f1/rcc.h>
-#include <libopencm3/cm3/systick.h>
+#include "general.h"
+#include "cdcacm.h"
+#include "usbuart.h"
+
+#include <libopencm3/stm32/rcc.h>
#include <libopencm3/cm3/scb.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/usb/usbd.h>
-#include <libopencm3/stm32/f1/adc.h>
-
-#include "platform.h"
-#include "jtag_scan.h"
-#include <usbuart.h>
-
-#include <ctype.h>
+#include <libopencm3/stm32/adc.h>
uint8_t running_status;
volatile uint32_t timeout_counter;
-jmp_buf fatal_error_jmpbuf;
-
uint16_t led_idle_run;
/* Pins PC[14:13] are used to detect hardware revision. Read
* 11 for STLink V1 e.g. on VL Discovery, tag as hwversion 0
@@ -49,98 +44,78 @@ uint16_t led_idle_run;
int platform_hwversion(void)
{
static int hwversion = -1;
- int i;
+ int i;
if (hwversion == -1) {
gpio_set_mode(GPIOC, GPIO_MODE_INPUT,
- GPIO_CNF_INPUT_PULL_UPDOWN,
- GPIO14 | GPIO13);
+ GPIO_CNF_INPUT_PULL_UPDOWN, GPIO14 | GPIO13);
gpio_set(GPIOC, GPIO14 | GPIO13);
- for (i = 0; i<10; i++)
- hwversion = ~(gpio_get(GPIOC, GPIO14 | GPIO13) >> 13) & 3;
- switch (hwversion)
- {
- case 0:
- led_idle_run = GPIO8;
- break;
- default:
- led_idle_run = GPIO9;
- }
+ for (i = 0; i<10; i++)
+ hwversion = ~(gpio_get(GPIOC, GPIO14 | GPIO13) >> 13) & 3;
+ switch (hwversion)
+ {
+ case 0:
+ led_idle_run = GPIO8;
+ break;
+ default:
+ led_idle_run = GPIO9;
+ }
}
return hwversion;
}
-int platform_init(void)
+void platform_init(void)
{
rcc_clock_setup_in_hse_8mhz_out_72mhz();
/* Enable peripherals */
- rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
+ rcc_periph_clock_enable(RCC_USB);
+ 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);
/* On Rev 1 unconditionally activate MCO on PORTA8 with HSE
- * platform_hwversion() also needed to initialize led_idle_run!
- */
- if (platform_hwversion() == 1)
- {
- RCC_CFGR &= ~( 0xf<< 24);
- RCC_CFGR |= (RCC_CFGR_MCO_HSECLK << 24);
- gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
- GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO8);
- }
+ * platform_hwversion() also needed to initialize led_idle_run!
+ */
+ if (platform_hwversion() == 1)
+ {
+ RCC_CFGR &= ~(0xf << 24);
+ RCC_CFGR |= (RCC_CFGR_MCO_HSECLK << 24);
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO8);
+ }
/* Setup GPIO ports */
- gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ,
- GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN);
- gpio_set_mode(TCK_PORT, GPIO_MODE_OUTPUT_50_MHZ,
- GPIO_CNF_OUTPUT_PUSHPULL, TCK_PIN);
- gpio_set_mode(TDI_PORT, GPIO_MODE_OUTPUT_50_MHZ,
- GPIO_CNF_OUTPUT_PUSHPULL, TDI_PIN);
-
- gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_2_MHZ,
- GPIO_CNF_OUTPUT_PUSHPULL, led_idle_run);
-
- /* Setup heartbeat timer */
- systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
- systick_set_reload(900000); /* 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 = 0x2000; // Relocate interrupt vector table here
-
+ gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN);
+ gpio_set_mode(TCK_PORT, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, TCK_PIN);
+ gpio_set_mode(TDI_PORT, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, TDI_PIN);
+ uint16_t srst_pin = platform_hwversion() == 0 ?
+ SRST_PIN_V1 : SRST_PIN_V2;
+ gpio_set(SRST_PORT, srst_pin);
+ gpio_set_mode(SRST_PORT, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_OPENDRAIN, srst_pin);
+
+ gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, led_idle_run);
+
+ SCB_VTOR = 0x2000; /* Relocate interrupt vector table here */
+
+ platform_timing_init();
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(running_status)
- gpio_toggle(LED_PORT, led_idle_run);
-
- if(timeout_counter)
- timeout_counter--;
+ usbuart_init();
}
-const char *morse_msg;
-
-void morse(const char *msg, char repeat)
+void platform_srst_set_val(bool assert)
{
- (void)repeat;
- morse_msg = msg;
+ uint16_t pin;
+ pin = platform_hwversion() == 0 ? SRST_PIN_V1 : SRST_PIN_V2;
+ if (assert)
+ gpio_clear(SRST_PORT, pin);
+ else
+ gpio_set(SRST_PORT, pin);
}
const char *platform_target_voltage(void)
@@ -148,22 +123,19 @@ const char *platform_target_voltage(void)
return "unknown";
}
-void disconnect_usb(void)
+void platform_request_boot(void)
{
/* Disconnect USB cable by resetting USB Device and pulling USB_DP low*/
- rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
- rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
- rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ 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);
-}
+ GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12);
-void assert_boot_pin(void)
-{
+ /* Assert bootloader pin */
uint32_t crl = GPIOA_CRL;
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ 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
@@ -172,4 +144,4 @@ void assert_boot_pin(void)
crl |= 0x80;
GPIOA_CRL = crl;
}
-void setup_vbus_irq(void){};
+
diff --git a/src/platforms/stlink/platform.h b/src/platforms/stlink/platform.h
index cbfc0ba..498e512 100644
--- a/src/platforms/stlink/platform.h
+++ b/src/platforms/stlink/platform.h
@@ -24,24 +24,20 @@
#ifndef __PLATFORM_H
#define __PLATFORM_H
-#include <libopencm3/stm32/f1/gpio.h>
-#include <libopencm3/usb/usbd.h>
-
-#include <setjmp.h>
-#include <alloca.h>
+#include "gpio.h"
+#include "timing.h"
+#include "version.h"
-#include "gdb_packet.h"
-
-#define INLINE_GPIO
-#define CDCACM_PACKET_SIZE 64
-#define BOARD_IDENT "Black Magic Probe (STLINK), (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")"
-#define BOARD_IDENT_DFU "Black Magic (Upgrade) for STLink/Discovery, (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")"
-#define DFU_IDENT "Black Magic Firmware Upgrade (STLINK)"
-#define DFU_IFACE_STRING "@Internal Flash /0x08000000/8*001Ka,56*001Kg"
+#include <libopencm3/cm3/common.h>
+#include <libopencm3/stm32/f1/memorymap.h>
+#include <libopencm3/usb/usbd.h>
-extern usbd_device *usbdev;
-#define CDCACM_GDB_ENDPOINT 1
-#define CDCACM_UART_ENDPOINT 3
+#define BOARD_IDENT "Black Magic Probe (STLINK), (Firmware " FIRMWARE_VERSION ")"
+#define BOARD_IDENT_DFU "Black Magic (Upgrade) for STLink/Discovery, (Firmware " FIRMWARE_VERSION ")"
+#define BOARD_IDENT_UPD "Black Magic (DFU Upgrade) for STLink/Discovery, (Firmware " FIRMWARE_VERSION ")"
+#define DFU_IDENT "Black Magic Firmware Upgrade (STLINK)"
+#define DFU_IFACE_STRING "@Internal Flash /0x08000000/8*001Ka,56*001Kg"
+#define UPD_IFACE_STRING "@Internal Flash /0x08000000/8*001Kg"
/* Important pin mappings for STM32 implementation:
*
@@ -59,7 +55,7 @@ extern usbd_device *usbdev;
* nSRST = PA7 (input)
*
* USB cable pull-up: PA8
- * USB VBUS detect: PB13 -- New on mini design.
+ * USB VBUS detect: PB13 -- New on mini design.
* Enable pull up for compatibility.
* Force DFU mode button: PB12
*/
@@ -79,115 +75,69 @@ extern usbd_device *usbdev;
#define SWDIO_PIN TMS_PIN
#define SWCLK_PIN TCK_PIN
+#define SRST_PORT GPIOB
+#define SRST_PIN_V1 GPIO1
+#define SRST_PIN_V2 GPIO0
+
#define LED_PORT GPIOA
/* 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 TMS_SET_MODE() \
- gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ, \
- GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN);
-#define SWDIO_MODE_FLOAT() \
- gpio_set_mode(SWDIO_PORT, GPIO_MODE_INPUT, \
- GPIO_CNF_INPUT_FLOAT, SWDIO_PIN);
-#define SWDIO_MODE_DRIVE() \
- gpio_set_mode(SWDIO_PORT, GPIO_MODE_OUTPUT_50_MHZ, \
- GPIO_CNF_OUTPUT_PUSHPULL, SWDIO_PIN);
+#define TMS_SET_MODE() \
+ gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ, \
+ GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN);
+#define SWDIO_MODE_FLOAT() \
+ gpio_set_mode(SWDIO_PORT, GPIO_MODE_INPUT, \
+ GPIO_CNF_INPUT_FLOAT, SWDIO_PIN);
+#define SWDIO_MODE_DRIVE() \
+ gpio_set_mode(SWDIO_PORT, GPIO_MODE_OUTPUT_50_MHZ, \
+ GPIO_CNF_OUTPUT_PUSHPULL, SWDIO_PIN);
+
+#define UART_PIN_SETUP() \
+ gpio_set_mode(USBUSART_PORT, GPIO_MODE_OUTPUT_2_MHZ, \
+ GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USBUSART_TX_PIN);
-#define UART_PIN_SETUP() \
- gpio_set_mode(USBUSART_PORT, GPIO_MODE_OUTPUT_2_MHZ, \
- GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USBUSART_TX_PIN);
+#define SRST_SET_VAL(x) \
+ platform_srst_set_val(x)
#define USB_DRIVER stm32f103_usb_driver
-#define USB_IRQ NVIC_USB_LP_CAN_RX0_IRQ
-#define USB_ISR usb_lp_can_rx0_isr
+#define USB_IRQ NVIC_USB_LP_CAN_RX0_IRQ
+#define USB_ISR usb_lp_can_rx0_isr
/* Interrupt priorities. Low numbers are high priority.
* For now USART2 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_USBUSART_TIM (3 << 4)
#define IRQ_PRI_USB_VBUS (14 << 4)
#define IRQ_PRI_TIM3 (0 << 4)
#define USBUSART USART2
#define USBUSART_CR1 USART2_CR1
#define USBUSART_IRQ NVIC_USART2_IRQ
-#define USBUSART_APB_ENR RCC_APB1ENR
-#define USBUSART_CLK_ENABLE RCC_APB1ENR_USART2EN
+#define USBUSART_CLK RCC_USART2
#define USBUSART_PORT GPIOA
#define USBUSART_TX_PIN GPIO2
#define USBUSART_ISR usart2_isr
+#define USBUSART_TIM TIM4
+#define USBUSART_TIM_CLK_EN() rcc_periph_clock_enable(RCC_TIM4)
+#define USBUSART_TIM_IRQ NVIC_TIM4_IRQ
+#define USBUSART_TIM_ISR tim4_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)
-
extern uint16_t led_idle_run;
+#define LED_IDLE_RUN led_idle_run
#define SET_RUN_STATE(state) {running_status = (state);}
#define SET_IDLE_STATE(state) {gpio_set_val(LED_PORT, led_idle_run, 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(); \
- longjmp(fatal_error_jmpbuf, (error)); \
-}
-
-int platform_init(void);
-void morse(const char *msg, char repeat);
-const char *platform_target_voltage(void);
-void platform_delay(uint32_t delay);
-
-/* <cdcacm.c> */
-void cdcacm_init(void);
-/* Returns current usb configuration, or 0 if not configured. */
-int cdcacm_get_config(void);
-int cdcacm_get_dtr(void);
-
-/* <platform.h> */
-void uart_usb_buf_drain(uint8_t ep);
+#define SET_ERROR_STATE(x)
/* 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_BRR(gpioport) = gpios;
-}
-#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
-void disconnect_usb(void);
-void assert_boot_pin(void);
diff --git a/src/platforms/stlink/usbdfu.c b/src/platforms/stlink/usbdfu.c
index f688c1c..b42ec20 100644
--- a/src/platforms/stlink/usbdfu.c
+++ b/src/platforms/stlink/usbdfu.c
@@ -29,24 +29,31 @@ static uint8_t rev;
static uint16_t led_idle_run;
static uint32_t led2_state = 0;
+uint32_t app_address = 0x08002000;
+
static int stlink_test_nrst(void)
{
/* Test if JRST/NRST is pulled down*/
- int i;
uint16_t nrst;
uint16_t pin;
+ uint32_t systick_value;
+
+ systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8);
+ systick_set_reload(0xffffff); /* no underflow for about 16.7 seconds*/
+ systick_counter_enable();
+ /* systick ist now running with 1 MHz, systick counts down */
/* First, get Board revision by pulling PC13/14 up. Read
* 11 for ST-Link V1, e.g. on VL Discovery, tag as rev 0
* 10 for ST-Link V2, e.g. on F4 Discovery, tag as rev 1
*/
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
+ rcc_periph_clock_enable(RCC_GPIOC);
gpio_set_mode(GPIOC, GPIO_MODE_INPUT,
- GPIO_CNF_INPUT_PULL_UPDOWN, GPIO14 | GPIO13);
+ GPIO_CNF_INPUT_PULL_UPDOWN, GPIO14 | GPIO13);
gpio_set(GPIOC, GPIO14 | GPIO13);
- for (i = 0; i < 100; i++)
- rev = (~(gpio_get(GPIOC, GPIO14 | GPIO13)) >> 13) & 3;
-
+ systick_value = systick_get_value();
+ while (systick_get_value() > (systick_value - 1000)); /* Wait 1 msec*/
+ rev = (~(gpio_get(GPIOC, GPIO14 | GPIO13)) >> 13) & 3;
switch (rev) {
case 0:
pin = GPIO1;
@@ -58,12 +65,14 @@ static int stlink_test_nrst(void)
}
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, led_idle_run);
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
+ rcc_periph_clock_enable(RCC_GPIOB);
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, pin);
gpio_set(GPIOB, pin);
- for (i = 0; i < 100; i++)
- nrst = gpio_get(GPIOB, pin);
+ systick_value = systick_get_value();
+ while (systick_get_value() > (systick_value - 20000)); /* Wait 20 msec*/
+ nrst = gpio_get(GPIOB, pin);
+ systick_counter_disable();
return (nrst) ? 1 : 0;
}
@@ -71,10 +80,9 @@ void dfu_detach(void)
{
/* Disconnect USB cable by resetting USB Device
and pulling USB_DP low*/
- rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
- rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
- rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ 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);
@@ -84,7 +92,7 @@ void dfu_detach(void)
int main(void)
{
/* Check the force bootloader pin*/
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ rcc_periph_clock_enable(RCC_GPIOA);
/* Check value of GPIOA1 configuration. This pin is unconnected on
* STLink V1 and V2. If we have a value other than the reset value (0x4),
* we have a warm start and request Bootloader entry
@@ -92,20 +100,19 @@ int main(void)
if(((GPIOA_CRL & 0x40) == 0x40) && stlink_test_nrst())
dfu_jump_app_if_valid();
- dfu_protect_enable();
+ dfu_protect(DFU_MODE);
rcc_clock_setup_in_hse_8mhz_out_72mhz();
- systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
+ systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8);
systick_set_reload(900000);
- /* Handle USB disconnect/connect */
+ /* 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_peripheral_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
- rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
- rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ * 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);
@@ -113,7 +120,7 @@ int main(void)
systick_interrupt_enable();
systick_counter_enable();
- dfu_init(&stm32f103_usb_driver);
+ dfu_init(&stm32f103_usb_driver, DFU_MODE);
dfu_main();
}