Browse Source

Implement bootloader #137 (#142)

* Boot: switch to DFU routines. Implements #132 part 1 of 2.

* Boot: boot to DFU shortcut, hard reset USB on each boot. Implements #132 part 2 of 2.

* Deploy scripts: fix path for deploy dfu.

* Bootloader: initial version. Target_f2: rebase, update deployment scripts.

* Bootloader: cleanup, refactor switch2 proc. Readme,wiki: document bootloader.

* Wiki: deploy symlinks as files, bootloader info.

* Target_f2: valid flash size in linker script.

* Github CI: bootloader build and artifacts.

* Bootloader: rename platforms to targets.

* Bootloader: change dfu/os colors.

* disable set -e

* lint code

* add bootloader testing page

Co-authored-by: Aleksandr Kutuzov <aku@plooks.com>
Co-authored-by: aanper <mail@s3f.ru>
あく 5 năm trước cách đây
mục cha
commit
805bb886c0

+ 15 - 0
.github/workflows/ci.yml

@@ -63,3 +63,18 @@ jobs:
             target_f2/build/target_prod.bin
             target_f2/build/target_prod.hex
           if-no-files-found: error
+
+      - name: Build bootloader in docker
+        uses: ./.github/actions/docker
+        with:
+          run: make -C bootloader
+
+      - name: Publish bootloader artifacts
+        uses: actions/upload-artifact@v2
+        with:
+          name: bootloader
+          path: |
+            bootloader/.obj/bootloader.elf
+            bootloader/.obj/bootloader.bin
+            bootloader/.obj/bootloader.hex
+          if-no-files-found: error

+ 2 - 0
.gitignore

@@ -1,4 +1,6 @@
 .idea/
+.obj/
+target_lo/build/
 target_*/build/
 bindings/
 

+ 97 - 0
bootloader/Makefile

