f4discovery: Adapt from the "native" file and add or change code where needed

- stm32_mem.py has problems with erasing the big pages, but dfu-util works
- serial GDB remote server doesn't work. It neither works for the STM32F107,
  so maybe there is a problem with the usbd_f107_driver.
This commit is contained in:
Uwe Bonnes 2013-01-17 20:05:25 +01:00
parent e373619374
commit 04624af4e5
7 changed files with 264 additions and 219 deletions

View File

@ -3,13 +3,13 @@ CC = $(CROSS_COMPILE)gcc
OBJCOPY = $(CROSS_COMPILE)objcopy OBJCOPY = $(CROSS_COMPILE)objcopy
CFLAGS += -Istm32/include -mcpu=cortex-m3 -mthumb \ CFLAGS += -Istm32/include -mcpu=cortex-m3 -mthumb \
-DSTM32F1 -DBLACKMAGIC -I../libopencm3/include -DSTM32F4 -DF4DISCOVERY -I../libopencm3/include
LDFLAGS_BOOT = -lopencm3_stm32f1 -Wl,--defsym,_stack=0x20005000 \ LDFLAGS_BOOT = -lopencm3_stm32f4 -Wl,--defsym,_stack=0x20020000 \
-Wl,-T,platforms/stm32/blackmagic.ld -nostartfiles -lc -lnosys \ -Wl,-T,platforms/stm32/f4discovery.ld -nostartfiles -lc -lnosys \
-Wl,-Map=mapfile -mthumb -mcpu=cortex-m3 -Wl,-gc-sections \ -Wl,-Map=mapfile -mthumb -mcpu=cortex-m3 -Wl,-gc-sections \
-L../libopencm3/lib -L../libopencm3/lib
LDFLAGS = $(LDFLAGS_BOOT) -Wl,-Ttext=0x8002000 LDFLAGS = $(LDFLAGS_BOOT) -Wl,-Ttext=0x8010000
VPATH += platforms/stm32 VPATH += platforms/stm32

View File

@ -0,0 +1,17 @@
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
Internal boot loader:
====================
When we request invokation of a bootloader from inside the application,
we boot the device internal bootloader with the blue botton pressed.
That way, we can easy exchange the custom bootloader via the device
internale bootloader

View File

