diff --git a/Makefile b/Makefile index f2620df..e5d724e 100644 --- a/Makefile +++ b/Makefile @@ -21,28 +21,24 @@ Q := @ NULL := 1> /dev/null 2> /dev/null endif -# the final binary name (without extension) -BINARY = firmware +# main names (without extension, for input source file and output binary) +APPLICATION = application +BOOTLOADER = bootloader +FIRMWARE = $(APPLICATION) $(BOOTLOADER) # which development board is used # supported are: SYSTEM_BOARD, MAPLE_MINI, BLUE_PILL, CORE_BOARD -BOARD = CORE_BOARD +BOARD = BLUE_PILL -# source files -CSRC = $(wildcard *.c) -CHDR = $(wildcard *.h) +# source files (this will be populated using includes based DEPENDENCIES) +CSRC = global.c +# headers corresponding to source files +CHDR = $(patsubst %.c,%.h,$(CSRC)) +# objects compiled from source files OBJ = $(patsubst %.c,%.o,$(CSRC)) - -# my library collection -LIB = lib -# the library files to use (this will be populated using includes based DEPENDENCIES) -LIB_CSRC = -LIB_CHDR = $(patsubst %.c,%.h,$(LIB_CSRC)) -LIB_OBJ = $(patsubst %.c,%.o,$(LIB_CSRC)) - -# figure out based on the includes which library files are used in the main CSRC files -DEPENDENCIES = $(patsubst %.c,%.inc,$(CSRC)) -# populates LIB_CSRC based on the library files used +# figure out based on the main sources files which library files are used +DEPENDENCIES = $(patsubst %,%.inc,$(FIRMWARE)) +# populates CSRC based on the library files used -include $(DEPENDENCIES) # executables for linking, compiling, debugging, ... @@ -56,8 +52,9 @@ AR := $(ELLCC)bin/ecc-ar AS := $(ELLCC)bin/ecc-as OBJCOPY := $(ELLCC)bin/ecc-objcopy OBJDUMP := $(ELLCC)bin/ecc-objdump -# ecc-gdb is buggy and crashes on "kill" -GDB := gdb +GDB := $(ELLCC)bin/ecc-gdb +# ecc-gdb (0.13.3) is buggy (crash on kill, can't load elf) +GDB := arm-none-eabi-gdb # opencm3 libraries OPENCM3_DIR := libopencm3 @@ -66,7 +63,7 @@ OPENCM3_LIB = $(OPENCM3_DIR)/lib # library for the STM32F1 (provided by opencm3) STM32F1_LIB = opencm3_stm32f1 -# linker script for STN32F1 boards +# linker script for STM32F103x8 boards (MAPLE_MINI has STM32F103xB with just more 128 kB flash instead of 64 kB, thus is compatible) ifeq ($(BOARD),SYSTEM_BOARD) LDSCRIPT = $(OPENCM3_DIR)/lib/stm32/f1/stm32f103x8.ld else ifeq ($(BOARD),BLUE_PILL) @@ -76,6 +73,7 @@ LDSCRIPT = $(OPENCM3_DIR)/lib/stm32/f1/stm32f103x8.ld else ifeq ($(BOARD),MAPLE_MINI) LDSCRIPT = $(OPENCM3_DIR)/lib/stm32/f1/stm32f103xb.ld endif +LDSCRIPT = application.ld # device micro-controller and board DEFS += -DSTM32F1 -D$(BOARD) @@ -100,9 +98,9 @@ CFLAGS += -ffreestanding # don't use the standard library CFLAGS += -nostdlib -nostdinc # include ELLCC libraries -CFLAGS += -I$(ELLCC)libecc/include/ -I$(ELLCC)libecc/include/arm/ +CFLAGS += -I $(ELLCC)libecc/include/ -I $(ELLCC)libecc/include/arm/ # include own libraries -CFLAGS += -I . $(patsubst %,-I%,$(LIB)) +CFLAGS += -I . -I lib # include opencm3 libraries CFLAGS += -I $(OPENCM3_INC) # add defines for micro-controller and board @@ -122,7 +120,7 @@ LDFLAGS += --library-path $(ELLCC)libecc/lib/cortex-m3-linux/ # opencm3 libraries LDFLAGS += --library-path $(OPENCM3_LIB) # linker script with definitions for micro-controller -LDFLAGS += --script $(LDSCRIPT) +#LDFLAGS += --script $(LDSCRIPT) # used libraries (gcc provides the ARM ABI, not sure how to replace with compiler-rt) LDLIBS += --library $(STM32F1_LIB) --library c --library m --library gcc @@ -131,7 +129,7 @@ ARCH_FLAGS = -mthumb -mcpu=cortex-m3 -msoft-float # SWD adapter used # supported are : st-link v2 (STLINKV2), black magic probe (BMP) -SWD_ADAPTER ?= BMP +SWD_ADAPTER ?= STLINKV2 ifeq ($(SWD_ADAPTER),STLINKV2) # OpenOCD configuration OOCD ?= openocd @@ -139,38 +137,31 @@ OOCD_INTERFACE ?= stlink-v2 OOCD_TARGET ?= stm32f1x else ifeq ($(SWD_ADAPTER),BMP) # the black magic probe has a SWD controller built in -BMPPORT ?= /dev/ttyACM0 +BMP_PORT ?= /dev/ttyACM0 endif -# which USB CDC ACM port is used bu the device, so we can reset it -ifeq ($(SWD_ADAPTER),STLINKV2) -ACMPORT = /dev/ttyACM0 -else ifeq ($(SWD_ADAPTER),BMP) -ACMPORT = /dev/ttyACM2 -endif -ACMPORT_EXISTS = $(shell [ -e $(ACMPORT) ] && echo 1 || echo 0 ) - # compile target rules -all: elf +all: elf hex bin -elf: $(BINARY).elf -bin: $(BINARY).bin -hex: $(BINARY).hex -srec: $(BINARY).srec -list: $(BINARY).list +elf: $(patsubst %,%.elf,$(FIRMWARE)) +bin: $(patsubst %,%.bin,$(FIRMWARE)) +hex: $(patsubst %,%.hex,$(FIRMWARE)) -%.bin %.hex %.srec: %.elf - $(Q)$(OBJCOPY) -Osrec $(<) $(@) +%.hex: %.elf + $(Q)$(OBJCOPY) --strip-all --strip-debug --output-target ihex $(<) $(@) + +%.bin: %.elf + $(Q)$(OBJCOPY) --strip-all --strip-debug --output-target binary $(<) $(@) %.map %.list: %.elf $(Q)$(OBJDUMP) -S $(<) > $(@) -%.elf: $(OPENCM3_LIB)/lib$(STM32F1_LIB).a $(OBJ) $(LIB_OBJ) +%.elf: %.o %.ld $(OBJ) $(OPENCM3_LIB)/lib$(STM32F1_LIB).a $(info linking $(@)) - $(Q)$(LD) $(LDFLAGS) $(OBJ) $(LIB_OBJ) $(LDLIBS) -o $(@) + $(Q)$(LD) $(LDFLAGS) --script $(*).ld $(<) $(OBJ) $(LDLIBS) -o $(@) $(Q)size $(@) -%.o: %.c $(CHDR) $(LIB_CHDR) +%.o: %.c $(CHDR) $(info compiling $(@)) $(Q)$(CC) $(CFLAGS) $(ARCH_FLAGS) -o $(@) -c $(<) @@ -181,14 +172,14 @@ list: $(BINARY).list # figure out which library source files are used for later inclusion %.inc: %.d - $(Q)grep -o -e " ${LIB}\/[^ ]*\.h" $(<) | sed -e 's|\(.*\)\.h$$|LIB_CSRC +=\1.c\n-include\1.inc|g' -e 's|.*${*}.*||g' > $(@) + $(Q)grep -o -e " lib\/[^ ]*\.h" $(<) | sed -e 's|\(.*\)\.h$$|CSRC +=\1.c\n-include\1.inc|g' -e 's|.*${*}.*||g' > $(@) # doxygen documentation -doc: Doxyfile README.md $(CSRC) $(CHDR) $(LIB_CSRC) $(LIB_CHDR) +doc: Doxyfile README.md $(patsubst %,%.c,$(FIRMWARE)) $(CSRC) $(CHDR) $(Q)doxygen $(<) clean: - $(Q)$(RM) $(BINARY).elf $(BINARY).bin $(BINARY).hex $(BINARY).map $(OBJ) $(LIB_OBJ) $(LIB)/*.o $(DEPENDENCIES) $(LIB)/*.inc + $(Q)$(RM) $(BOOTLOADER).elf $(BOOTLOADER).bin $(BOOTLOADER).hex $(OBJ) $(DEPENDENCIES) # make libopencm3 if library for STM32F1 is not yet existing $(OPENCM3_LIB)/lib$(STM32F1_LIB).a: @@ -197,28 +188,45 @@ $(OPENCM3_LIB)/lib$(STM32F1_LIB).a: git submodule update $(Q)$(MAKE) CFLAGS=-fno-short-enums -C $(OPENCM3_DIR) -flash: $(BINARY).hex +# flash application using DFU +flash: $(APPLICATION).bin + $(Q)dfu-util -d c440:0d00 -D $(<) + +# flash bootloader using SWD +flash_bootloader: $(BOOTLOADER).hex $(info flashing $(<) using SWD) ifeq ($(SWD_ADAPTER),STLINKV2) $(Q)$(OOCD) --file interface/$(OOCD_INTERFACE).cfg --file target/$(OOCD_TARGET).cfg --command "init" --command "reset init" --command "flash write_image erase $(<)" --command "reset" --command "shutdown" $(NULL) else ifeq ($(SWD_ADAPTER),BMP) - $(Q)$(GDB) --eval-command="target extended-remote $(BMPPORT)" --eval-command="set confirm off" --eval-command="kill" --eval-command="monitor swdp_scan" --eval-command="attach 1" --eval-command="load" --eval-command="kill" --eval-command="detach" --eval-command="quit" $(<) + $(Q)$(GDB) --eval-command="target extended-remote $(BMP_PORT)" --eval-command="set confirm off" --eval-command="monitor swdp_scan" --eval-command="attach 1" --eval-command="load" --eval-command="detach" --eval-command="quit" $(<) +endif + +# flash application using SWD +flash_application: $(APPLICATION).hex + $(info flashing $(<) using SWD) +ifeq ($(SWD_ADAPTER),STLINKV2) + $(Q)$(OOCD) --file interface/$(OOCD_INTERFACE).cfg --file target/$(OOCD_TARGET).cfg --command "init" --command "reset init" --command "flash write_image erase $(<)" --command "reset" --command "shutdown" $(NULL) +else ifeq ($(SWD_ADAPTER),BMP) + $(Q)$(GDB) --eval-command="target extended-remote $(BMP_PORT)" --eval-command="set confirm off" --eval-command="monitor swdp_scan" --eval-command="attach 1" --eval-command="load" --eval-command="detach" --eval-command="quit" $(<) endif # reset device by setting the data width to 5 bis on the USB CDC ACM port -reset: -ifeq ($(ACMPORT_EXISTS), 1) - $(Q)stty --file $(ACMPORT) 115200 raw cs5 - $(Q)sleep 0.5 +ifeq ($(SWD_ADAPTER)$(BMP_PORT),BMP/dev/ttyACM0) +ACM_PORT := /dev/ttyACM2 +else +ACM_PORT := /dev/ttyACM0 endif +reset: + $(Q)stty --file $(ACM_PORT) raw cs5 + $(Q)sleep 0.5 -# debug using GDB -debug: $(BINARY).elf +# debug application using GDB +debug: $(APPLICATION).elf ifeq ($(SWD_ADAPTER),STLINKV2) # for GDB to work with openOCD the firmware needs to be reloaded $(Q)$(GDB) --eval-command="target remote | $(OOCD) --file interface/$(OOCD_INTERFACE).cfg --file target/$(OOCD_TARGET).cfg --command \"gdb_port pipe; log_output /dev/null; init\"" --eval-command="monitor reset halt" --eval-command="load" --eval-command="monitor reset init" $(<) else ifeq ($(SWD_ADAPTER),BMP) - $(Q)$(GDB) --eval-command="target extended-remote $(BMPPORT)" --eval-command="monitor version" --eval-command="monitor swdp_scan" --eval-command="attach 1" $(<) + $(Q)$(GDB) --eval-command="target extended-remote $(BMP_PORT)" --eval-command="monitor version" --eval-command="monitor swdp_scan" --eval-command="attach 1" $(<) endif .PHONY: clean elf bin hex srec list flash reset diff --git a/main.c b/application.c similarity index 100% rename from main.c rename to application.c diff --git a/application.ld b/application.ld new file mode 100644 index 0000000..ab7deea --- /dev/null +++ b/application.ld @@ -0,0 +1,16 @@ +/* linker script for application running on STM32F103x8 micro-controller + * the STM32F103x8 has 64kB of flash starting at 0x0800 0000, and 20kB of RAM starting at 0x2000 0000 + * the bootloader will take the first 9 kB of flash, followed by the application + */ + +/* Define memory regions. */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000 + 9K, LENGTH = 55K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K +} +PROVIDE(__application_beginning = ORIGIN(rom)); +PROVIDE(__application_end = ORIGIN(rom) + LENGTH(rom)); + +/* include rest of the definitions for the STM32F1 family */ +INCLUDE libopencm3_stm32f1.ld diff --git a/bootloader.c b/bootloader.c new file mode 100644 index 0000000..6a90280 --- /dev/null +++ b/bootloader.c @@ -0,0 +1,85 @@ +/* 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 . + * + */ +/** USB DFU bootloader + * @file bootloader.c + * @author King Kévin + * @date 2017 + */ +/* standard libraries */ +#include // standard integer types +#include // boolean types + +/* STM32 (including CM3) libraries */ +#include // vector table definition +#include // clock utilities +#include // GPIO utilities + +/* own libraries */ +#include "global.h" // board definitions +#include "usb_dfu.h" // USB DFU utilities + +/** bootloader entry point */ +void main(void); +void main(void) +{ + // check of DFU mode is forced + bool dfu_force = false; // to remember if DFU mode is forced + // check if a soft boot has been used + if (0==(RCC_CSR&0xfc000000)) { // no reset flag present -> this was a soft reset using csr_reset_core(), very probably to start the DFU mode + dfu_force = true; + } else { // check if the force DFU mode input is set + // disable SWJ pin to use as GPIO +#if (GPIO(B)==GPIO(DFU_FORCE_PORT)) && (GPIO(4)==GPIO(DFU_FORCE_PIN)) + gpio_primary_remap(AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST, 0); +#elif ((GPIO(B)==GPIO(DFU_FORCE_PORT)) && (GPIO(3)==GPIO(DFU_FORCE_PIN))) || ((GPIO(A)==GPIO(DFU_FORCE_PORT)) && (GPIO(15)==GPIO(DFU_FORCE_PIN))) + gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_ON, 0); +#elif ((GPIO(A)==GPIO(DFU_FORCE_PORT)) && (GPIO(14)==GPIO(DFU_FORCE_PIN))) || ((GPIO(A)==GPIO(DFU_FORCE_PORT)) && (GPIO(13)==GPIO(DFU_FORCE_PIN))) + gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF, 0); +#endif + rcc_periph_clock_enable(RCC_GPIO(DFU_FORCE_PORT)); // enable clock for GPIO domain + gpio_set_mode(GPIO(DFU_FORCE_PORT), GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, GPIO(DFU_FORCE_PIN)); // set GPIO to input + // pull on the opposite of the expected value + if (DFU_FORCE_VALUE) { + gpio_clear(GPIO(DFU_FORCE_PORT), GPIO(DFU_FORCE_PIN)); // pull down to be able to detect when tied to high + } else { + gpio_set(GPIO(DFU_FORCE_PORT), GPIO(DFU_FORCE_PIN)); // pull up to be able to detect when tied to low + } + if ((!DFU_FORCE_VALUE && 0==gpio_get(GPIO(DFU_FORCE_PORT), GPIO(DFU_FORCE_PIN))) || (DFU_FORCE_VALUE && 0!=gpio_get(GPIO(DFU_FORCE_PORT), GPIO(DFU_FORCE_PIN)))) { // check if output is set to the value to force DFU mode + dfu_force = true; // DFU mode forced + } + } + + // start application if valid + /* the application starts with the vector table + * the first entry in the vector table is the initial stack pointer (SP) address + * the stack will be placed in RAM + * on STM32F1xx SRAM begins at 0x2000 0000, and on STM32F103x8 there is 20KB of RAM (0x5000). + * since the stack grown "downwards" it should start at the end of the RAM: 0x2000 5000 + * if the SP is not in this range (e.g. flash has been erased) there is no valid application + * the second entry in the vector table is the reset address, corresponding to the application start + */ + volatile uint32_t* application = &__application_beginning; // get the value of the application address symbol (use a register instead on the stack since the stack pointer will be changed) + if (!dfu_force && (((*application)&0xFFFE0000)==0x20000000)) { // application at address seems valid + SCB_VTOR = (volatile uint32_t)(application); // set vector table to application vector table (store at the beginning of the application) + __asm__ volatile ("MSR msp,%0" : :"r"(*application)); // set stack pointer to address provided in the beginning of the application (loaded into a register first) + (*(void(**)())(application + 1))(); // start application (by jumping to the reset function which address is stored as second entry of the vector table) + } + + rcc_clock_setup_in_hse_8mhz_out_72mhz(); // start main clock + board_setup(); // setup board to control LED + led_on(); // indicate bootloader started + usb_dfu_setup(); // setup USB DFU for firmware upload + usb_dfu_start(); // run DFU mode +} diff --git a/bootloader.ld b/bootloader.ld new file mode 100644 index 0000000..da996bd --- /dev/null +++ b/bootloader.ld @@ -0,0 +1,16 @@ +/* linker script for application running on STM32F103x8 micro-controller + * the STM32F103x8 has 64kB of flash starting at 0x0800 0000, and 20kB of RAM starting at 0x2000 0000 + * the bootloader will take the first 9 kB of flash, followed by the application + */ + +/* Define memory regions. */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 9K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K +} +PROVIDE(__application_beginning = ORIGIN(rom) + LENGTH(rom)); +PROVIDE(__application_end = __application_beginning + 55K); + +/* include rest of the definitions for the STM32F1 family */ +INCLUDE libopencm3_stm32f1.ld diff --git a/global.h b/global.h index bf35164..03598e4 100644 --- a/global.h +++ b/global.h @@ -252,24 +252,23 @@ #define SPI_MISO_PIN(x) CAT3(GPIO_SPI,x,_MISO) /** get SPI pin for MOSI signal based on SPI identifier */ #define SPI_MOSI_PIN(x) CAT3(GPIO_SPI,x,_MOSI) - /** @} */ /** @defgroup board_led board LED GPIO * @{ */ #if defined(SYSTEM_BOARD) || defined(CORE_BOARD) -/* on system and core board LED is on pin 11/PA1 */ -#define LED_PORT A /**< GPIO port (port A) */ -#define LED_PIN 1 /**< GPIO pin (pin PA1) */ + /* on system and core board LED is on pin 11/PA1 */ + #define LED_PORT A /**< GPIO port (port A) */ + #define LED_PIN 1 /**< GPIO pin (pin PA1) */ #elif defined(BLUE_PILL) -/* on minimum system LED is on pin 2/PC13 */ -#define LED_PORT C /**< GPIO port (port C on blue pill) */ -#define LED_PIN 13 /**< GPIO pin (pin PC13 on system board) */ + /* on minimum system LED is on pin 2/PC13 */ + #define LED_PORT C /**< GPIO port (port C on blue pill) */ + #define LED_PIN 13 /**< GPIO pin (pin PC13 on system board) */ #elif defined (MAPLE_MINI) -/* on maple mini LED is on pin 19/PB1 */ -#define LED_PORT B /**< GPIO port (port B on maple mini) */ -#define LED_PIN 1 /**< GPIO pin (pin PB1 on maple mini) */ + /* on maple mini LED is on pin 19/PB1 */ + #define LED_PORT B /**< GPIO port (port B on maple mini) */ + #define LED_PIN 1 /**< GPIO pin (pin PB1 on maple mini) */ #endif /** @} */ @@ -277,16 +276,46 @@ * @{ */ #if defined(MAPLE_MINI) -/* on maple mini user button is on 32/PB8 */ -#define BUTTON_PORT B /**< GPIO port (port B on maple mini) */ -#define BUTTON_PIN 8 /**< GPIO pin (pin PB8 on maple mini) */ + /* on maple mini user button is on 32/PB8 */ + #define BUTTON_PORT B /**< GPIO port (port B on maple mini) */ + #define BUTTON_PIN 8 /**< GPIO pin (pin PB8 on maple mini) */ #elif defined(CORE_BOARD) -/* on core board user button is on PA8 */ -#define BUTTON_PORT A /**< GPIO port (port A) */ -#define BUTTON_PIN 8 /**< GPIO pin (pin PA8) */ + /* on core board user button is on PA8 */ + #define BUTTON_PORT A /**< GPIO port (port A) */ + #define BUTTON_PIN 8 /**< GPIO pin (pin PA8) */ #endif /** @} */ +/** @defgroup input to force DFU mode on low, even if application is valid + * @{ + */ +#if defined(MAPLE_MINI) + /* use button */ + #define DFU_FORCE_PORT BUTTON_PORT /**< button port */ + #define DFU_FORCE_PIN BUTTON_PIN /**< button pin */ + #define DFU_FORCE_VALUE true /**< button is pulled low unpressed, high pressed to force DFU mode */ +#elif defined(CORE_BOARD) + /* use button */ + #define DFU_FORCE_PORT BUTTON_PORT /**< button port */ + #define DFU_FORCE_PIN BUTTON_PIN /**< button pin */ + #define DFU_FORCE_VALUE false /**< button floating unpressed, connected to ground pressed to force DFU mode */ +#else + /* use the JNTRST pin as JPIO (this will disable the SWJ function, but we are not using it) */ + #define DFU_FORCE_PORT B /**< JNTRST port (needs to be remapped to become PB4) */ + #define DFU_FORCE_PIN 4 /**< JNTRST pin (needs to be remapped to become PB4) */ + #define DFU_FORCE_VALUE false /**< must be high to force DFU mode, since it's low after reset */ +#endif +/** @} */ + +/** symbol for beginning of the application + * @note this symbol will be provided by the linker script + */ +extern uint32_t __application_beginning; +/** symbol for end of the application + * @note this symbol will be provided by the linker script + */ +extern uint32_t __application_end; + extern volatile bool button_flag; /**< flag set when board user button has been pressed/released */ /** get binary representation of a number diff --git a/usb_dfu.c b/usb_dfu.c new file mode 100644 index 0000000..03ceef6 --- /dev/null +++ b/usb_dfu.c @@ -0,0 +1,299 @@ +/* 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 . + * + */ +/** library for USB DFU to write on internal flash (code) + * @file usb_dfu.c + * @author King Kévin + * @date 2017 + */ + +/* standard libraries */ +#include // standard integer types +#include // general utilities + +/* STM32 (including CM3) libraries */ +#include // Cortex M3 utilities +#include // reset utilities +#include // real-time control clock library +#include // general purpose input output library +#include // USB library +#include // USB DFU library + +#include "global.h" // global utilities +#include "usb_dfu.h" // USB DFU header and definitions +#include "flash_internal.h" // flash reading/writing utilities + +static uint8_t usbd_control_buffer[1024] = {0}; /**< buffer to be used for control requests (fit to flash page size) */ +static usbd_device *usb_device = NULL; /**< structure holding all the info related to the USB device */ +static enum dfu_state usb_dfu_state = STATE_DFU_IDLE; /**< current DFU state */ +static enum dfu_status usb_dfu_status = DFU_STATUS_OK; /**< current DFU status */ + +static uint8_t download_data[sizeof(usbd_control_buffer)] = {0}; /**< downloaded data to be programmed in flash */ +static uint16_t download_length = 0; /**< length of downloaded data */ +static uint32_t flash_pointer = 0; /**< where the downloaded data should be flashed */ + +/** USB DFU device descriptor + * @note as defined in USB Device Firmware Upgrade specification section 4.2.1 + */ +static const struct usb_device_descriptor usb_dfu_device = { + .bLength = USB_DT_DEVICE_SIZE, /**< the size of this header in bytes, 18 */ + .bDescriptorType = USB_DT_DEVICE, /**< a value of 1 indicates that this is a device descriptor */ + .bcdUSB = 0x0200, /**< this device supports USB 2.0 */ + .bDeviceClass = 0, /**< unused */ + .bDeviceSubClass = 0, /**< unused */ + .bDeviceProtocol = 0, /**< unused */ + .bMaxPacketSize0 = 64, /**< packet size for endpoint zero in bytes */ + .idVendor = 0xc440, /**< Vendor ID (CuVo...) */ + .idProduct = 0x0d00, /**< product ID within the Vendor ID space (...odoo) */ + .bcdDevice = 0x0100, /**< version number for the device */ + .iManufacturer = 1, /**< the index of the string in the string table that represents the name of the manufacturer of this device */ + .iProduct = 2, /**< the index of the string in the string table that represents the name of the product */ + .iSerialNumber = 3, /**< the index of the string in the string table that represents the serial number of this item in string form */ + .bNumConfigurations = 1, /**< the number of possible configurations this device has */ +}; + +/** USB DFU functional descriptor + * @note as defined in USB Device Firmware Upgrade specification section 4.2.4 + */ +static const struct usb_dfu_descriptor usb_dfu_functional = { + .bLength = sizeof(struct usb_dfu_descriptor), /**< provide own size */ + .bDescriptorType = DFU_FUNCTIONAL, /**< functional descriptor type */ + .bmAttributes = USB_DFU_CAN_DOWNLOAD | USB_DFU_WILL_DETACH, /**< this DFU can download and will detach after download (we don't support manifest for simplicity, technically we could) */ + .wDetachTimeout = 200, /**< maximum time in milliseconds to detach (and reboot) */ + .wTransferSize = sizeof(usbd_control_buffer), /**< set max transfer size */ + .bcdDFUVersion = 0x0110, /**< DFU specification version 1.1 used */ +}; + +/** USB DFU interface descriptor + * @note as defined in USB Device Firmware Upgrade specification section 4.2.3 + */ +static const struct usb_interface_descriptor usb_dfu_interface = { + .bLength = USB_DT_INTERFACE_SIZE, /**< size of descriptor in byte */ + .bDescriptorType = USB_DT_INTERFACE, /**< interface descriptor type */ + .bInterfaceNumber = 0, /**< this interface is the first (and only) */ + .bAlternateSetting = 0, /**< no alternative settings */ + .bNumEndpoints = 0, /**< only the control pipe at endpoint 0 is used */ + .bInterfaceClass = 0xFE, /**< DFU interface class (not defined in libopencm3 dfu lib) */ + .bInterfaceSubClass = 1, /**< DFU interface subclass (not defined in libopencm3 dfu lib) */ + .bInterfaceProtocol = 2, /**< DFU interface mode protocol (not defined in libopencm3 dfu lib) */ + .iInterface = 4, /**< the index of the string in the string table that represents interface description */ + .extra = &usb_dfu_functional, /**< point to functional descriptor */ + .extralen = sizeof(usb_dfu_functional), /**< size of functional descriptor */ +}; + +/** USB DFU interface descriptor list */ +static const struct usb_interface usb_dfu_interfaces[] = {{ + .num_altsetting = 1, /**< this is the only alternative */ + .altsetting = &usb_dfu_interface, /**< point to only interface descriptor */ +}}; + +/** USB DFU configuration descriptor + * @note as defined in USB Device Firmware Upgrade specification section 4.2.2 + */ +static const struct usb_config_descriptor usb_dfu_configuration = { + .bLength = USB_DT_CONFIGURATION_SIZE, /**< the length of this header in bytes */ + .bDescriptorType = USB_DT_CONFIGURATION, /**< a value of 2 indicates that this is a configuration descriptor */ + .wTotalLength = 0, /**< total size of the configuration descriptor including all sub interfaces (automatically filled in by the USB stack in libopencm3) */ + .bNumInterfaces = LENGTH(usb_dfu_interfaces), /**< the number of interfaces in this configuration */ + .bConfigurationValue = 1, /**< the index of this configuration */ + .iConfiguration = 0, /**< a string index describing this configuration (zero means not provided) */ + .bmAttributes = 0x80, /**< bus powered (1<<7) */ + .bMaxPower = 0x32, /**< the maximum amount of current that this device will draw in 2mA units */ + // end of header + .interface = usb_dfu_interfaces, /**< pointer to an array of interfaces */ +}; + +/** USB string table + * @note starts with index 1 + */ +static const char *usb_dfu_strings[] = { + "CuVoodoo", + "STM32F1", + "DFU", + "CuVoodoo DFU bootloader (DFU mode)", +}; + +/** disconnect USB to force re-enumerate */ +static void usb_disconnect(void) +{ +#if defined(MAPLE_MINI) + // disconnect USB D+ using dedicated DISC line/circuit on PB9 + rcc_periph_clock_enable(RCC_GPIOB); + gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO9); + gpio_set(GPIOB, GPIO9); + for (uint32_t i = 0; i < 0x2000; i++) { + __asm__("nop"); + } + gpio_clear(GPIOB, GPIO9); +#else + // pull USB D+ low for a short while + rcc_periph_clock_enable(RCC_GPIOA); + gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO12); + gpio_clear(GPIOA, GPIO12); + for (uint32_t i = 0; i < 0x2000; i++) { + __asm__("nop"); + } +#endif +} + +/** flash downloaded data block + * @param[in] usbd_dev USB device (unused) + * @param[in] req USB request (unused) + * @note this function is called after the corresponding GETSTATUS request + */ +static void usb_dfu_flash(usbd_device *usbd_dev, struct usb_setup_data *req) +{ + (void)usbd_dev; // variable not used + (void)req; // variable not used + led_off(); // indicate we are processing + if (flash_internal_write(flash_pointer, download_data, download_length)) { // write downloaded data + flash_pointer += download_length; // go to next segment + usb_dfu_state = STATE_DFU_DNLOAD_IDLE; // go back to idle stat to wait for next segment + } else { // warn about writing error + usb_dfu_status = DFU_STATUS_ERR_WRITE; + usb_dfu_state = STATE_DFU_ERROR; + } + led_on(); // indicate we finished processing +} + +/** disconnect USB and perform system reset + * @param[in] usbd_dev USB device (unused) + * @param[in] req USB request (unused) + * @note this function is called after the corresponding GETSTATUS request + */ +static void usb_dfu_reset(usbd_device *usbd_dev, struct usb_setup_data *req) +{ + (void)usbd_dev; // variable not used + (void)req; // variable not used + usb_disconnect(); // USB detach (disconnect to force re-enumeration) + scb_reset_system(); // reset device + while (true); // wait for the reset to happen +} + +/** handle incoming USB DFU control request + * @param[in] usbd_dev USB device descriptor + * @param[in] req control request information + * @param[in] buf control request data + * @param[in] len control request data length + * @param[in] complete not used + * @return 0 if succeeded, error else + * @note resets device when configured with 5 bits + */ +static int usb_dfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) +{ + (void)complete; + (void)usbd_dev; // device is not used + + // DFU only requires handling class requests + if ((req->bmRequestType & USB_REQ_TYPE_TYPE)!=USB_REQ_TYPE_CLASS) { + return 0; + } + + led_off(); // indicate we are processing request + int to_return = 1; // value to return + switch (req->bRequest) { + case DFU_DETACH: // USB detach requested + *complete = usb_dfu_reset; // reset after reply + break; + case DFU_DNLOAD: // download firmware on flash + if (STATE_DFU_IDLE!=usb_dfu_state && STATE_DFU_DNLOAD_IDLE!=usb_dfu_state) { // wrong start to request download + // warn about programming error + usb_dfu_status = DFU_STATUS_ERR_PROG; + usb_dfu_state = STATE_DFU_ERROR; + } else if (STATE_DFU_IDLE==usb_dfu_state && ((NULL==len) || (0 == *len))) { // download request should not start empty + // warn about programming error + usb_dfu_status = DFU_STATUS_ERR_PROG; + usb_dfu_state = STATE_DFU_ERROR; + } else if (STATE_DFU_DNLOAD_IDLE==usb_dfu_state && ((NULL==len) || (0 == *len))) { // download completed + // go to manifestation phase + usb_dfu_state = STATE_DFU_MANIFEST_SYNC; + } else { // there is data to be flashed + if (*len%2) { + // we can only write half words + usb_dfu_status = DFU_STATUS_ERR_PROG; + usb_dfu_state = STATE_DFU_ERROR; + } else if (flash_pointer+*len>=(uint32_t)&__application_end) { + // application data is too large + usb_dfu_status = DFU_STATUS_ERR_ADDRESS; + usb_dfu_state = STATE_DFU_ERROR; + } else { + // save downloaded data to be flashed + for (uint16_t i=0; i<*len && i. + * + */ +/** library for USB DFU to write on internal flash (API) + * @file usb_dfu.h + * @author King Kévin + * @date 2017 + */ +#pragma once + +/** setup USB DFU peripheral */ +void usb_dfu_setup(void); +/** start USB DFU handling */ +void usb_dfu_start(void); +