@@ -0,0 +1,97 @@
+PROJECT			= bootloader
+
+SRC_DIR			= src
+OBJ_DIR			= .obj
+
+ASM_SOURCES		= $(wildcard $(SRC_DIR)/*.s)
+C_SOURCES		= $(wildcard $(SRC_DIR)/*.c)
+CPP_SOURCES		= $(wildcard $(SRC_DIR)/*.cpp)
+
+# 
+TARGET			?= f2
+TARGET_DIR		= targets/$(TARGET)
+include			$(TARGET_DIR)/target.mk
+CFLAGS			+= -Itargets/include
+C_SOURCES		+= $(wildcard $(TARGET_DIR)/*.c)
+
+DEBUG ?= 1
+ifeq ($(DEBUG), 1)
+CFLAGS += -DDEBUG -g
+else
+CFLAGS += -DNDEBUG -Os
+endif
+
+PREFIX = arm-none-eabi-
+ifdef GCC_PATH
+CC	= $(GCC_PATH)/$(PREFIX)gcc
+CPP	= $(GCC_PATH)/$(PREFIX)g++
+AS	= $(GCC_PATH)/$(PREFIX)gcc -x assembler-with-cpp
+CP	= $(GCC_PATH)/$(PREFIX)objcopy
+SZ	= $(GCC_PATH)/$(PREFIX)size
+else
+CC	= $(PREFIX)gcc
+CPP	= $(PREFIX)g++
+AS	= $(PREFIX)gcc -x assembler-with-cpp
+CP	= $(PREFIX)objcopy
+SZ	= $(PREFIX)size
+endif
+HEX	= $(CP) -O ihex
+BIN	= $(CP) -O binary -S
+
+$(shell mkdir -p $(OBJ_DIR))
+
+OBJECTS = $(addprefix $(OBJ_DIR)/,$(notdir $(C_SOURCES:.c=.o)))
+vpath %.c $(sort $(dir $(C_SOURCES)))
+
+OBJECTS += $(addprefix $(OBJ_DIR)/,$(notdir $(ASM_SOURCES:.s=.o)))
+vpath %.s $(sort $(dir $(ASM_SOURCES)))
+
+OBJECTS += $(addprefix $(OBJ_DIR)/,$(notdir $(CPP_SOURCES:.cpp=.o)))
+vpath %.cpp $(sort $(dir $(CPP_SOURCES)))
+
+DEPS = $(OBJECTS:.o=.d)
+
+CFLAGS += -MMD -MP -MF"$(@:%.o=%.d)"
+CPPFLAGS = -fno-threadsafe-statics
+
+all: $(OBJ_DIR)/$(PROJECT).elf $(OBJ_DIR)/$(PROJECT).hex $(OBJ_DIR)/$(PROJECT).bin
+
+$(OBJ_DIR)/$(PROJECT).elf: $(OBJECTS)
+	@echo "\tLD\t" $@
+	@$(CC) $(LDFLAGS) $(OBJECTS) -o $@
+	$(SZ) $@
+
+$(OBJ_DIR)/$(PROJECT).hex: $(OBJ_DIR)/$(PROJECT).elf
+	@echo "\tHEX\t" $@
+	@$(HEX) $< $@
+	
+$(OBJ_DIR)/$(PROJECT).bin: $(OBJ_DIR)/$(PROJECT).elf
+	@echo "\tBIN\t" $@
+	@$(BIN) $< $@
+
+$(OBJ_DIR)/%.o: %.c
+	@echo "\tCC\t" $@
+	@$(CC) $(CFLAGS) -c $< -o $@
+
+$(OBJ_DIR)/%.o: %.s
+	@echo "\tASM\t" $@
+	@$(AS) $(CFLAGS) -c $< -o $@
+
+$(OBJ_DIR)/%.o: %.cpp
+	@echo "\tCPP\t" $@
+	@$(CPP) $(CFLAGS) $(CPPFLAGS) -c $< -o $@
+
+flash: $(OBJ_DIR)/$(PROJECT).bin
+	st-flash --reset write $(OBJ_DIR)/$(PROJECT).bin $(BOOT_ADDRESS)
+
+debug:
+	st-util & arm-none-eabi-gdb -ex "PROJECT extended-remote 127.0.0.1:4242" $(OBJ_DIR)/$(PROJECT).elf
+
+clean:
+	$(RM) $(OBJ_DIR)/*
+
+zz: | clean flash
+
+zzz: | clean flash debug
+
+-include $(DEPS)

+ 47 - 0
bootloader/ReadMe.md

@@ -0,0 +1,47 @@
+# Flipper bootloader
+
+What it does?
+
+- [+] Hardware initialization
+- [ ] Firmware CRC check
+- [+] Firmware update
+- [ ] Interactive UI
+- [+] Boot process LED indicators
+- [ ] FS check
+- [ ] Recovery mode
+
+# Targets
+
+| Name      | Bootloader    | Firmware      | Reset | DFU           |
+|           | Address       | Address       | Combo | Combo         |
+---------------------------------------------------------------------
+| f2        | 0x08000000    | 0x00008000    | L+R   | L+R, hold R   |
+
+Target independend code and headers in `src`and `target/include` folders.
+
+# Building
+
+## With dev docker image:
+
+`docker-compose exec dev make -C bootloader`
+
+## With toolchain installed in path:
+
+`make`
+
+## Build Options
+
+- `DEBUG` - 0/1 - enable or disable debug build. Default is 1.
+- `TARGET` - string - target to build. Default is `f2`.
+
+# Flashing 
+
+Using stlink(st-flash):
+
+`make flash`
+
+# Debug
+
+Using stlink (st-util + gdb):
+
+`make debug`

+ 14 - 0
bootloader/src/main.c

@@ -0,0 +1,14 @@
+#include "target.h"
+
+int main() {
+    // Initialize hardware
+    target_init();
+    // Check if dfu requested
+    if(target_is_dfu_requested()) {
+        target_switch2dfu();
+    }
+    // Switch to OS
+    target_switch2os();
+    // Never should get here
+    return 0;
+}

+ 204 - 0
bootloader/targets/f2/STM32L476RGTx_FLASH.ld

@@ -0,0 +1,204 @@
+/*
+******************************************************************************
+**
+
+**  File        : LinkerScript.ld
+**
+**  Author		: Auto-generated by System Workbench for STM32
+**
+**  Abstract    : Linker script for STM32L476RGTx series
+**                1024Kbytes FLASH and 128Kbytes RAM
+**
+**                Set heap size, stack size and stack location according
+**                to application requirements.
+**
+**                Set memory bank area and size if external memory is used.
+**
+**  Target      : STMicroelectronics STM32
+**
+**  Distribution: The file is distributed “as is,” without any warranty
+**                of any kind.
+**
+*****************************************************************************
+** @attention
+**
+** <h2><center>&copy; COPYRIGHT(c) 2019 STMicroelectronics</center></h2>
+**
+** Redistribution and use in source and binary forms, with or without modification,
+** are permitted provided that the following conditions are met:
+**   1. Redistributions of source code must retain the above copyright notice,
+**      this list of conditions and the following disclaimer.
+**   2. Redistributions in binary form must reproduce the above copyright notice,
+**      this list of conditions and the following disclaimer in the documentation
+**      and/or other materials provided with the distribution.
+**   3. Neither the name of STMicroelectronics nor the names of its contributors
+**      may be used to endorse or promote products derived from this software
+**      without specific prior written permission.
+**
+** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20018000;    /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200;      /* required amount of heap  */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+RAM (xrw)      : ORIGIN = 0x20000000, LENGTH = 96K
+RAM2 (xrw)      : ORIGIN = 0x10000000, LENGTH = 32K
+FLASH (rx)      : ORIGIN = 0x8000000, LENGTH = 1024K
+}
+
+/* Define output sections */
+SECTIONS
+{
+  /* The startup code goes first into FLASH */
+  .isr_vector :
+  {
+    . = ALIGN(8);
+    KEEP(*(.isr_vector)) /* Startup code */
+    . = ALIGN(8);
+  } >FLASH
+
+  /* The program code and other data goes into FLASH */
+  .text :
+  {
+    . = ALIGN(8);
+    *(.text)           /* .text sections (code) */
+    *(.text*)          /* .text* sections (code) */
+    *(.glue_7)         /* glue arm to thumb code */
+    *(.glue_7t)        /* glue thumb to arm code */
+    *(.eh_frame)
+
+    KEEP (*(.init))
+    KEEP (*(.fini))
+
+    . = ALIGN(8);
+    _etext = .;        /* define a global symbols at end of code */
+  } >FLASH
+
+  /* Constant data goes into FLASH */
+  .rodata :
+  {
+    . = ALIGN(8);
+    *(.rodata)         /* .rodata sections (constants, strings, etc.) */
+    *(.rodata*)        /* .rodata* sections (constants, strings, etc.) */
+    . = ALIGN(8);
+  } >FLASH
+
+  .ARM.extab   : 
+  { 
+  . = ALIGN(8);
+  *(.ARM.extab* .gnu.linkonce.armextab.*)
+  . = ALIGN(8);
+  } >FLASH
+  .ARM : {
+	. = ALIGN(8);
+    __exidx_start = .;
+    *(.ARM.exidx*)
+    __exidx_end = .;
+	. = ALIGN(8);
+  } >FLASH
+
+  .preinit_array     :
+  {
+	. = ALIGN(8);
+    PROVIDE_HIDDEN (__preinit_array_start = .);
+    KEEP (*(.preinit_array*))
+    PROVIDE_HIDDEN (__preinit_array_end = .);
+	. = ALIGN(8);
+  } >FLASH
+  
+  .init_array :
+  {
+	. = ALIGN(8);
+    PROVIDE_HIDDEN (__init_array_start = .);
+    KEEP (*(SORT(.init_array.*)))
+    KEEP (*(.init_array*))
+    PROVIDE_HIDDEN (__init_array_end = .);
+	. = ALIGN(8);
+  } >FLASH
+  .fini_array :
+  {
+	. = ALIGN(8);
+    PROVIDE_HIDDEN (__fini_array_start = .);
+    KEEP (*(SORT(.fini_array.*)))
+    KEEP (*(.fini_array*))
+    PROVIDE_HIDDEN (__fini_array_end = .);
+	. = ALIGN(8);
+  } >FLASH
+
+  /* used by the startup to initialize data */
+  _sidata = LOADADDR(.data);
+
+  /* Initialized data sections goes into RAM, load LMA copy after code */
+  .data : 
+  {
+    . = ALIGN(8);
+    _sdata = .;        /* create a global symbol at data start */
+    *(.data)           /* .data sections */
+    *(.data*)          /* .data* sections */
+
+    . = ALIGN(8);
+    _edata = .;        /* define a global symbol at data end */
+  } >RAM AT> FLASH
+
+  
+  /* Uninitialized data section */
+  . = ALIGN(4);
+  .bss :
+  {
+    /* This is used by the startup in order to initialize the .bss secion */
+    _sbss = .;         /* define a global symbol at bss start */
+    __bss_start__ = _sbss;
+    *(.bss)
+    *(.bss*)
+    *(COMMON)
+
+    . = ALIGN(4);
+    _ebss = .;         /* define a global symbol at bss end */
+    __bss_end__ = _ebss;
+  } >RAM
+
+  /* User_heap_stack section, used to check that there is enough RAM left */
+  ._user_heap_stack :
+  {
+    . = ALIGN(8);
+    PROVIDE ( end = . );
+    PROVIDE ( _end = . );
+    . = . + _Min_Heap_Size;
+    . = . + _Min_Stack_Size;
+    . = ALIGN(8);
+  } >RAM
+
+  
+
+  /* Remove information from the standard libraries */
+  /DISCARD/ :
+  {
+    libc.a ( * )
+    libm.a ( * )
+    libgcc.a ( * )
+  }
+
+  .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+

+ 154 - 0
bootloader/targets/f2/target.c

@@ -0,0 +1,154 @@
+#include <target.h>
+#include <stm32l4xx.h>
+#include <stm32l4xx_ll_system.h>
+#include <stm32l4xx_ll_bus.h>
+#include <stm32l4xx_ll_utils.h>
+#include <stm32l4xx_ll_rcc.h>
+#include <stm32l4xx_ll_rtc.h>
+#include <stm32l4xx_ll_pwr.h>
+#include <stm32l4xx_ll_gpio.h>
+
+// Boot request enum
+#define BOOT_REQUEST_NONE 0x00000000
+#define BOOT_REQUEST_DFU 0xDF00B000
+// Boot to DFU pin
+#define BOOT_DFU_PORT GPIOB
+#define BOOT_DFU_PIN LL_GPIO_PIN_8
+// LCD backlight
+#define BOOT_LCD_BL_PORT GPIOB
+#define BOOT_LCD_BL_PIN LL_GPIO_PIN_6
+// LEDs
+#define LED_RED_PORT GPIOA
+#define LED_RED_PIN LL_GPIO_PIN_8
+#define LED_GREEN_PORT GPIOB
+#define LED_GREEN_PIN LL_GPIO_PIN_14
+#define LED_BLUE_PORT GPIOB
+#define LED_BLUE_PIN LL_GPIO_PIN_1
+// USB pins
+#define BOOT_USB_PORT GPIOA
+#define BOOT_USB_DM_PIN LL_GPIO_PIN_11
+#define BOOT_USB_DP_PIN LL_GPIO_PIN_12
+#define BOOT_USB_PIN (BOOT_USB_DM_PIN | BOOT_USB_DP_PIN)
+
+void clock_init() {
+    LL_FLASH_SetLatency(LL_FLASH_LATENCY_4);
+    LL_RCC_MSI_Enable();
+    while(LL_RCC_MSI_IsReady() != 1) {
+    }
+
+    /* Main PLL configuration and activation */
+    LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_MSI, LL_RCC_PLLM_DIV_1, 40, LL_RCC_PLLR_DIV_2);
+    LL_RCC_PLL_Enable();
+    LL_RCC_PLL_EnableDomain_SYS();
+    while(LL_RCC_PLL_IsReady() != 1) {
+    }
+
+    /* Sysclk activation on the main PLL */
+    LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1);
+    LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL);
+    while(LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) {
+    };
+
+    /* Set APB1 & APB2 prescaler*/
+    LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1);
+    LL_RCC_SetAPB2Prescaler(LL_RCC_APB2_DIV_1);
+
+    /* Set systick to 1ms in using frequency set to 80MHz */
+    /* This frequency can be calculated through LL RCC macro */
+    /* ex: __LL_RCC_CALC_PLLCLK_FREQ(__LL_RCC_CALC_MSI_FREQ(LL_RCC_MSIRANGESEL_RUN, LL_RCC_MSIRANGE_6), 
+                                    LL_RCC_PLLM_DIV_1, 40, LL_RCC_PLLR_DIV_2)*/
+    LL_Init1msTick(80000000);
+
+    /* Update CMSIS variable (which can be updated also through SystemCoreClockUpdate function) */
+    LL_SetSystemCoreClock(80000000);
+}
+
+void gpio_init() {
+    LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOA);
+    LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOB);
+    // USB D+
+    LL_GPIO_SetPinMode(BOOT_USB_PORT, BOOT_USB_DP_PIN, LL_GPIO_MODE_OUTPUT);
+    LL_GPIO_SetPinSpeed(BOOT_USB_PORT, BOOT_USB_DP_PIN, LL_GPIO_SPEED_FREQ_VERY_HIGH);
+    LL_GPIO_SetPinOutputType(BOOT_USB_PORT, BOOT_USB_DP_PIN, LL_GPIO_OUTPUT_OPENDRAIN);
+    // USB D-
+    LL_GPIO_SetPinMode(BOOT_USB_PORT, BOOT_USB_DM_PIN, LL_GPIO_MODE_OUTPUT);
+    LL_GPIO_SetPinSpeed(BOOT_USB_PORT, BOOT_USB_DM_PIN, LL_GPIO_SPEED_FREQ_VERY_HIGH);
+    LL_GPIO_SetPinOutputType(BOOT_USB_PORT, BOOT_USB_DM_PIN, LL_GPIO_OUTPUT_OPENDRAIN);
+    // Button: back
+    LL_GPIO_SetPinMode(BOOT_DFU_PORT, BOOT_DFU_PIN, LL_GPIO_MODE_INPUT);
+    LL_GPIO_SetPinPull(BOOT_DFU_PORT, BOOT_DFU_PIN, LL_GPIO_PULL_DOWN);
+    // Display backlight
+    LL_GPIO_SetPinMode(BOOT_LCD_BL_PORT, BOOT_LCD_BL_PIN, LL_GPIO_MODE_OUTPUT);
+    LL_GPIO_SetPinSpeed(BOOT_LCD_BL_PORT, BOOT_LCD_BL_PIN, LL_GPIO_SPEED_FREQ_LOW);
+    LL_GPIO_SetPinOutputType(BOOT_LCD_BL_PORT, BOOT_LCD_BL_PIN, LL_GPIO_OUTPUT_PUSHPULL);
+    // LEDs
+    LL_GPIO_SetPinMode(LED_RED_PORT, LED_RED_PIN, LL_GPIO_MODE_OUTPUT);
+    LL_GPIO_SetPinOutputType(LED_RED_PORT, LED_RED_PIN, LL_GPIO_OUTPUT_OPENDRAIN);
+    LL_GPIO_SetOutputPin(LED_RED_PORT, LED_RED_PIN);
+    LL_GPIO_SetPinMode(LED_GREEN_PORT, LED_GREEN_PIN, LL_GPIO_MODE_OUTPUT);
+    LL_GPIO_SetPinOutputType(LED_GREEN_PORT, LED_GREEN_PIN, LL_GPIO_OUTPUT_OPENDRAIN);
+    LL_GPIO_SetOutputPin(LED_GREEN_PORT, LED_GREEN_PIN);
+    LL_GPIO_SetPinMode(LED_BLUE_PORT, LED_BLUE_PIN, LL_GPIO_MODE_OUTPUT);
+    LL_GPIO_SetPinOutputType(LED_BLUE_PORT, LED_BLUE_PIN, LL_GPIO_OUTPUT_OPENDRAIN);
+    LL_GPIO_SetOutputPin(LED_BLUE_PORT, LED_BLUE_PIN);
+}
+
+void rtc_init() {
+    LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_PWR);
+    LL_PWR_EnableBkUpAccess();
+    LL_RCC_EnableRTC();
+}
+
+void lcd_backlight_on() {
+    LL_GPIO_SetOutputPin(BOOT_LCD_BL_PORT, BOOT_LCD_BL_PIN);
+}
+
+void usb_wire_reset() {
+    LL_GPIO_ResetOutputPin(BOOT_USB_PORT, BOOT_USB_PIN);
+    LL_mDelay(10);
+    LL_GPIO_SetOutputPin(BOOT_USB_PORT, BOOT_USB_PIN);
+}
+
+void target_init() {
+    clock_init();
+    rtc_init();
+    gpio_init();
+
+    usb_wire_reset();
+}
+
+int target_is_dfu_requested() {
+    if(LL_RTC_BAK_GetRegister(RTC, LL_RTC_BKP_DR0) == BOOT_REQUEST_DFU) {
+        LL_RTC_BAK_SetRegister(RTC, LL_RTC_BKP_DR0, BOOT_REQUEST_NONE);
+        return 1;
+    }
+
+    if(LL_GPIO_IsInputPinSet(BOOT_DFU_PORT, BOOT_DFU_PIN)) {
+        return 1;
+    }
+
+    return 0;
+}
+
+void target_switch(void* offset) {
+    asm volatile("ldr    r3, [%0]    \n"
+                 "msr    msp, r3     \n"
+                 "ldr    r3, [%1]    \n"
+                 "mov    pc, r3      \n"
+                 :
+                 : "r"(offset), "r"(offset + 0x4)
+                 : "r3");
+}
+
+void target_switch2dfu() {
+    LL_GPIO_ResetOutputPin(LED_BLUE_PORT, LED_BLUE_PIN);
+    // Remap memory to system bootloader
+    LL_SYSCFG_SetRemapMemory(LL_SYSCFG_REMAP_SYSTEMFLASH);
+    target_switch(0x0);
+}
+
+void target_switch2os() {
+    LL_GPIO_ResetOutputPin(LED_RED_PORT, LED_RED_PIN);
+    SCB->VTOR = OS_OFFSET;
+    target_switch((void*)(BOOT_ADDRESS + OS_OFFSET));
+}