@ -22,14 +22,14 @@
* implementation. * implementation.
*/ */
#include <libopencm3/stm32/f1/rcc.h> #include <libopencm3/stm32/f4/rcc.h>
#include <libopencm3/cm3/systick.h> #include <libopencm3/cm3/systick.h>
#include <libopencm3/cm3/scb.h> #include <libopencm3/cm3/scb.h>
#include <libopencm3/cm3/nvic.h> #include <libopencm3/cm3/nvic.h>
#include <libopencm3/stm32/exti.h> #include <libopencm3/stm32/exti.h>
#include <libopencm3/stm32/usart.h> #include <libopencm3/stm32/usart.h>
#include <libopencm3/stm32/syscfg.h>
#include <libopencm3/usb/usbd.h> #include <libopencm3/usb/usbd.h>
#include <libopencm3/stm32/f1/adc.h>
#include "platform.h" #include "platform.h"
#include "jtag_scan.h" #include "jtag_scan.h"
@ -44,64 +44,39 @@ jmp_buf fatal_error_jmpbuf;
static void morse_update(void); static void morse_update(void);
static void adc_init(void);
/* Pins PB[7:5] are used to detect hardware revision.
* 000 - Original production build.
* 001 - Mini production build.
*/
int platform_hwversion(void)
{
static int hwversion = -1;
if (hwversion == -1) {
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN,
GPIO7 | GPIO6 | GPIO5);
gpio_clear(GPIOB, GPIO7 | GPIO6 | GPIO5);
hwversion = gpio_get(GPIOB, GPIO7 | GPIO6 | GPIO5) >> 5;
}
return hwversion;
}
int platform_init(void) int platform_init(void)
{ {
rcc_clock_setup_in_hse_8mhz_out_72mhz(); rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_168MHZ]);
/* Enable peripherals */ /* Enable peripherals */
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN); rcc_peripheral_enable_clock(&RCC_AHB2ENR, RCC_AHB2ENR_OTGFSEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN); rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN); rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN); rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPDEN);
/* Setup GPIO ports */
gpio_clear(USB_PU_PORT, USB_PU_PIN);
gpio_set_mode(USB_PU_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT,
USB_PU_PIN);
gpio_set_mode(JTAG_PORT, GPIO_MODE_OUTPUT_50_MHZ, /* Set up USB Pins and alternate function*/
GPIO_CNF_OUTPUT_PUSHPULL, gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE,
GPIO9 | GPIO11 | GPIO12);
gpio_set_af(GPIOA, GPIO_AF10, GPIO9 | GPIO11 | GPIO12);
GPIOA_OSPEEDR &=~0xfc;
GPIOA_OSPEEDR |= 0xa8;
gpio_mode_setup(JTAG_PORT, GPIO_MODE_OUTPUT,
GPIO_PUPD_NONE,
TMS_PIN | TCK_PIN | TDI_PIN); TMS_PIN | TCK_PIN | TDI_PIN);
/* This needs some fixing... */ gpio_mode_setup(TDO_PORT, GPIO_MODE_INPUT,
/* Toggle required to sort out line drivers... */ GPIO_PUPD_NONE,
gpio_port_write(GPIOA, 0x8100); TDO_PIN);
gpio_port_write(GPIOB, 0x2000);
gpio_port_write(GPIOA, 0x8180); gpio_mode_setup(LED_PORT, GPIO_MODE_OUTPUT,
gpio_port_write(GPIOB, 0x2002); GPIO_PUPD_NONE,
LED_UART | LED_IDLE_RUN | LED_ERROR | LED_SPARE1);
gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL,
LED_UART | LED_IDLE_RUN | LED_ERROR);
/* FIXME: This pin in intended to be input, but the TXS0108 fails
* to release the device from reset if this floats. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
/* Setup heartbeat timer */ /* Setup heartbeat timer */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8); systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
systick_set_reload(900000); /* Interrupt us at 10 Hz */ systick_set_reload(168000000/(10*8)); /* Interrupt us at 10 Hz */
SCB_SHPR(11) &= ~((15 << 4) & 0xff); SCB_SHPR(11) &= ~((15 << 4) & 0xff);
SCB_SHPR(11) |= ((14 << 4) & 0xff); SCB_SHPR(11) |= ((14 << 4) & 0xff);
systick_interrupt_enable(); systick_interrupt_enable();
@ -109,15 +84,7 @@ int platform_init(void)
usbuart_init(); usbuart_init();
if (platform_hwversion() > 0) { SCB_VTOR = 0x10000; // Relocate interrupt vector table here
adc_init();
} else {
gpio_clear(GPIOB, GPIO0);
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, GPIO0);
}
SCB_VTOR = 0x2000; // Relocate interrupt vector table here
cdcacm_init(); cdcacm_init();
@ -219,88 +186,23 @@ static void morse_update(void)
code >>= 1; bits--; code >>= 1; bits--;
} }
static void adc_init(void)
{
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN);
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_ANALOG, GPIO0);
adc_off(ADC1);
adc_disable_scan_mode(ADC1);
adc_set_single_conversion_mode(ADC1);
adc_disable_external_trigger_regular(ADC1);
adc_set_right_aligned(ADC1);
adc_set_conversion_time_on_all_channels(ADC1, ADC_SMPR_SMP_28DOT5CYC);
adc_power_on(ADC1);
/* Wait for ADC starting up. */
for (int i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
adc_reset_calibration(ADC1);
adc_calibration(ADC1);
}
const char *platform_target_voltage(void) const char *platform_target_voltage(void)
{ {
if (platform_hwversion() == 0) return "ABSENT!";
return gpio_get(GPIOB, GPIO0) ? "OK" : "ABSENT!";
static char ret[] = "0.0V";
const u8 channel = 8;
adc_set_regular_sequence(ADC1, 1, (u8*)&channel);
adc_on(ADC1);
/* Wait for end of conversion. */
while (!(ADC_SR(ADC1) & ADC_SR_EOC));
u32 val = ADC_DR(ADC1) * 99; /* 0-4095 */
ret[0] = '0' + val / 81910;
ret[2] = '0' + (val / 8191) % 10;
return ret;
} }
void assert_boot_pin(void) void assert_boot_pin(void)
{ {
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ, if (gpio_get(GPIOA, GPIO0)) {
GPIO_CNF_OUTPUT_PUSHPULL, GPIO12); /* Jump to the built in bootloader by mapping System flash */
gpio_clear(GPIOB, GPIO12); rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_SYSCFGEN);
SYSCFG_MEMRM &= ~3;
SYSCFG_MEMRM |= 1;
} }
else {
void exti15_10_isr(void) /* Flag Bootloader Request by mimicing a pushed USER button*/
{ gpio_mode_setup(GPIOA, GPIO_MODE_OUTPUT,
if (gpio_get(USB_VBUS_PORT, USB_VBUS_PIN)) { GPIO_PUPD_NONE, GPIO0);
/* Drive pull-up high if VBUS connected */ gpio_set(GPIOA, GPIO0);
gpio_set_mode(USB_PU_PORT, GPIO_MODE_OUTPUT_10_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, USB_PU_PIN);
} else {
/* Allow pull-up to float if VBUS disconnected */
gpio_set_mode(USB_PU_PORT, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, USB_PU_PIN);
} }
exti_reset_request(USB_VBUS_PIN);
}
void setup_vbus_irq(void)
{
nvic_set_priority(USB_VBUS_IRQ, IRQ_PRI_USB_VBUS);
nvic_enable_irq(USB_VBUS_IRQ);
gpio_set(USB_VBUS_PORT, USB_VBUS_PIN);
gpio_set(USB_PU_PORT, USB_PU_PIN);
gpio_set_mode(USB_VBUS_PORT, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, USB_VBUS_PIN);
/* Configure EXTI for USB VBUS monitor */
exti_select_source(USB_VBUS_PIN, USB_VBUS_PORT);
exti_set_trigger(USB_VBUS_PIN, EXTI_TRIGGER_BOTH);
exti_enable_request(USB_VBUS_PIN);
exti15_10_isr();
} }