+ 21 - 0
bootloader/targets/f2/target.mk

@@ -0,0 +1,21 @@
+BOOT_ADDRESS	= 0x08000000
+OS_OFFSET		= 0x00008000
+
+BOOT_CFLAGS		= -DBOOT_ADDRESS=$(BOOT_ADDRESS) -DOS_OFFSET=$(OS_OFFSET)
+MCU_FLAGS		= -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=hard
+
+CFLAGS			+= $(MCU_FLAGS) $(BOOT_CFLAGS) -DSTM32L4R7xx -Wall -fdata-sections -ffunction-sections
+LDFLAGS			+= $(MCU_FLAGS) -specs=nosys.specs -specs=nano.specs
+
+CUBE_DIR		= ../target_f2
+CUBE_CMSIS_DIR	= $(CUBE_DIR)/Drivers/CMSIS
+CUBE_HAL_DIR	= $(CUBE_DIR)/Drivers/STM32L4xx_HAL_Driver
+
+ASM_SOURCES		+= $(CUBE_CMSIS_DIR)/Device/ST/STM32L4xx/Source/Templates/gcc/startup_stm32l476xx.s
+C_SOURCES		+= $(CUBE_CMSIS_DIR)/Device/ST/STM32L4xx/Source/Templates/system_stm32l4xx.c
+C_SOURCES		+= $(CUBE_HAL_DIR)/Src/stm32l4xx_ll_utils.c
+
+CFLAGS			+= -I$(CUBE_CMSIS_DIR)/Include
+CFLAGS			+= -I$(CUBE_CMSIS_DIR)/Device/ST/STM32L4xx/Include
+CFLAGS			+= -I$(CUBE_HAL_DIR)/Inc
+LDFLAGS			+= -Ttargets/f2/STM32L476RGTx_FLASH.ld