View File

@ -24,7 +24,7 @@
#ifndef __PLATFORM_H #ifndef __PLATFORM_H
#define __PLATFORM_H #define __PLATFORM_H
#include <libopencm3/stm32/f1/gpio.h> #include <libopencm3/stm32/f4/gpio.h>
#include <libopencm3/usb/usbd.h> #include <libopencm3/usb/usbd.h>
#include <setjmp.h> #include <setjmp.h>
@ -42,18 +42,18 @@ extern usbd_device *usbdev;
/* Important pin mappings for STM32 implementation: /* Important pin mappings for STM32 implementation:
* *
* LED0 = PB2 (Yellow LED : Running) * LED0 = PD12 (Green LED : Running)
* LED1 = PB10 (Yellow LED : Idle) * LED1 = PD13 (Orange LED : Idle)
* LED2 = PB11 (Red LED : Error) * LED2 = PD12 (Red LED : Error)
* *
* TPWR = RB0 (input) -- analogue on mini design ADC1, ch8 * TPWR = XXX (input) -- analogue on mini design ADC1, ch8
* nTRST = PB1 * nTRST = PD0
* SRST_OUT = PA2 * SRST_OUT = PD1
* TDI = PA3 * TDI = PA1
* TMS = PA4 (input for SWDP) * TMS = PA3 (input for SWDP)
* TCK = PA5 * TCK = PA8
* TDO = PA6 (input) * TDO = PB4 (input)
* nSRST = PA7 (input) * nSRST = PD2 (input)
* *
* USB cable pull-up: PA8 * USB cable pull-up: PA8
* USB VBUS detect: PB13 -- New on mini design. * USB VBUS detect: PB13 -- New on mini design.
@ -66,55 +66,68 @@ extern usbd_device *usbdev;
#define TDI_PORT JTAG_PORT #define TDI_PORT JTAG_PORT
#define TMS_PORT JTAG_PORT #define TMS_PORT JTAG_PORT
#define TCK_PORT JTAG_PORT #define TCK_PORT JTAG_PORT
#define TDO_PORT JTAG_PORT #define TDO_PORT GPIOB
#define TDI_PIN GPIO3 #define TDI_PIN GPIO1
#define TMS_PIN GPIO4 #define TMS_PIN GPIO3
#define TCK_PIN GPIO5 #define TCK_PIN GPIO2
#define TDO_PIN GPIO6 #define TDO_PIN GPIO4
#define SWDIO_PORT JTAG_PORT #define SWDIO_PORT JTAG_PORT
#define SWCLK_PORT JTAG_PORT #define SWCLK_PORT JTAG_PORT
#define SWDIO_PIN TMS_PIN #define SWDIO_PIN TMS_PIN
#define SWCLK_PIN TCK_PIN #define SWCLK_PIN TCK_PIN
#define TRST_PORT GPIOB #define TRST_PORT GPIOD
#define TRST_PIN GPIO1 #define TRST_PIN GPIO0
#define SRST_PORT GPIOA #define SRST_PORT GPIOD
#define SRST_PIN GPIO2 #define SRST_PIN GPIO1
#define USB_PU_PORT GPIOA #define LED_PORT GPIOD
#define USB_PU_PIN GPIO8 #define LED_PORT_UART GPIOD
#define LED_UART GPIO12
#define LED_IDLE_RUN GPIO13
#define LED_ERROR GPIO14
#define LED_SPARE1 GPIO15
#define USB_VBUS_PORT GPIOB #define TMS_SET_MODE() gpio_mode_setup(TMS_PORT, GPIO_MODE_OUTPUT, \
#define USB_VBUS_PIN GPIO13 GPIO_PUPD_NONE, TMS_PIN);
#define USB_VBUS_IRQ NVIC_EXTI15_10_IRQ #define SWDIO_MODE_FLOAT() gpio_mode_setup(SWDIO_PORT, GPIO_MODE_INPUT, \
GPIO_PUPD_NONE, SWDIO_PIN);
#define LED_PORT GPIOB #define SWDIO_MODE_DRIVE() gpio_mode_setup(SWDIO_PORT, GPIO_MODE_OUTPUT, \
#define LED_PORT_UART GPIOB GPIO_PUPD_NONE, SWDIO_PIN);
#define LED_UART GPIO2
#define LED_IDLE_RUN GPIO10
#define LED_ERROR GPIO11
#define USB_DRIVER stm32f103_usb_driver
#define USB_IRQ NVIC_USB_LP_CAN_RX0_IRQ #define USB_DRIVER stm32f107_usb_driver
#define USB_ISR usb_lp_can_rx0_isr #define USB_IRQ NVIC_OTG_FS_IRQ
#define USB_ISR otg_fs_isr
/* Interrupt priorities. Low numbers are high priority. /* Interrupt priorities. Low numbers are high priority.
* For now USART1 preempts USB which may spin while buffer is drained. * For now USART1 preempts USB which may spin while buffer is drained.
* TIM3 is used for traceswo capture and must be highest priority. * TIM3 is used for traceswo capture and must be highest priority.
*/ */
#define IRQ_PRI_USB (2 << 4) #define IRQ_PRI_USB (2 << 4)
#define IRQ_PRI_USBUSART (1 << 4) #define IRQ_PRI_USBUSART (1 << 4)
#define IRQ_PRI_USB_VBUS (14 << 4)
#define IRQ_PRI_TRACE (0 << 4) #define IRQ_PRI_TRACE (0 << 4)
#define USBUSART USART1 #define USBUSART USART3
#define USBUSART_CR1 USART1_CR1 #define USBUSART_CR1 USART3_CR1
#define USBUSART_IRQ NVIC_USART1_IRQ #define USBUSART_IRQ NVIC_USART3_IRQ
#define USBUSART_APB_ENR RCC_APB2ENR #define USBUSART_APB_ENR RCC_APB1ENR
#define USBUSART_CLK_ENABLE RCC_APB2ENR_USART1EN #define USBUSART_CLK_ENABLE RCC_APB1ENR_USART3EN
#define USBUSART_PORT GPIOA #define USBUSART_TX_PORT GPIOD
#define USBUSART_TX_PIN GPIO9 #define USBUSART_TX_PIN GPIO8
#define USBUSART_ISR usart1_isr #define USBUSART_RX_PORT GPIOD
#define USBUSART_RX_PIN GPIO9
#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 TIM3
#define TRACE_TIM_CLK_EN() rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM3EN) #define TRACE_TIM_CLK_EN() rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM3EN)
@ -180,7 +193,7 @@ static inline void _gpio_set(u32 gpioport, u16 gpios)
static inline void _gpio_clear(u32 gpioport, u16 gpios) static inline void _gpio_clear(u32 gpioport, u16 gpios)
{ {
GPIO_BRR(gpioport) = gpios; GPIO_BSRR(gpioport) = gpios<<16;
} }
#define gpio_clear _gpio_clear #define gpio_clear _gpio_clear
@ -193,6 +206,6 @@ static inline u16 _gpio_get(u32 gpioport, u16 gpios)
#endif #endif
#define disconnect_usb() gpio_set_mode(USB_PU_PORT, GPIO_MODE_INPUT, 0, USB_PU_PIN); #define disconnect_usb() do {usbd_disconnect(usbdev,1); nvic_disable_irq(USB_IRQ);} while(0)
void assert_boot_pin(void); void assert_boot_pin(void);
void setup_vbus_irq(void); #define setup_vbus_irq()