+ 25 - 0
bootloader/targets/include/target.h

@@ -0,0 +1,25 @@
+#ifndef TARGET_H
+#define TARGET_H
+
+/*
+ * Initialize hardware
+*/
+void target_init();
+
+/*
+ * Check if dfu mode requested
+ * @return 1 if dfu mode requested, 0 if not
+*/
+int target_is_dfu_requested();
+
+/*
+ * Switch to dfu mode
+*/
+void target_switch2dfu();
+
+/*
+ * Switch to OS
+*/
+void target_switch2os();
+
+#endif

+ 15 - 0
core/boot.h

@@ -0,0 +1,15 @@
+/*
+Flipper devices inc.
+
+Bootloader API, must be implemented by target
+*/
+
+#ifndef __BOOT_H
+#define __BOOT_H
+
+/*
+ * @brief Request DFU and reboot
+*/
+void boot_restart_in_dfu();
+
+#endif

+ 1 - 1
docker/syntax_check.sh

@@ -1,6 +1,6 @@
 #!/usr/bin/env bash
 
-set -e
+# set -e
 
 CLANG_FORMAT_BIN="/usr/bin/clang-format-10"
 PATH="$HOME/.cargo/bin:${PATH}"

+ 1 - 0
target_f2/Makefile

@@ -44,6 +44,7 @@ C_DEFS =
 
 C_SOURCES +=  \
 Src/main.c \
+Src/boot.c \
 Src/freertos.c \
 Src/stm32l4xx_it.c \
 Src/stm32l4xx_hal_msp.c \

+ 1 - 1
target_f2/STM32L476RGTx_FLASH.ld

@@ -63,7 +63,7 @@ MEMORY
 {
 RAM (xrw)      : ORIGIN = 0x20000000, LENGTH = 96K
 RAM2 (xrw)      : ORIGIN = 0x10000000, LENGTH = 32K
-FLASH (rx)      : ORIGIN = 0x8000000, LENGTH = 1024K
+FLASH (rx)      : ORIGIN = 0x08008000, LENGTH = 992K
 }
 
 /* Define output sections */

+ 19 - 0
target_f2/Src/boot.c

@@ -0,0 +1,19 @@
+#include "boot.h"
+#include "stm32l4xx_ll_bus.h"
+#include "stm32l4xx_ll_rcc.h"
+#include "stm32l4xx_ll_rtc.h"
+#include "stm32l4xx_ll_pwr.h"
+
+#define BOOT_REQUEST_DFU 0xDF00B000
+
+void boot_restart_in_dfu() {
+    // Request DFU on boot
+    LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_PWR);
+    LL_PWR_EnableBkUpAccess();
+    // Enable RTC
+    LL_RCC_EnableRTC();
+    // Write backup registry
+    LL_RTC_BAK_SetRegister(RTC, LL_RTC_BKP_DR0, BOOT_REQUEST_DFU);
+    // Reset
+    NVIC_SystemReset();
+}