View File

@ -553,7 +553,11 @@ void USB_ISR(void)
static char *get_dev_unique_id(char *s) static char *get_dev_unique_id(char *s)
{ {
#if defined(STM32F4)
volatile uint32_t *unique_id_p = (volatile uint32_t *)0x1FFF7A10;
#else
volatile uint32_t *unique_id_p = (volatile uint32_t *)0x1FFFF7E8; volatile uint32_t *unique_id_p = (volatile uint32_t *)0x1FFFF7E8;
#endif
uint32_t unique_id = *unique_id_p + uint32_t unique_id = *unique_id_p +
*(unique_id_p + 1) + *(unique_id_p + 1) +
*(unique_id_p + 2); *(unique_id_p + 2);

View File

@ -20,9 +20,10 @@
/* Define memory regions. */ /* Define memory regions. */
MEMORY MEMORY
{ {
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K ram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
} }
/* Include the common ld script from libopenstm32. */ /* Include the common ld script from libopenstm32. */
INCLUDE libopencm3_stm32f1.ld INCLUDE libopencm3_stm32f4.ld

View File

@ -34,8 +34,6 @@
#include <libopencm3/usb/usbd.h> #include <libopencm3/usb/usbd.h>
#include <libopencm3/usb/dfu.h> #include <libopencm3/usb/dfu.h>
#define APP_ADDRESS 0x08002000
/* Commands sent with wBlockNum == 0 as per ST implementation. */ /* Commands sent with wBlockNum == 0 as per ST implementation. */
#define CMD_SETADDR 0x21 #define CMD_SETADDR 0x21
#define CMD_ERASE 0x41 #define CMD_ERASE 0x41
@ -49,10 +47,60 @@ usbd_device *usbdev;
/* We need a special large control buffer for this device: */ /* We need a special large control buffer for this device: */
u8 usbd_control_buffer[1024]; u8 usbd_control_buffer[1024];
#if defined (STM32_CAN)
#define FLASHBLOCKSIZE 2048
#else
#define FLASHBLOCKSIZE 1024
#endif
#if defined(DISCOVERY_STLINK) #if defined(DISCOVERY_STLINK)
u32 led2_state = 0; u32 led2_state = 0;
#endif #endif
static u32 max_address;
#if defined (STM32F4)
#define APP_ADDRESS 0x08010000
static u32 sector_addr[] = {0x8000000, 0x8004000, 0x8008000, 0x800c000,
0x8010000, 0x8020000, 0x8040000, 0x8060000,
0x8080000, 0x80a0000, 0x80c0000, 0x80e0000,
0x8100000, 0};
u16 sector_erase_time[12]= {500, 500, 500, 500,
1100,
2600, 2600, 2600, 2600, 2600, 2600, 2600};
u8 sector_num = 0xff;
/* Find the sector number for a given address*/
void get_sector_num(u32 addr)
{
int i = 0;
while(sector_addr[i+1]) {
if (addr < sector_addr[i+1])
break;
i++;
}
if (!sector_addr[i])
return;
sector_num = i;
}
void check_and_do_sector_erase(u32 addr)
{
if(addr == sector_addr[sector_num]) {
flash_erase_sector((sector_num & 0x1f)<<3, FLASH_PROGRAM_X32);
}
}
#else
#define APP_ADDRESS 0x08002000
static uint32_t last_erased_page=0xffffffff;
void check_and_do_sector_erase(u32 sector)
{
sector &= (~(FLASHBLOCKSIZE-1));
if (sector != last_erased_page) {
flash_erase_page(sector);
last_erased_page = sector;
}
}
#endif
static enum dfu_state usbdfu_state = STATE_DFU_IDLE; static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
static char *get_dev_unique_id(char *serial_no); static char *get_dev_unique_id(char *serial_no);
@ -136,6 +184,8 @@ static const char *usb_strings[] = {
"Black Magic (Upgrade) for STLink/Discovery", "Black Magic (Upgrade) for STLink/Discovery",
#elif defined(STM32_CAN) #elif defined(STM32_CAN)
"Black Magic (Upgrade) for STM32_CAN", "Black Magic (Upgrade) for STM32_CAN",
#elif defined(F4DISCOVERY)
"Black Magic (Upgrade) for F4DISCOVERY",
#else #else
#warning "Unhandled board" #warning "Unhandled board"
#endif #endif
@ -147,6 +197,8 @@ static const char *usb_strings[] = {
"@Internal Flash /0x08000000/8*001Ka,56*001Kg" "@Internal Flash /0x08000000/8*001Ka,56*001Kg"
#elif defined(STM32_CAN) #elif defined(STM32_CAN)
"@Internal Flash /0x08000000/4*002Ka,124*002Kg" "@Internal Flash /0x08000000/4*002Ka,124*002Kg"
#elif defined(F4DISCOVERY)
"@Internal Flash /0x08000000/1*016Ka,3*016Kg,1*064Kg,7*128Kg"
#else #else
#warning "Unhandled board" #warning "Unhandled board"
#endif #endif
@ -157,7 +209,20 @@ static u8 usbdfu_getstatus(u32 *bwPollTimeout)
switch(usbdfu_state) { switch(usbdfu_state) {
case STATE_DFU_DNLOAD_SYNC: case STATE_DFU_DNLOAD_SYNC:
usbdfu_state = STATE_DFU_DNBUSY; usbdfu_state = STATE_DFU_DNBUSY;
#if defined(STM32F4)
/* Programming 256 word with 100 us(max) per word*/
*bwPollTimeout = 26;
/* Erase for big pages on STM2/4 needs "long" time
Try not to hit USB timeouts*/
if ((prog.blocknum == 0) && (prog.buf[0] == CMD_ERASE)) {
u32 addr = *(u32 *)(prog.buf + 1);
get_sector_num(addr);
if(addr == sector_addr[sector_num])
*bwPollTimeout = sector_erase_time[sector_num];
}
#else
*bwPollTimeout = 100; *bwPollTimeout = 100;
#endif
return DFU_STATUS_OK; return DFU_STATUS_OK;
case STATE_DFU_MANIFEST_SYNC: case STATE_DFU_MANIFEST_SYNC:
@ -170,13 +235,6 @@ static u8 usbdfu_getstatus(u32 *bwPollTimeout)
} }
} }
#if defined (STM32_CAN)
#define FLASHBLOCKSIZE 2048
#else
#define FLASHBLOCKSIZE 1024
#endif
static uint32_t last_erased_pages=0xffffffff;
static void static void
usbdfu_getstatus_complete(usbd_device *dev, struct usb_setup_data *req) usbdfu_getstatus_complete(usbd_device *dev, struct usb_setup_data *req)
{ {
@ -188,32 +246,33 @@ usbdfu_getstatus_complete(usbd_device *dev, struct usb_setup_data *req)
flash_unlock(); flash_unlock();
if(prog.blocknum == 0) { if(prog.blocknum == 0) {
if ((*(u32*)(prog.buf+1) < 0x8002000) || u32 addr = *(u32 *)(prog.buf + 1);
(*(u32*)(prog.buf+1) >= 0x8020000)) { if (addr < APP_ADDRESS ||
(addr >= max_address)) {
flash_lock();
usbd_ep_stall_set(dev, 0, 1); usbd_ep_stall_set(dev, 0, 1);
return; return;
} }
switch(prog.buf[0]) { switch(prog.buf[0]) {
case CMD_ERASE: { case CMD_ERASE:
u32 page_start = *(u32*)(prog.buf+1); check_and_do_sector_erase(addr);
page_start &= (~(FLASHBLOCKSIZE-1));
if (page_start != last_erased_pages) {
flash_erase_page(page_start);
last_erased_pages = page_start;
}
}
case CMD_SETADDR: case CMD_SETADDR:
prog.addr = *(u32*)(prog.buf+1); prog.addr = addr;
} }
} else { } else {
u32 baseaddr = prog.addr + u32 baseaddr = prog.addr +
((prog.blocknum - 2) * ((prog.blocknum - 2) *
dfu_function.wTransferSize); dfu_function.wTransferSize);
#if defined (STM32F4)
for(i = 0; i < prog.len; i += 4)
flash_program_word(baseaddr + i,
*(u32*)(prog.buf+i),
FLASH_PROGRAM_X32);
#else
for(i = 0; i < prog.len; i += 2) for(i = 0; i < prog.len; i += 2)
flash_program_half_word(baseaddr + i, flash_program_half_word(baseaddr + i,
*(u16*)(prog.buf+i)); *(u16*)(prog.buf+i));
#endif
} }
flash_lock(); flash_lock();
@ -311,14 +370,23 @@ int main(void)
#elif defined (STM32_CAN) #elif defined (STM32_CAN)
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN); rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
if(!gpio_get(GPIOA, GPIO0)) { if(!gpio_get(GPIOA, GPIO0)) {
#elif defined (F4DISCOVERY)
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPAEN);
if(!gpio_get(GPIOA, GPIO0)) {
#else #else
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN); rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
if(gpio_get(GPIOB, GPIO12)) { if(gpio_get(GPIOB, GPIO12)) {
#endif #endif
/* Boot the application if it's valid */ /* Boot the application if it's valid */
#if defined (STM32F4)
/* Vector table may be anywhere in 128 kByte RAM
CCM not handled*/
if((*(volatile u32*)APP_ADDRESS & 0x2FFC0000) == 0x20000000) {
#else
if((*(volatile u32*)APP_ADDRESS & 0x2FFE0000) == 0x20000000) { if((*(volatile u32*)APP_ADDRESS & 0x2FFE0000) == 0x20000000) {
#endif
/* Set vector table base address */ /* Set vector table base address */
SCB_VTOR = APP_ADDRESS & 0xFFFF; SCB_VTOR = APP_ADDRESS & 0x1FFFFF; /* Max 2 MByte Flash*/
/* Initialise master stack pointer */ /* Initialise master stack pointer */
asm volatile ("msr msp, %0"::"g" asm volatile ("msr msp, %0"::"g"
(*(volatile u32*)APP_ADDRESS)); (*(volatile u32*)APP_ADDRESS));
@ -327,6 +395,9 @@ int main(void)
} }
} }
#if defined (STM32F4)
/* don' touch option bits for now */
#else
if ((FLASH_WRPR & 0x03) != 0x00) { if ((FLASH_WRPR & 0x03) != 0x00) {
flash_unlock(); flash_unlock();
FLASH_CR = 0; FLASH_CR = 0;
@ -336,6 +407,7 @@ int main(void)
/* MD Device: Protect 2 bits with (4 * 1k pages each)*/ /* MD Device: Protect 2 bits with (4 * 1k pages each)*/
flash_program_option_bytes(FLASH_OBP_WRP10, 0x03FC); flash_program_option_bytes(FLASH_OBP_WRP10, 0x03FC);
} }
#endif
#if defined (DISCOVERY_STLINK) #if defined (DISCOVERY_STLINK)
/* Just in case: Disconnect USB cable by resetting USB Device /* Just in case: Disconnect USB cable by resetting USB Device
@ -348,19 +420,22 @@ int main(void)
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12); GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12);
#endif #endif
#if defined (F4DISCOVERY)
rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_168MHZ]);
#else
rcc_clock_setup_in_hse_8mhz_out_72mhz(); rcc_clock_setup_in_hse_8mhz_out_72mhz();
#endif
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
#if defined(DISCOVERY_STLINK) #if defined(DISCOVERY_STLINK)
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, #elif defined(F4DISCOVERY)
GPIO_CNF_INPUT_ANALOG, GPIO0);
#elif defined (STM32_CAN) #elif defined (STM32_CAN)
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_AHBENR, RCC_AHBENR_OTGFSEN); rcc_peripheral_enable_clock(&RCC_AHBENR, RCC_AHBENR_OTGFSEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN); rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ, gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO0); GPIO_CNF_OUTPUT_PUSHPULL, GPIO0);
#else #else
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN); rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, 0, GPIO8); gpio_set_mode(GPIOA, GPIO_MODE_INPUT, 0, GPIO8);
@ -368,18 +443,33 @@ int main(void)
GPIO_CNF_OUTPUT_PUSHPULL, GPIO11); GPIO_CNF_OUTPUT_PUSHPULL, GPIO11);
#endif #endif
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8); systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
systick_set_reload(900000); systick_set_reload(2100000);
systick_interrupt_enable(); systick_interrupt_enable();
systick_counter_enable(); systick_counter_enable();
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, GPIO2 | GPIO10);
get_dev_unique_id(serial_no); get_dev_unique_id(serial_no);
#if defined(STM32_CAN) #if defined(STM32_CAN)
usbdev = usbd_init(&stm32f107_usb_driver,
&dev, &config, usb_strings, 4);
#elif defined(F4DISCOVERY)
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPDEN);
gpio_clear(GPIOD, GPIO12 | GPIO13 | GPIO14 |GPIO15);
gpio_mode_setup(GPIOD, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE,
GPIO12 | GPIO13 | GPIO14 |GPIO15);
rcc_peripheral_enable_clock(&RCC_AHB2ENR, RCC_AHB2ENR_OTGFSEN);
/* Set up USB Pins and alternate function*/
gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE,
GPIO9 | GPIO11 | GPIO12);
gpio_set_af(GPIOA, GPIO_AF10, GPIO9 | GPIO11 | GPIO12);
usbdev = usbd_init(&stm32f107_usb_driver, usbdev = usbd_init(&stm32f107_usb_driver,
&dev, &config, usb_strings, 4); &dev, &config, usb_strings, 4);
#else #else
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, GPIO2 | GPIO10);
usbdev = usbd_init(&stm32f103_usb_driver, usbdev = usbd_init(&stm32f103_usb_driver,
&dev, &config, usb_strings, 4); &dev, &config, usb_strings, 4);
#endif #endif
@ -401,12 +491,28 @@ int main(void)
static char *get_dev_unique_id(char *s) static char *get_dev_unique_id(char *s)
{ {
volatile uint32_t *unique_id_p = (volatile uint32_t *)0x1FFFF7E8; #if defined(STM32F4) || defined(STM32F2)
#define UNIQUE_SERIAL_R 0x1FFF7A10
#define FLASH_SIZE_R 0x1fff7A22
#elif defined(STM32F3)
#define UNIQUE_SERIAL_R 0x1FFFF7AC
#define FLASH_SIZE_R 0x1fff77cc
#elif defined(STM32L1)
#define UNIQUE_SERIAL_R 0x1ff80050
#define FLASH_SIZE_R 0x1FF8004C
#else
#define UNIQUE_SERIAL_R 0x1FFFF7E8;
#define FLASH_SIZE_R 0x1ffff7e0
#endif
volatile uint32_t *unique_id_p = (volatile uint32_t *)UNIQUE_SERIAL_R;
uint32_t unique_id = *unique_id_p + uint32_t unique_id = *unique_id_p +
*(unique_id_p + 1) + *(unique_id_p + 1) +
*(unique_id_p + 2); *(unique_id_p + 2);
int i; int i;
/* Calculated the upper flash limit from the exported data
in theparameter block*/
max_address = (*(u32 *) FLASH_SIZE_R) <<10;
/* Fetch serial number from chip's unique ID */ /* Fetch serial number from chip's unique ID */
for(i = 0; i < 8; i++) { for(i = 0; i < 8; i++) {
s[7-i] = ((unique_id >> (4*i)) & 0xF) + '0'; s[7-i] = ((unique_id >> (4*i)) & 0xF) + '0';
@ -429,6 +535,8 @@ void sys_tick_handler()
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_ANALOG, GPIO9); GPIO_CNF_INPUT_ANALOG, GPIO9);
led2_state++; led2_state++;
#elif defined (F4DISCOVERY)
gpio_toggle(GPIOD, GPIO12); /* Green LED on/off */
#elif defined(STM32_CAN) #elif defined(STM32_CAN)
gpio_toggle(GPIOB, GPIO0); /* LED2 on/off */ gpio_toggle(GPIOB, GPIO0); /* LED2 on/off */
#else #else