+ 1 - 1
target_f2/Src/main.c

@@ -20,6 +20,7 @@
 
 /* Includes ------------------------------------------------------------------*/
 #include "main.h"
+#include "boot.h"
 #include "cmsis_os.h"
 #include "usb_device.h"
 
@@ -89,7 +90,6 @@ void StartDefaultTask(void const* argument);
   */
 int main(void) {
     /* USER CODE BEGIN 1 */
-
     /* USER CODE END 1 */
 
     /* MCU Configuration--------------------------------------------------------*/

+ 2 - 0
target_f2/Src/system_stm32l4xx.c

@@ -123,6 +123,8 @@
 /*!< Uncomment the following line if you need to relocate your vector Table in
      Internal SRAM. */
 /* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET \
+    0x8000 /*!< Vector Table base offset field.
 #define VECT_TAB_OFFSET \
     0x00 /*!< Vector Table base offset field.
                                    This value must be a multiple of 0x200. */

+ 3 - 0
target_f2/deploy-dfu.sh

@@ -0,0 +1,3 @@
+#!/bin/bash
+
+dfu-util -D `dirname "$0"`/build/target_prod.bin -a 0 -s 0x08008000

+ 3 - 1
target_f2/deploy.sh

@@ -1 +1,3 @@
-st-flash write `dirname "$0"`/build/target_prod.bin 0x08000000
+#!/bin/bash
+
+st-flash --reset write `dirname "$0"`/build/target_prod.bin 0x08008000

+ 1 - 1
wiki-deploy.sh

@@ -1,4 +1,4 @@
 rm -rf flipperzero-firmware-community.wiki/*
-cp -r wiki/* flipperzero-firmware-community.wiki/
+cp -Hr wiki/* flipperzero-firmware-community.wiki/
 cp README.md flipperzero-firmware-community.wiki/Home.md
 cd flipperzero-firmware-community.wiki && git add * && git commit -a -m "deployed by script" && git push -f

+ 37 - 0
wiki/Testing.md

@@ -0,0 +1,37 @@
+# Bootloader test
+
+1. # Clean flash
+2. `make -C bootloader flash` # Load bootloader
+3.  # reboot device
+    1. Press right
+    2. Press left
+    3. Wait 0.1 s
+    4. Release left
+    5. Release right
+4. Wait 0.5 s
+5. # Expect no FW
+    1. Expect: no uart welcome message
+    2. Expect: red led on
+    3. Expect: no USB
+6. # reboot device and go to DFU
+    1. Press left 
+    2. Press right
+    3. Wait 0.1 s
+    4. Release left
+    5. Wait 0.5 s 
+    6. Release right
+7. Wait 0.5 s
+8. # Expect DFU
+    1. Expect: blue led on
+    2. Expect: USB: DFU
+9. `target_f2/deploy-dfu.sh` # load FW
+10.  # reboot device
+    1. Press right
+    2. Press left
+    3. Wait 0.1 s
+    4. Release left
+    5. Release right
+11. Wait 0.5 s
+12. # Expect FW
+    1. Expect: uart welcome message
+    2. Expect: USB Flipper CDC

+ 1 - 0
wiki/fw/Bootloader.md

@@ -0,0 +1 @@
+bootloader/ReadMe.md

+ 27 - 11
wiki/fw/Firmware.md

@@ -6,30 +6,31 @@ _Overview of Flipper firmware architecture:_
 
 ```
 .
-├── applications 	# Flipper applications
-│   └── furi_test	# Test app for checking and demonstrating FURI func
-├── core 	# Main feature like OS, HAL (target-independed)
-├── target_f1 # Target-depended code for target F1
-│   ├── Drivers # STM HAL drivers
+├── applications    # Flipper applications
+│   └── furi_test   # Test app for checking and demonstrating FURI func
+├── bootloader      # Firmware bootloader, used for `target_f2` and newer
+├── core            # Main feature like OS, HAL (target-independed)
+├── target_f1       # Target-depended code for target F1
+│   ├── Drivers     # STM HAL drivers
 │   │   ├── CMSIS
 │   │   └── STM32L4xx_HAL_Driver
 │   │       ├── Inc
 │   │       │   └── Legacy
 │   │       └── Src
-│   ├── Inc # Autogenerated CubeMX code and target-depended includes
+│   ├── Inc         # Autogenerated CubeMX code and target-depended includes
 │   ├── Middlewares
 │   │   ├── ST
 │   │   │   └── STM32_USB_Device_Library
 │   │   └── Third_Party
 │   │       └── FreeRTOS
-│   └── Src # Autogenerated CubeMX code and target-depended sources
-├── target_lo # Target-depended code for local linux target
+│   └── Src         # Autogenerated CubeMX code and target-depended sources
+├── target_lo       # Target-depended code for local linux target
 │   ├── Inc
 │   └── Src
-└── wiki # Documentation (wiki) generates from this files
+└── wiki            # Documentation (wiki) generates from this files
     ├── applications # info about separate features of flipper
-    ├── fw # core, environment info about firmware
-    └── hw # info about hardware
+    ├── fw          # core, environment info about firmware
+    └── hw          # info about hardware
 ```
 
 # HAL
@@ -48,6 +49,21 @@ Some flipper-specific implementation of gpio/HAL:
 
 Files location: `/app/app_hal.[ch]`
 
+# Bootloader
+
+For production targets('target_f2' and newer) bootloader must be flashed first.
+Detailed instruction on how to compile and flash you can find in `bootloader` fodler.
+
+Production version will have following features:
+
+- Hardware initialization
+- Firmware CRC check
+- Firmware update
+- Interactive UI
+- Boot process LED indicators
+- FS check
+- Recovery mode
+
 # OS
 
 We use FreeRTOS 10.0.1 for sheduling. Documentation available on [freertos.org](https://www.freertos.org/a00106.html).