diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml
index 1c2a0d1d..000aa138 100644
--- a/.github/workflows/ci.yml
+++ b/.github/workflows/ci.yml
@@ -71,6 +71,39 @@ jobs:
firmware/.obj/f2/firmware.hex
if-no-files-found: error
retention-days: 7
+
+ - name: Build F3 bootloader in docker
+ uses: ./.github/actions/docker
+ with:
+ run: make -C bootloader TARGET=f3
+
+ - name: Publish F3 bootloader artifacts
+ uses: actions/upload-artifact@v2
+ with:
+ name: bootloader_f3
+ path: |
+ bootloader/.obj/f3/bootloader.elf
+ bootloader/.obj/f3/bootloader.bin
+ bootloader/.obj/f3/bootloader.hex
+ if-no-files-found: error
+ retention-days: 7
+
+ - name: Build F3 firmware in docker
+ uses: ./.github/actions/docker
+ with:
+ run: make -C firmware TARGET=f3 APP_RELEASE=1
+
+ - name: Publish F3 firmware artifacts
+ uses: actions/upload-artifact@v2
+ with:
+ name: firmware_f3
+ path: |
+ firmware/.obj/f3/firmware.elf
+ firmware/.obj/f3/firmware.bin
+ firmware/.obj/f3/firmware.hex
+ if-no-files-found: error
+ retention-days: 7
+
upload:
name: Upload artifacts to external storage
needs: build
diff --git a/.gitmodules b/.gitmodules
index 38192f3d..aab7c81c 100644
--- a/.gitmodules
+++ b/.gitmodules
@@ -4,3 +4,6 @@
[submodule "lib/mlib"]
path = lib/mlib
url = https://github.com/P-p-H-d/mlib.git
+[submodule "lib/STM32CubeWB"]
+ path = lib/STM32CubeWB
+ url = https://github.com/STMicroelectronics/STM32CubeWB.git
diff --git a/bootloader/targets/f3/stm32wb55xx_flash_cm4.ld b/bootloader/targets/f3/stm32wb55xx_flash_cm4.ld
new file mode 100644
index 00000000..ce970b16
--- /dev/null
+++ b/bootloader/targets/f3/stm32wb55xx_flash_cm4.ld
@@ -0,0 +1,187 @@
+/**
+*****************************************************************************
+**
+** File : stm32wb55xx_flash_cm4.ld
+**
+** Abstract : System Workbench Minimal System calls file
+**
+** For more information about which c-functions
+** need which of these lowlevel functions
+** please consult the Newlib libc-manual
+**
+** Environment : System Workbench for MCU
+**
+** Distribution: The file is distributed “as is,” without any warranty
+** of any kind.
+**
+*****************************************************************************
+**
+**
© COPYRIGHT(c) 2019 Ac6
+**
+** 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 Ac6 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 = 0x20030000; /* 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
+{
+FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K
+RAM1 (xrw) : ORIGIN = 0x20000004, LENGTH = 0x2FFFC
+RAM_SHARED (xrw) : ORIGIN = 0x20030000, LENGTH = 10K
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(4);
+ *(.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(4);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+ .ARM : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >FLASH
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >FLASH
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >FLASH
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM1 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;
+ } >RAM1
+
+ /* 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);
+ } >RAM1
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+ MAPPING_TABLE (NOLOAD) : { *(MAPPING_TABLE) } >RAM_SHARED
+ MB_MEM1 (NOLOAD) : { *(MB_MEM1) } >RAM_SHARED
+ MB_MEM2 (NOLOAD) : { _sMB_MEM2 = . ; *(MB_MEM2) ; _eMB_MEM2 = . ; } >RAM_SHARED
+}
+
+
diff --git a/bootloader/targets/f3/target.c b/bootloader/targets/f3/target.c
new file mode 100644
index 00000000..60b72f90
--- /dev/null
+++ b/bootloader/targets/f3/target.c
@@ -0,0 +1,160 @@
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+// 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_12
+// LCD backlight
+#define BOOT_LCD_BL_PORT GPIOA
+#define BOOT_LCD_BL_PIN LL_GPIO_PIN_15
+// LEDs
+#define LED_RED_PORT GPIOA
+#define LED_RED_PIN LL_GPIO_PIN_1
+#define LED_GREEN_PORT GPIOA
+#define LED_GREEN_PIN LL_GPIO_PIN_2
+#define LED_BLUE_PORT GPIOA
+#define LED_BLUE_PIN LL_GPIO_PIN_3
+// 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_3);
+ 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, 32, 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 */
+ /* Set CPU1 prescaler*/
+ LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1);
+
+ /* Set CPU2 prescaler*/
+ LL_C2_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_2);
+
+ LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL);
+ while(LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) {
+ }
+
+ /* Set AHB SHARED prescaler*/
+ LL_RCC_SetAHB4Prescaler(LL_RCC_SYSCLK_DIV_1);
+
+ /* Set APB1 prescaler*/
+ LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1);
+
+ /* Set APB2 prescaler*/
+ LL_RCC_SetAPB2Prescaler(LL_RCC_APB2_DIV_1);
+
+ LL_Init1msTick(64000000);
+
+ /* Update CMSIS variable (which can be updated also through SystemCoreClockUpdate function) */
+ LL_SetSystemCoreClock(64000000);
+}
+
+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_UP);
+ // 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_RCC_EnableRTC();
+ LL_APB2_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_RTCAPB);
+ LL_PWR_EnableBkUpAccess();
+}
+
+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 = BOOT_ADDRESS + OS_OFFSET;
+ target_switch((void*)(BOOT_ADDRESS + OS_OFFSET));
+}
\ No newline at end of file
diff --git a/bootloader/targets/f3/target.mk b/bootloader/targets/f3/target.mk
new file mode 100644
index 00000000..d031ead8
--- /dev/null
+++ b/bootloader/targets/f3/target.mk
@@ -0,0 +1,28 @@
+TOOLCHAIN = arm
+
+BOOT_ADDRESS = 0x08000000
+FW_ADDRESS = 0x08008000
+OS_OFFSET = 0x00008000
+FLASH_ADDRESS = 0x08000000
+
+BOOT_CFLAGS = -DBOOT_ADDRESS=$(BOOT_ADDRESS) -DFW_ADDRESS=$(FW_ADDRESS) -DOS_OFFSET=$(OS_OFFSET)
+MCU_FLAGS = -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=hard
+
+CFLAGS += $(MCU_FLAGS) $(BOOT_CFLAGS) -DSTM32WB55xx -Wall -fdata-sections -ffunction-sections
+LDFLAGS += $(MCU_FLAGS) -specs=nosys.specs -specs=nano.specs
+
+CUBE_DIR = ../lib/STM32CubeWB
+
+ASM_SOURCES += $(CUBE_DIR)/Drivers/CMSIS/Device/ST/STM32WBxx/Source/Templates/gcc/startup_stm32wb55xx_cm4.s
+C_SOURCES += $(CUBE_DIR)/Drivers/CMSIS/Device/ST/STM32WBxx/Source/Templates/system_stm32wbxx.c
+C_SOURCES += $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_utils.c
+
+CFLAGS += -I$(CUBE_DIR)/Drivers/CMSIS/Include
+CFLAGS += -I$(CUBE_DIR)/Drivers/CMSIS/Device/ST/STM32WBxx/Include
+CFLAGS += -I$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Inc
+
+LDFLAGS += -Ttargets/f3/stm32wb55xx_flash_cm4.ld
+
+ASM_SOURCES += $(wildcard $(TARGET_DIR)/*.s)
+C_SOURCES += $(wildcard $(TARGET_DIR)/*.c)
+CPP_SOURCES += $(wildcard $(TARGET_DIR)/*.cpp)
diff --git a/debug/stm32wbx.cfg b/debug/stm32wbx.cfg
new file mode 100644
index 00000000..ccb70d17
--- /dev/null
+++ b/debug/stm32wbx.cfg
@@ -0,0 +1,105 @@
+# script for stm32wbx family
+
+gdb_port 4242
+
+#
+# stm32wb devices support both JTAG and SWD transports.
+#
+source [find target/swj-dp.tcl]
+source [find mem_helper.tcl]
+
+if { [info exists CHIPNAME] } {
+ set _CHIPNAME $CHIPNAME
+} else {
+ set _CHIPNAME stm32wbx
+}
+
+set _ENDIAN little
+
+# Work-area is a space in RAM used for flash programming
+# By default use 64kB
+if { [info exists WORKAREASIZE] } {
+ set _WORKAREASIZE $WORKAREASIZE
+} else {
+ set _WORKAREASIZE 0x10000
+}
+
+#jtag scan chain
+if { [info exists CPUTAPID] } {
+ set _CPUTAPID $CPUTAPID
+} else {
+ if { [using_jtag] } {
+ set _CPUTAPID 0x6ba00477
+ } else {
+ # SWD IDCODE (single drop, arm)
+ set _CPUTAPID 0x6ba02477
+ }
+}
+
+swj_newdap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID
+dap create $_CHIPNAME.dap -chain-position $_CHIPNAME.cpu
+
+if {[using_jtag]} {
+ jtag newtap $_CHIPNAME bs -irlen 5
+}
+
+set _TARGETNAME $_CHIPNAME.cpu
+target create $_TARGETNAME cortex_m -endian $_ENDIAN -dap $_CHIPNAME.dap
+
+$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0
+
+set _FLASHNAME $_CHIPNAME.flash
+flash bank $_FLASHNAME stm32l4x 0 0 0 0 $_TARGETNAME
+
+# Common knowledges tells JTAG speed should be <= F_CPU/6.
+# F_CPU after reset is MSI 4MHz, so use F_JTAG = 500 kHz to stay on
+# the safe side.
+#
+# Note that there is a pretty wide band where things are
+# more or less stable, see http://openocd.zylin.com/#/c/3366/
+adapter speed 500
+
+adapter srst delay 100
+if {[using_jtag]} {
+ jtag_ntrst_delay 100
+}
+
+reset_config srst_nogate
+
+if {![using_hla]} {
+ # if srst is not fitted use SYSRESETREQ to
+ # perform a soft reset
+ cortex_m reset_config sysresetreq
+}
+
+$_TARGETNAME configure -event reset-init {
+ # CPU comes out of reset with MSI_ON | MSI_RDY | MSI Range 4 MHz.
+ # Configure system to use MSI 24 MHz clock, compliant with VOS default Range1.
+ # 2 WS compliant with VOS=Range1 and 24 MHz.
+ mmw 0x58004000 0x00000102 0 ;# FLASH_ACR |= PRFTBE | 2(Latency)
+ mmw 0x58000000 0x00000091 0 ;# RCC_CR = MSI_ON | MSI Range 24 MHz
+ # Boost JTAG frequency
+ adapter speed 4000
+}
+
+$_TARGETNAME configure -event reset-start {
+ # Reset clock is MSI (4 MHz)
+ adapter speed 500
+}
+
+$_TARGETNAME configure -event examine-end {
+ # Enable debug during low power modes (uses more power)
+ # DBGMCU_CR |= DBG_STANDBY | DBG_STOP | DBG_SLEEP
+ mmw 0xE0042004 0x00000007 0
+
+ # Stop watchdog counters during halt
+ # DBGMCU_APB1_FZR1 |= DBG_IWDG_STOP | DBG_WWDG_STOP
+ mmw 0xE004203C 0x00001800 0
+}
+
+$_TARGETNAME configure -event trace-config {
+ # Set TRACE_IOEN; TRACE_MODE is set to async; when using sync
+ # change this value accordingly to configure trace pins
+ # assignment
+ mmw 0xE0042004 0x00000020 0
+}
diff --git a/firmware/targets/f3/Inc/FreeRTOSConfig.h b/firmware/targets/f3/Inc/FreeRTOSConfig.h
new file mode 100644
index 00000000..ca8cb033
--- /dev/null
+++ b/firmware/targets/f3/Inc/FreeRTOSConfig.h
@@ -0,0 +1,172 @@
+/* USER CODE BEGIN Header */
+/*
+ * FreeRTOS Kernel V10.2.1
+ * Portion Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
+ * Portion Copyright (C) 2019 StMicroelectronics, Inc. All Rights Reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of
+ * this software and associated documentation files (the "Software"), to deal in
+ * the Software without restriction, including without limitation the rights to
+ * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
+ * the Software, and to permit persons to whom the Software is furnished to do so,
+ * subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+ * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
+ * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
+ * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ *
+ * http://www.FreeRTOS.org
+ * http://aws.amazon.com/freertos
+ *
+ * 1 tab == 4 spaces!
+ */
+/* USER CODE END Header */
+
+#ifndef FREERTOS_CONFIG_H
+#define FREERTOS_CONFIG_H
+
+/*-----------------------------------------------------------
+ * Application specific definitions.
+ *
+ * These definitions should be adjusted for your particular hardware and
+ * application requirements.
+ *
+ * These parameters and more are described within the 'configuration' section of the
+ * FreeRTOS API documentation available on the FreeRTOS.org web site.
+ *
+ * See http://www.freertos.org/a00110.html
+ *----------------------------------------------------------*/
+
+/* USER CODE BEGIN Includes */
+/* Section where include file can be added */
+/* USER CODE END Includes */
+
+/* Ensure definitions are only used by the compiler, and not by the assembler. */
+#if defined(__ICCARM__) || defined(__CC_ARM) || defined(__GNUC__)
+ #include
+ extern uint32_t SystemCoreClock;
+/* USER CODE BEGIN 0 */
+ extern void configureTimerForRunTimeStats(void);
+ extern unsigned long getRunTimeCounterValue(void);
+/* USER CODE END 0 */
+#endif
+#define configENABLE_FPU 1
+#define configENABLE_MPU 0
+
+#define configUSE_PREEMPTION 1
+#define configSUPPORT_STATIC_ALLOCATION 1
+#define configSUPPORT_DYNAMIC_ALLOCATION 1
+#define configUSE_IDLE_HOOK 1
+#define configUSE_TICK_HOOK 0
+#define configCPU_CLOCK_HZ ( SystemCoreClock )
+#define configTICK_RATE_HZ ((TickType_t)1000)
+#define configMAX_PRIORITIES ( 56 )
+#define configMINIMAL_STACK_SIZE ((uint16_t)128)
+#define configTOTAL_HEAP_SIZE ((size_t)40960)
+#define configMAX_TASK_NAME_LEN ( 16 )
+#define configGENERATE_RUN_TIME_STATS 1
+#define configUSE_TRACE_FACILITY 1
+#define configUSE_16_BIT_TICKS 0
+#define configUSE_MUTEXES 1
+#define configQUEUE_REGISTRY_SIZE 8
+#define configCHECK_FOR_STACK_OVERFLOW 1
+#define configUSE_RECURSIVE_MUTEXES 1
+#define configUSE_COUNTING_SEMAPHORES 1
+#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
+#define configRECORD_STACK_HIGH_ADDRESS 1
+/* USER CODE BEGIN MESSAGE_BUFFER_LENGTH_TYPE */
+/* Defaults to size_t for backward compatibility, but can be changed
+ if lengths will always be less than the number of bytes in a size_t. */
+#define configMESSAGE_BUFFER_LENGTH_TYPE size_t
+#define configNUM_THREAD_LOCAL_STORAGE_POINTERS 1
+/* USER CODE END MESSAGE_BUFFER_LENGTH_TYPE */
+
+/* Co-routine definitions. */
+#define configUSE_CO_ROUTINES 0
+#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
+
+/* Software timer definitions. */
+#define configUSE_TIMERS 1
+#define configTIMER_TASK_PRIORITY ( 2 )
+#define configTIMER_QUEUE_LENGTH 10
+#define configTIMER_TASK_STACK_DEPTH 256
+
+/* Set the following definitions to 1 to include the API function, or zero
+to exclude the API function. */
+#define INCLUDE_vTaskPrioritySet 1
+#define INCLUDE_uxTaskPriorityGet 1
+#define INCLUDE_vTaskDelete 1
+#define INCLUDE_vTaskCleanUpResources 0
+#define INCLUDE_vTaskSuspend 1
+#define INCLUDE_vTaskDelayUntil 1
+#define INCLUDE_vTaskDelay 1
+#define INCLUDE_xTaskGetSchedulerState 1
+#define INCLUDE_xTimerPendFunctionCall 1
+#define INCLUDE_xQueueGetMutexHolder 1
+#define INCLUDE_uxTaskGetStackHighWaterMark 1
+#define INCLUDE_eTaskGetState 1
+
+/*
+ * The CMSIS-RTOS V2 FreeRTOS wrapper is dependent on the heap implementation used
+ * by the application thus the correct define need to be enabled below
+ */
+#define USE_FreeRTOS_HEAP_4
+
+/* Cortex-M specific definitions. */
+#ifdef __NVIC_PRIO_BITS
+ /* __BVIC_PRIO_BITS will be specified when CMSIS is being used. */
+ #define configPRIO_BITS __NVIC_PRIO_BITS
+#else
+ #define configPRIO_BITS 4
+#endif
+
+/* The lowest interrupt priority that can be used in a call to a "set priority"
+function. */
+#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 15
+
+/* The highest interrupt priority that can be used by any interrupt service
+routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL
+INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER
+PRIORITY THAN THIS! (higher priorities are lower numeric values. */
+#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 5
+
+/* Interrupt priorities used by the kernel port layer itself. These are generic
+to all Cortex-M ports, and do not rely on any particular library functions. */
+#define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
+/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
+See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
+#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
+
+/* Normal assert() semantics without relying on the provision of an assert.h
+header file. */
+/* USER CODE BEGIN 1 */
+#define configASSERT( x ) if ((x) == 0) {taskDISABLE_INTERRUPTS(); for( ;; );}
+/* USER CODE END 1 */
+
+/* Definitions that map the FreeRTOS port interrupt handlers to their CMSIS
+standard names. */
+#define vPortSVCHandler SVC_Handler
+#define xPortPendSVHandler PendSV_Handler
+
+/* IMPORTANT: This define is commented when used with STM32Cube firmware, when the timebase source is SysTick,
+ to prevent overwriting SysTick_Handler defined within STM32Cube HAL */
+
+#define xPortSysTickHandler SysTick_Handler
+
+/* USER CODE BEGIN 2 */
+/* Definitions needed when configGENERATE_RUN_TIME_STATS is on */
+#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS configureTimerForRunTimeStats
+#define portGET_RUN_TIME_COUNTER_VALUE getRunTimeCounterValue
+/* USER CODE END 2 */
+
+/* USER CODE BEGIN Defines */
+/* Section where parameter definitions can be added (for instance, to override default ones in FreeRTOS.h) */
+/* USER CODE END Defines */
+
+#endif /* FREERTOS_CONFIG_H */
diff --git a/firmware/targets/f3/Inc/adc.h b/firmware/targets/f3/Inc/adc.h
new file mode 100644
index 00000000..fd4c3847
--- /dev/null
+++ b/firmware/targets/f3/Inc/adc.h
@@ -0,0 +1,58 @@
+/**
+ ******************************************************************************
+ * File Name : ADC.h
+ * Description : This file provides code for the configuration
+ * of the ADC instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __adc_H
+#define __adc_H
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern ADC_HandleTypeDef hadc1;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_ADC1_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ adc_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/comp.h b/firmware/targets/f3/Inc/comp.h
new file mode 100644
index 00000000..3ec923b1
--- /dev/null
+++ b/firmware/targets/f3/Inc/comp.h
@@ -0,0 +1,58 @@
+/**
+ ******************************************************************************
+ * File Name : COMP.h
+ * Description : This file provides code for the configuration
+ * of the COMP instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __comp_H
+#define __comp_H
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern COMP_HandleTypeDef hcomp1;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_COMP1_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ comp_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/gpio.h b/firmware/targets/f3/Inc/gpio.h
new file mode 100644
index 00000000..6fac8b7a
--- /dev/null
+++ b/firmware/targets/f3/Inc/gpio.h
@@ -0,0 +1,57 @@
+/**
+ ******************************************************************************
+ * File Name : gpio.h
+ * Description : This file contains all the functions prototypes for
+ * the gpio
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __gpio_H
+#define __gpio_H
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_GPIO_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ pinoutConfig_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/i2c.h b/firmware/targets/f3/Inc/i2c.h
new file mode 100644
index 00000000..9fa519cf
--- /dev/null
+++ b/firmware/targets/f3/Inc/i2c.h
@@ -0,0 +1,58 @@
+/**
+ ******************************************************************************
+ * File Name : I2C.h
+ * Description : This file provides code for the configuration
+ * of the I2C instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __i2c_H
+#define __i2c_H
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern I2C_HandleTypeDef hi2c1;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_I2C1_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ i2c_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/main.h b/firmware/targets/f3/Inc/main.h
new file mode 100644
index 00000000..40550057
--- /dev/null
+++ b/firmware/targets/f3/Inc/main.h
@@ -0,0 +1,190 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : main.h
+ * @brief : Header for main.c file.
+ * This file contains the common defines of the application.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __MAIN_H
+#define __MAIN_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32wbxx_hal.h"
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Exported types ------------------------------------------------------------*/
+/* USER CODE BEGIN ET */
+
+/* USER CODE END ET */
+
+/* Exported constants --------------------------------------------------------*/
+/* USER CODE BEGIN EC */
+
+/* USER CODE END EC */
+
+/* Exported macro ------------------------------------------------------------*/
+/* USER CODE BEGIN EM */
+
+/* USER CODE END EM */
+
+/* Exported functions prototypes ---------------------------------------------*/
+void Error_Handler(void);
+
+/* USER CODE BEGIN EFP */
+
+/* USER CODE END EFP */
+
+/* Private defines -----------------------------------------------------------*/
+#define BUTTON_BACK_Pin GPIO_PIN_13
+#define BUTTON_BACK_GPIO_Port GPIOC
+#define BUTTON_BACK_EXTI_IRQn EXTI15_10_IRQn
+#define QUARTZ_32MHZ_IN_Pin GPIO_PIN_14
+#define QUARTZ_32MHZ_IN_GPIO_Port GPIOC
+#define QUARTZ_32MHZ_OUT_Pin GPIO_PIN_15
+#define QUARTZ_32MHZ_OUT_GPIO_Port GPIOC
+#define BOOT0_Pin GPIO_PIN_3
+#define BOOT0_GPIO_Port GPIOH
+#define SPEAKER_Pin GPIO_PIN_8
+#define SPEAKER_GPIO_Port GPIOB
+#define IR_TX_Pin GPIO_PIN_9
+#define IR_TX_GPIO_Port GPIOB
+#define PC0_Pin GPIO_PIN_0
+#define PC0_GPIO_Port GPIOC
+#define PC1_Pin GPIO_PIN_1
+#define PC1_GPIO_Port GPIOC
+#define BUTTON_OK_Pin GPIO_PIN_2
+#define BUTTON_OK_GPIO_Port GPIOC
+#define BUTTON_OK_EXTI_IRQn EXTI2_IRQn
+#define PC3_Pin GPIO_PIN_3
+#define PC3_GPIO_Port GPIOC
+#define IR_RX_Pin GPIO_PIN_0
+#define IR_RX_GPIO_Port GPIOA
+#define LED_RED_Pin GPIO_PIN_1
+#define LED_RED_GPIO_Port GPIOA
+#define LED_GREEN_Pin GPIO_PIN_2
+#define LED_GREEN_GPIO_Port GPIOA
+#define LED_BLUE_Pin GPIO_PIN_3
+#define LED_BLUE_GPIO_Port GPIOA
+#define PA4_Pin GPIO_PIN_4
+#define PA4_GPIO_Port GPIOA
+#define PA5_Pin GPIO_PIN_5
+#define PA5_GPIO_Port GPIOA
+#define PA6_Pin GPIO_PIN_6
+#define PA6_GPIO_Port GPIOA
+#define PA7_Pin GPIO_PIN_7
+#define PA7_GPIO_Port GPIOA
+#define RFID_PULL_Pin GPIO_PIN_8
+#define RFID_PULL_GPIO_Port GPIOA
+#define RFID_PULL_EXTI_IRQn EXTI9_5_IRQn
+#define I2C_SCL_Pin GPIO_PIN_9
+#define I2C_SCL_GPIO_Port GPIOA
+#define CC1101_G0_Pin GPIO_PIN_4
+#define CC1101_G0_GPIO_Port GPIOC
+#define RFID_RF_IN_Pin GPIO_PIN_5
+#define RFID_RF_IN_GPIO_Port GPIOC
+#define PB2_Pin GPIO_PIN_2
+#define PB2_GPIO_Port GPIOB
+#define BUTTON_UP_Pin GPIO_PIN_10
+#define BUTTON_UP_GPIO_Port GPIOB
+#define BUTTON_UP_EXTI_IRQn EXTI15_10_IRQn
+#define BUTTON_LEFT_Pin GPIO_PIN_11
+#define BUTTON_LEFT_GPIO_Port GPIOB
+#define BUTTON_LEFT_EXTI_IRQn EXTI15_10_IRQn
+#define DISPLAY_RST_Pin GPIO_PIN_0
+#define DISPLAY_RST_GPIO_Port GPIOB
+#define BUTTON_DOWN_Pin GPIO_PIN_1
+#define BUTTON_DOWN_GPIO_Port GPIOB
+#define BUTTON_DOWN_EXTI_IRQn EXTI1_IRQn
+#define NFC_CS_Pin GPIO_PIN_4
+#define NFC_CS_GPIO_Port GPIOE
+#define BUTTON_RIGHT_Pin GPIO_PIN_12
+#define BUTTON_RIGHT_GPIO_Port GPIOB
+#define BUTTON_RIGHT_EXTI_IRQn EXTI15_10_IRQn
+#define RFID_OUT_Pin GPIO_PIN_13
+#define RFID_OUT_GPIO_Port GPIOB
+#define iBTN_Pin GPIO_PIN_14
+#define iBTN_GPIO_Port GPIOB
+#define SPI_D_MOSI_Pin GPIO_PIN_15
+#define SPI_D_MOSI_GPIO_Port GPIOB
+#define DISPLAY_DI_Pin GPIO_PIN_6
+#define DISPLAY_DI_GPIO_Port GPIOC
+#define I2C_SDA_Pin GPIO_PIN_10
+#define I2C_SDA_GPIO_Port GPIOA
+#define DISPLAY_BACKLIGHT_Pin GPIO_PIN_15
+#define DISPLAY_BACKLIGHT_GPIO_Port GPIOA
+#define PC10_Pin GPIO_PIN_10
+#define PC10_GPIO_Port GPIOC
+#define DISPLAY_CS_Pin GPIO_PIN_11
+#define DISPLAY_CS_GPIO_Port GPIOC
+#define SD_CS_Pin GPIO_PIN_12
+#define SD_CS_GPIO_Port GPIOC
+#define CC1101_CS_Pin GPIO_PIN_0
+#define CC1101_CS_GPIO_Port GPIOD
+#define SPI_D_SCK_Pin GPIO_PIN_1
+#define SPI_D_SCK_GPIO_Port GPIOD
+#define SPI_R_SCK_Pin GPIO_PIN_3
+#define SPI_R_SCK_GPIO_Port GPIOB
+#define SPI_R_MISO_Pin GPIO_PIN_4
+#define SPI_R_MISO_GPIO_Port GPIOB
+#define SPI_R_MOSI_Pin GPIO_PIN_5
+#define SPI_R_MOSI_GPIO_Port GPIOB
+/* USER CODE BEGIN Private defines */
+
+#define MISO_PIN GpioPin{.port = SPI_R_MISO_GPIO_Port, .pin = SPI_R_MISO_Pin}
+
+#define SPI_R hspi1
+#define SPI_D hspi2
+#define SPI_SD_HANDLE SPI_R
+
+extern TIM_HandleTypeDef htim1;
+extern TIM_HandleTypeDef htim2;
+extern TIM_HandleTypeDef htim16;
+
+#define TIM_A htim1
+#define TIM_B htim2
+#define TIM_C htim16
+
+#define SPEAKER_TIM htim16
+#define SPEAKER_CH TIM_CHANNEL_1
+
+#define LFRFID_TIM htim1
+#define LFRFID_CH TIM_CHANNEL_1
+
+#define IRDA_TIM htim1
+#define IRDA_CH TIM_CHANNEL_3
+
+#define NFC_IRQ_Pin RFID_PULL_Pin
+#define NFC_IRQ_GPIO_Port RFID_PULL_GPIO_Port
+
+/* USER CODE END Private defines */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MAIN_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/rf.h b/firmware/targets/f3/Inc/rf.h
new file mode 100644
index 00000000..0ad8d042
--- /dev/null
+++ b/firmware/targets/f3/Inc/rf.h
@@ -0,0 +1,56 @@
+/**
+ ******************************************************************************
+ * File Name : RF.h
+ * Description : This file provides code for the configuration
+ * of the RF instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __rf_H
+#define __rf_H
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_RF_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ rf_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/rtc.h b/firmware/targets/f3/Inc/rtc.h
new file mode 100644
index 00000000..9c1d66eb
--- /dev/null
+++ b/firmware/targets/f3/Inc/rtc.h
@@ -0,0 +1,58 @@
+/**
+ ******************************************************************************
+ * File Name : RTC.h
+ * Description : This file provides code for the configuration
+ * of the RTC instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __rtc_H
+#define __rtc_H
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern RTC_HandleTypeDef hrtc;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_RTC_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ rtc_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/spi.h b/firmware/targets/f3/Inc/spi.h
new file mode 100644
index 00000000..e497d347
--- /dev/null
+++ b/firmware/targets/f3/Inc/spi.h
@@ -0,0 +1,63 @@
+/**
+ ******************************************************************************
+ * File Name : SPI.h
+ * Description : This file provides code for the configuration
+ * of the SPI instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __spi_H
+#define __spi_H
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern SPI_HandleTypeDef hspi1;
+extern SPI_HandleTypeDef hspi2;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_SPI1_Init(void);
+void MX_SPI2_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+void NFC_SPI_Reconfigure();
+void SD_SPI_Reconfigure_Slow();
+void SD_SPI_Reconfigure_Fast();
+void CC1101_SPI_Reconfigure();
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ spi_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/stm32wbxx_hal_conf.h b/firmware/targets/f3/Inc/stm32wbxx_hal_conf.h
new file mode 100644
index 00000000..03ce8e9c
--- /dev/null
+++ b/firmware/targets/f3/Inc/stm32wbxx_hal_conf.h
@@ -0,0 +1,359 @@
+/**
+ ******************************************************************************
+ * @file stm32wbxx_hal_conf.h
+ * @author MCD Application Team
+ * @brief HAL configuration file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32WBxx_HAL_CONF_H
+#define __STM32WBxx_HAL_CONF_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/* ########################## Module Selection ############################## */
+/**
+ * @brief This is the list of modules to be used in the HAL driver
+ */
+#define HAL_MODULE_ENABLED
+#define HAL_ADC_MODULE_ENABLED
+/*#define HAL_CRYP_MODULE_ENABLED */
+#define HAL_COMP_MODULE_ENABLED
+/*#define HAL_CRC_MODULE_ENABLED */
+#define HAL_HSEM_MODULE_ENABLED
+#define HAL_I2C_MODULE_ENABLED
+/*#define HAL_I2S_MODULE_ENABLED */
+/*#define HAL_IPCC_MODULE_ENABLED */
+/*#define HAL_IRDA_MODULE_ENABLED */
+/*#define HAL_IWDG_MODULE_ENABLED */
+/*#define HAL_LCD_MODULE_ENABLED */
+/*#define HAL_LPTIM_MODULE_ENABLED */
+#define HAL_PCD_MODULE_ENABLED
+/*#define HAL_PKA_MODULE_ENABLED */
+/*#define HAL_QSPI_MODULE_ENABLED */
+/*#define HAL_RNG_MODULE_ENABLED */
+#define HAL_RTC_MODULE_ENABLED
+/*#define HAL_SAI_MODULE_ENABLED */
+/*#define HAL_SMBUS_MODULE_ENABLED */
+/*#define HAL_SMARTCARD_MODULE_ENABLED */
+#define HAL_SPI_MODULE_ENABLED
+#define HAL_TIM_MODULE_ENABLED
+/*#define HAL_TSC_MODULE_ENABLED */
+#define HAL_UART_MODULE_ENABLED
+/*#define HAL_USART_MODULE_ENABLED */
+/*#define HAL_WWDG_MODULE_ENABLED */
+#define HAL_EXTI_MODULE_ENABLED
+#define HAL_CORTEX_MODULE_ENABLED
+#define HAL_DMA_MODULE_ENABLED
+#define HAL_FLASH_MODULE_ENABLED
+#define HAL_GPIO_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
+#define HAL_RCC_MODULE_ENABLED
+
+#define USE_HAL_ADC_REGISTER_CALLBACKS 0u
+#define USE_HAL_COMP_REGISTER_CALLBACKS 0u
+#define USE_HAL_CRYP_REGISTER_CALLBACKS 0u
+#define USE_HAL_I2C_REGISTER_CALLBACKS 0u
+#define USE_HAL_I2S_REGISTER_CALLBACKS 0u
+#define USE_HAL_IRDA_REGISTER_CALLBACKS 0u
+#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0u
+#define USE_HAL_PCD_REGISTER_CALLBACKS 0u
+#define USE_HAL_PKA_REGISTER_CALLBACKS 0u
+#define USE_HAL_QSPI_REGISTER_CALLBACKS 0u
+#define USE_HAL_RNG_REGISTER_CALLBACKS 0u
+#define USE_HAL_RTC_REGISTER_CALLBACKS 0u
+#define USE_HAL_SAI_REGISTER_CALLBACKS 0u
+#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0u
+#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0u
+#define USE_HAL_SPI_REGISTER_CALLBACKS 0u
+#define USE_HAL_TIM_REGISTER_CALLBACKS 0u
+#define USE_HAL_TSC_REGISTER_CALLBACKS 0u
+#define USE_HAL_UART_REGISTER_CALLBACKS 0u
+#define USE_HAL_USART_REGISTER_CALLBACKS 0u
+#define USE_HAL_WWDG_REGISTER_CALLBACKS 0u
+
+/* ########################## Oscillator Values adaptation ####################*/
+/**
+ * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSE is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSE_VALUE)
+#define HSE_VALUE 32000000U /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#if !defined (HSE_STARTUP_TIMEOUT)
+ #define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
+#endif /* HSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief Internal Multiple Speed oscillator (MSI) default value.
+ * This value is the default MSI range value after Reset.
+ */
+#if !defined (MSI_VALUE)
+ #define MSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/
+#endif /* MSI_VALUE */
+
+/**
+ * @brief Internal High Speed oscillator (HSI) value.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSI is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSI_VALUE)
+#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+/**
+ * @brief Internal Low Speed oscillator (LSI1) value.
+ */
+#if !defined (LSI1_VALUE)
+ #define LSI1_VALUE ((uint32_t)32000) /*!< LSI1 Typical Value in Hz*/
+#endif /* LSI1_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
+ The real value may vary depending on the variations
+ in voltage and temperature.*/
+/**
+ * @brief Internal Low Speed oscillator (LSI2) value.
+ */
+#if !defined (LSI2_VALUE)
+ #define LSI2_VALUE ((uint32_t)32000) /*!< LSI2 Typical Value in Hz*/
+#endif /* LSI2_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
+ The real value may vary depending on the variations
+ in voltage and temperature.*/
+
+/**
+ * @brief External Low Speed oscillator (LSE) value.
+ * This value is used by the UART, RTC HAL module to compute the system frequency
+ */
+#if !defined (LSE_VALUE)
+#define LSE_VALUE 32768U /*!< Value of the External oscillator in Hz*/
+#endif /* LSE_VALUE */
+
+/**
+ * @brief Internal Multiple Speed oscillator (HSI48) default value.
+ * This value is the default HSI48 range value after Reset.
+ */
+#if !defined (HSI48_VALUE)
+ #define HSI48_VALUE ((uint32_t)48000000) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI48_VALUE */
+
+#if !defined (LSE_STARTUP_TIMEOUT)
+#define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */
+#endif /* HSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief External clock source for SAI1 peripheral
+ * This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source
+ * frequency.
+ */
+#if !defined (EXTERNAL_SAI1_CLOCK_VALUE)
+ #define EXTERNAL_SAI1_CLOCK_VALUE ((uint32_t)2097000) /*!< Value of the SAI1 External clock source in Hz*/
+#endif /* EXTERNAL_SAI1_CLOCK_VALUE */
+
+/* Tip: To avoid modifying this file each time you need to use different HSE,
+ === you can define the HSE value in your toolchain compiler preprocessor. */
+
+/* ########################### System Configuration ######################### */
+/**
+ * @brief This is the HAL system configuration section
+ */
+
+#define VDD_VALUE 3300U /*!< Value of VDD in mv */
+#define TICK_INT_PRIORITY 0U /*!< tick interrupt priority */
+#define USE_RTOS 0U
+#define PREFETCH_ENABLE 1U
+#define INSTRUCTION_CACHE_ENABLE 1U
+#define DATA_CACHE_ENABLE 1U
+
+/* ########################## Assert Selection ############################## */
+/**
+ * @brief Uncomment the line below to expanse the "assert_param" macro in the
+ * HAL drivers code
+ */
+/* #define USE_FULL_ASSERT 1U */
+
+/* ################## SPI peripheral configuration ########################## */
+
+/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
+ * Activated: CRC code is present inside driver
+ * Deactivated: CRC code cleaned from driver
+ */
+
+#define USE_SPI_CRC 0U
+
+/* Includes ------------------------------------------------------------------*/
+/**
+ * @brief Include module's header file
+ */
+#ifdef HAL_DMA_MODULE_ENABLED
+ #include "stm32wbxx_hal_dma.h"
+#endif /* HAL_DMA_MODULE_ENABLED */
+
+#ifdef HAL_ADC_MODULE_ENABLED
+ #include "stm32wbxx_hal_adc.h"
+#endif /* HAL_ADC_MODULE_ENABLED */
+
+#ifdef HAL_COMP_MODULE_ENABLED
+ #include "stm32wbxx_hal_comp.h"
+#endif /* HAL_COMP_MODULE_ENABLED */
+
+#ifdef HAL_CORTEX_MODULE_ENABLED
+ #include "stm32wbxx_hal_cortex.h"
+#endif /* HAL_CORTEX_MODULE_ENABLED */
+
+#ifdef HAL_CRC_MODULE_ENABLED
+ #include "stm32wbxx_hal_crc.h"
+#endif /* HAL_CRC_MODULE_ENABLED */
+
+#ifdef HAL_CRYP_MODULE_ENABLED
+ #include "stm32wbxx_hal_cryp.h"
+#endif /* HAL_CRYP_MODULE_ENABLED */
+
+#ifdef HAL_EXTI_MODULE_ENABLED
+ #include "stm32wbxx_hal_exti.h"
+#endif /* HAL_EXTI_MODULE_ENABLED */
+
+#ifdef HAL_FLASH_MODULE_ENABLED
+ #include "stm32wbxx_hal_flash.h"
+#endif /* HAL_FLASH_MODULE_ENABLED */
+
+#ifdef HAL_GPIO_MODULE_ENABLED
+ #include "stm32wbxx_hal_gpio.h"
+#endif /* HAL_GPIO_MODULE_ENABLED */
+
+#ifdef HAL_HSEM_MODULE_ENABLED
+ #include "stm32wbxx_hal_hsem.h"
+#endif /* HAL_HSEM_MODULE_ENABLED */
+
+#ifdef HAL_I2C_MODULE_ENABLED
+ #include "stm32wbxx_hal_i2c.h"
+#endif /* HAL_I2C_MODULE_ENABLED */
+
+#ifdef HAL_I2S_MODULE_ENABLED
+ #include "stm32wbxx_hal_i2s.h"
+#endif /* HAL_I2S_MODULE_ENABLED */
+
+#ifdef HAL_IPCC_MODULE_ENABLED
+ #include "stm32wbxx_hal_ipcc.h"
+#endif /* HAL_IPCC_MODULE_ENABLED */
+
+#ifdef HAL_IRDA_MODULE_ENABLED
+ #include "stm32wbxx_hal_irda.h"
+#endif /* HAL_IRDA_MODULE_ENABLED */
+
+#ifdef HAL_IWDG_MODULE_ENABLED
+ #include "stm32wbxx_hal_iwdg.h"
+#endif /* HAL_IWDG_MODULE_ENABLED */
+
+#ifdef HAL_LCD_MODULE_ENABLED
+ #include "stm32wbxx_hal_lcd.h"
+#endif /* HAL_LCD_MODULE_ENABLED */
+
+#ifdef HAL_LPTIM_MODULE_ENABLED
+ #include "stm32wbxx_hal_lptim.h"
+#endif /* HAL_LPTIM_MODULE_ENABLED */
+
+#ifdef HAL_PCD_MODULE_ENABLED
+ #include "stm32wbxx_hal_pcd.h"
+#endif /* HAL_PCD_MODULE_ENABLED */
+
+#ifdef HAL_PKA_MODULE_ENABLED
+ #include "stm32wbxx_hal_pka.h"
+#endif /* HAL_PKA_MODULE_ENABLED */
+
+#ifdef HAL_PWR_MODULE_ENABLED
+ #include "stm32wbxx_hal_pwr.h"
+#endif /* HAL_PWR_MODULE_ENABLED */
+
+#ifdef HAL_QSPI_MODULE_ENABLED
+ #include "stm32wbxx_hal_qspi.h"
+#endif /* HAL_QSPI_MODULE_ENABLED */
+
+#ifdef HAL_RCC_MODULE_ENABLED
+ #include "stm32wbxx_hal_rcc.h"
+#endif /* HAL_RCC_MODULE_ENABLED */
+
+#ifdef HAL_RNG_MODULE_ENABLED
+ #include "stm32wbxx_hal_rng.h"
+#endif /* HAL_RNG_MODULE_ENABLED */
+
+#ifdef HAL_RTC_MODULE_ENABLED
+ #include "stm32wbxx_hal_rtc.h"
+#endif /* HAL_RTC_MODULE_ENABLED */
+
+#ifdef HAL_SAI_MODULE_ENABLED
+ #include "stm32wbxx_hal_sai.h"
+#endif /* HAL_SAI_MODULE_ENABLED */
+
+#ifdef HAL_SMARTCARD_MODULE_ENABLED
+ #include "stm32wbxx_hal_smartcard.h"
+#endif /* HAL_SMARTCARD_MODULE_ENABLED */
+
+#ifdef HAL_SMBUS_MODULE_ENABLED
+ #include "stm32wbxx_hal_smbus.h"
+#endif /* HAL_SMBUS_MODULE_ENABLED */
+
+#ifdef HAL_SPI_MODULE_ENABLED
+ #include "stm32wbxx_hal_spi.h"
+#endif /* HAL_SPI_MODULE_ENABLED */
+
+#ifdef HAL_TIM_MODULE_ENABLED
+ #include "stm32wbxx_hal_tim.h"
+#endif /* HAL_TIM_MODULE_ENABLED */
+
+#ifdef HAL_TSC_MODULE_ENABLED
+ #include "stm32wbxx_hal_tsc.h"
+#endif /* HAL_TSC_MODULE_ENABLED */
+
+#ifdef HAL_UART_MODULE_ENABLED
+ #include "stm32wbxx_hal_uart.h"
+#endif /* HAL_UART_MODULE_ENABLED */
+
+#ifdef HAL_USART_MODULE_ENABLED
+ #include "stm32wbxx_hal_usart.h"
+#endif /* HAL_USART_MODULE_ENABLED */
+
+#ifdef HAL_WWDG_MODULE_ENABLED
+ #include "stm32wbxx_hal_wwdg.h"
+#endif /* HAL_WWDG_MODULE_ENABLED */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief The assert_param macro is used for function's parameters check.
+ * @param expr If expr is false, it calls assert_failed function
+ * which reports the name of the source file and the source
+ * line number of the call that failed.
+ * If expr is true, it returns no value.
+ * @retval None
+ */
+ #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(uint8_t* file, uint32_t line);
+#else
+ #define assert_param(expr) ((void)0U)
+#endif /* USE_FULL_ASSERT */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32WBxx_HAL_CONF_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/stm32wbxx_it.h b/firmware/targets/f3/Inc/stm32wbxx_it.h
new file mode 100644
index 00000000..f646f87c
--- /dev/null
+++ b/firmware/targets/f3/Inc/stm32wbxx_it.h
@@ -0,0 +1,74 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32wbxx_it.h
+ * @brief This file contains the headers of the interrupt handlers.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32WBxx_IT_H
+#define __STM32WBxx_IT_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Exported types ------------------------------------------------------------*/
+/* USER CODE BEGIN ET */
+
+/* USER CODE END ET */
+
+/* Exported constants --------------------------------------------------------*/
+/* USER CODE BEGIN EC */
+
+/* USER CODE END EC */
+
+/* Exported macro ------------------------------------------------------------*/
+/* USER CODE BEGIN EM */
+
+/* USER CODE END EM */
+
+/* Exported functions prototypes ---------------------------------------------*/
+void NMI_Handler(void);
+void HardFault_Handler(void);
+void MemManage_Handler(void);
+void BusFault_Handler(void);
+void UsageFault_Handler(void);
+void DebugMon_Handler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void USB_LP_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_TRG_COM_TIM17_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void HSEM_IRQHandler(void);
+/* USER CODE BEGIN EFP */
+
+/* USER CODE END EFP */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32WBxx_IT_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/tim.h b/firmware/targets/f3/Inc/tim.h
new file mode 100644
index 00000000..b6e88184
--- /dev/null
+++ b/firmware/targets/f3/Inc/tim.h
@@ -0,0 +1,64 @@
+/**
+ ******************************************************************************
+ * File Name : TIM.h
+ * Description : This file provides code for the configuration
+ * of the TIM instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __tim_H
+#define __tim_H
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern TIM_HandleTypeDef htim1;
+extern TIM_HandleTypeDef htim2;
+extern TIM_HandleTypeDef htim16;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_TIM1_Init(void);
+void MX_TIM2_Init(void);
+void MX_TIM16_Init(void);
+
+void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ tim_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/usart.h b/firmware/targets/f3/Inc/usart.h
new file mode 100644
index 00000000..e87a9998
--- /dev/null
+++ b/firmware/targets/f3/Inc/usart.h
@@ -0,0 +1,58 @@
+/**
+ ******************************************************************************
+ * File Name : USART.h
+ * Description : This file provides code for the configuration
+ * of the USART instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __usart_H
+#define __usart_H
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern UART_HandleTypeDef huart1;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_USART1_UART_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ usart_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/usb_device.h b/firmware/targets/f3/Inc/usb_device.h
new file mode 100644
index 00000000..5d7a3f9c
--- /dev/null
+++ b/firmware/targets/f3/Inc/usb_device.h
@@ -0,0 +1,105 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : usb_device.h
+ * @version : v3.0_Cube
+ * @brief : Header for usb_device.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_DEVICE__H__
+#define __USB_DEVICE__H__
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32wbxx.h"
+#include "stm32wbxx_hal.h"
+#include "usbd_def.h"
+
+/* USER CODE BEGIN INCLUDE */
+
+/* USER CODE END INCLUDE */
+
+/** @addtogroup USBD_OTG_DRIVER
+ * @{
+ */
+
+/** @defgroup USBD_DEVICE USBD_DEVICE
+ * @brief Device file for Usb otg low level driver.
+ * @{
+ */
+
+/** @defgroup USBD_DEVICE_Exported_Variables USBD_DEVICE_Exported_Variables
+ * @brief Public variables.
+ * @{
+ */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/*
+ * -- Insert your variables declaration here --
+ */
+/* USER CODE BEGIN VARIABLES */
+
+/* USER CODE END VARIABLES */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DEVICE_Exported_FunctionsPrototype USBD_DEVICE_Exported_FunctionsPrototype
+ * @brief Declaration of public functions for Usb device.
+ * @{
+ */
+
+/** USB Device initialization function. */
+void MX_USB_Device_Init(void);
+
+/*
+ * -- Insert functions declaration here --
+ */
+/* USER CODE BEGIN FD */
+
+/* USER CODE END FD */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USB_DEVICE__H__ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/usbd_cdc_if.h b/firmware/targets/f3/Inc/usbd_cdc_if.h
new file mode 100644
index 00000000..1bd4eb8e
--- /dev/null
+++ b/firmware/targets/f3/Inc/usbd_cdc_if.h
@@ -0,0 +1,134 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : usbd_cdc_if.h
+ * @version : v3.0_Cube
+ * @brief : Header for usbd_cdc_if.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CDC_IF_H__
+#define __USBD_CDC_IF_H__
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_cdc.h"
+
+/* USER CODE BEGIN INCLUDE */
+
+/* USER CODE END INCLUDE */
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+ * @brief For Usb device.
+ * @{
+ */
+
+/** @defgroup USBD_CDC_IF USBD_CDC_IF
+ * @brief Usb VCP device module
+ * @{
+ */
+
+/** @defgroup USBD_CDC_IF_Exported_Defines USBD_CDC_IF_Exported_Defines
+ * @brief Defines.
+ * @{
+ */
+/* USER CODE BEGIN EXPORTED_DEFINES */
+/* Define size for the receive and transmit buffer over CDC */
+/* It's up to user to redefine and/or remove those define */
+#define APP_RX_DATA_SIZE 2048
+#define APP_TX_DATA_SIZE 2048
+
+/* USER CODE END EXPORTED_DEFINES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_IF_Exported_Types USBD_CDC_IF_Exported_Types
+ * @brief Types.
+ * @{
+ */
+
+/* USER CODE BEGIN EXPORTED_TYPES */
+
+/* USER CODE END EXPORTED_TYPES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_IF_Exported_Macros USBD_CDC_IF_Exported_Macros
+ * @brief Aliases.
+ * @{
+ */
+
+/* USER CODE BEGIN EXPORTED_MACRO */
+
+/* USER CODE END EXPORTED_MACRO */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_IF_Exported_Variables USBD_CDC_IF_Exported_Variables
+ * @brief Public variables.
+ * @{
+ */
+
+/** CDC Interface callback. */
+extern USBD_CDC_ItfTypeDef USBD_Interface_fops_FS;
+
+/* USER CODE BEGIN EXPORTED_VARIABLES */
+
+/* USER CODE END EXPORTED_VARIABLES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_IF_Exported_FunctionsPrototype USBD_CDC_IF_Exported_FunctionsPrototype
+ * @brief Public functions declaration.
+ * @{
+ */
+
+uint8_t CDC_Transmit_FS(uint8_t* Buf, uint16_t Len);
+
+/* USER CODE BEGIN EXPORTED_FUNCTIONS */
+
+/* USER CODE END EXPORTED_FUNCTIONS */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_CDC_IF_H__ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/usbd_conf.h b/firmware/targets/f3/Inc/usbd_conf.h
new file mode 100644
index 00000000..49b801ef
--- /dev/null
+++ b/firmware/targets/f3/Inc/usbd_conf.h
@@ -0,0 +1,176 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : usbd_conf.h
+ * @version : v3.0_Cube
+ * @brief : Header for usbd_conf.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CONF__H__
+#define __USBD_CONF__H__
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include
+#include
+#include
+#include "stm32wbxx.h"
+#include "stm32wbxx_hal.h"
+
+/* USER CODE BEGIN INCLUDE */
+
+/* USER CODE END INCLUDE */
+
+/** @addtogroup USBD_OTG_DRIVER
+ * @brief Driver for Usb device.
+ * @{
+ */
+
+/** @defgroup USBD_CONF USBD_CONF
+ * @brief Configuration file for Usb otg low level driver.
+ * @{
+ */
+
+/** @defgroup USBD_CONF_Exported_Variables USBD_CONF_Exported_Variables
+ * @brief Public variables.
+ * @{
+ */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+/* USER CODE END PV */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CONF_Exported_Defines USBD_CONF_Exported_Defines
+ * @brief Defines for configuration of the Usb device.
+ * @{
+ */
+
+/*---------- -----------*/
+#define USBD_MAX_NUM_INTERFACES 1U
+/*---------- -----------*/
+#define USBD_MAX_NUM_CONFIGURATION 1U
+/*---------- -----------*/
+#define USBD_MAX_STR_DESC_SIZ 512U
+/*---------- -----------*/
+#define USBD_DEBUG_LEVEL 0U
+/*---------- -----------*/
+#define USBD_LPM_ENABLED 1U
+/*---------- -----------*/
+#define USBD_SELF_POWERED 1U
+
+/****************************************/
+/* #define for FS and HS identification */
+#define DEVICE_FS 0
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CONF_Exported_Macros USBD_CONF_Exported_Macros
+ * @brief Aliases.
+ * @{
+ */
+
+/* Memory management macros */
+
+/** Alias for memory allocation. */
+#define USBD_malloc (void *)USBD_static_malloc
+
+/** Alias for memory release. */
+#define USBD_free USBD_static_free
+
+/** Alias for memory set. */
+#define USBD_memset memset
+
+/** Alias for memory copy. */
+#define USBD_memcpy memcpy
+
+/** Alias for delay. */
+#define USBD_Delay HAL_Delay
+/* DEBUG macros */
+
+#if (USBD_DEBUG_LEVEL > 0)
+#define USBD_UsrLog(...) printf(__VA_ARGS__);\
+ printf("\n");
+#else
+#define USBD_UsrLog(...)
+#endif
+
+#if (USBD_DEBUG_LEVEL > 1)
+
+#define USBD_ErrLog(...) printf("ERROR: ") ;\
+ printf(__VA_ARGS__);\
+ printf("\n");
+#else
+#define USBD_ErrLog(...)
+#endif
+
+#if (USBD_DEBUG_LEVEL > 2)
+#define USBD_DbgLog(...) printf("DEBUG : ") ;\
+ printf(__VA_ARGS__);\
+ printf("\n");
+#else
+#define USBD_DbgLog(...)
+#endif
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CONF_Exported_Types USBD_CONF_Exported_Types
+ * @brief Types.
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CONF_Exported_FunctionsPrototype USBD_CONF_Exported_FunctionsPrototype
+ * @brief Declaration of public functions for Usb device.
+ * @{
+ */
+
+/* Exported functions -------------------------------------------------------*/
+void *USBD_static_malloc(uint32_t size);
+void USBD_static_free(void *p);
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_CONF__H__ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Inc/usbd_desc.h b/firmware/targets/f3/Inc/usbd_desc.h
new file mode 100644
index 00000000..2a5bea5c
--- /dev/null
+++ b/firmware/targets/f3/Inc/usbd_desc.h
@@ -0,0 +1,145 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : usbd_desc.c
+ * @version : v3.0_Cube
+ * @brief : Header for usbd_conf.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_DESC__C__
+#define __USBD_DESC__C__
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_def.h"
+
+/* USER CODE BEGIN INCLUDE */
+
+/* USER CODE END INCLUDE */
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_DESC USBD_DESC
+ * @brief Usb device descriptors module.
+ * @{
+ */
+
+/** @defgroup USBD_DESC_Exported_Constants USBD_DESC_Exported_Constants
+ * @brief Constants.
+ * @{
+ */
+#define DEVICE_ID1 (UID_BASE)
+#define DEVICE_ID2 (UID_BASE + 0x4)
+#define DEVICE_ID3 (UID_BASE + 0x8)
+
+#define USB_SIZ_STRING_SERIAL 0x1A
+
+/* USER CODE BEGIN EXPORTED_CONSTANTS */
+
+/* USER CODE END EXPORTED_CONSTANTS */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Exported_Defines USBD_DESC_Exported_Defines
+ * @brief Defines.
+ * @{
+ */
+
+/* USER CODE BEGIN EXPORTED_DEFINES */
+
+/* USER CODE END EXPORTED_DEFINES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Exported_TypesDefinitions USBD_DESC_Exported_TypesDefinitions
+ * @brief Types.
+ * @{
+ */
+
+/* USER CODE BEGIN EXPORTED_TYPES */
+
+/* USER CODE END EXPORTED_TYPES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Exported_Macros USBD_DESC_Exported_Macros
+ * @brief Aliases.
+ * @{
+ */
+
+/* USER CODE BEGIN EXPORTED_MACRO */
+
+/* USER CODE END EXPORTED_MACRO */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Exported_Variables USBD_DESC_Exported_Variables
+ * @brief Public variables.
+ * @{
+ */
+
+extern USBD_DescriptorsTypeDef CDC_Desc;
+
+/* USER CODE BEGIN EXPORTED_VARIABLES */
+
+/* USER CODE END EXPORTED_VARIABLES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Exported_FunctionsPrototype USBD_DESC_Exported_FunctionsPrototype
+ * @brief Public functions declaration.
+ * @{
+ */
+
+/* USER CODE BEGIN EXPORTED_FUNCTIONS */
+
+/* USER CODE END EXPORTED_FUNCTIONS */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_DESC__C__ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Makefile b/firmware/targets/f3/Makefile
new file mode 100644
index 00000000..8d28cb58
--- /dev/null
+++ b/firmware/targets/f3/Makefile
@@ -0,0 +1,398 @@
+##########################################################################################################################
+# File automatically-generated by tool: [projectgenerator] version: [3.10.0-B14] date: [Thu Nov 05 17:53:24 MSK 2020]
+##########################################################################################################################
+
+# ------------------------------------------------
+# Generic Makefile (based on gcc)
+#
+# ChangeLog :
+# 2017-02-10 - Several enhancements + project update mode
+# 2015-07-22 - first version
+# ------------------------------------------------
+
+######################################
+# target
+######################################
+TARGET = f3
+
+
+######################################
+# building variables
+######################################
+# debug build?
+DEBUG = 1
+# optimization
+OPT = -Og
+
+
+#######################################
+# paths
+#######################################
+# Build path
+BUILD_DIR = build
+
+######################################
+# source
+######################################
+# C sources
+C_SOURCES = \
+Src/main.c \
+Src/gpio.c \
+Src/app_freertos.c \
+Src/adc.c \
+Src/i2c.c \
+Src/rtc.c \
+Src/spi.c \
+Src/tim.c \
+Src/usart.c \
+Src/usb_device.c \
+Src/usbd_conf.c \
+Src/usbd_desc.c \
+Src/usbd_cdc_if.c \
+Src/stm32wbxx_it.c \
+Src/stm32wbxx_hal_msp.c \
+Src/stm32wbxx_hal_timebase_tim.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_gpio.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd_ex.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_usb.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rcc.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rcc_ex.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash_ex.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_hsem.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_dma.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_dma_ex.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr_ex.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_cortex.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_exti.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc_ex.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_adc.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_i2c.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_i2c_ex.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc_ex.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi_ex.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim_ex.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_uart.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_uart_ex.c \
+Src/system_stm32wbxx.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/croutine.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/event_groups.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/list.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/queue.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/stream_buffer.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/tasks.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/timers.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/portable/MemMang/heap_4.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c \
+/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_gpio.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd_ex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_usb.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rcc.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rcc_ex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash_ex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_hsem.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_dma.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_dma_ex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr_ex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_cortex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_exti.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc_ex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_adc.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_i2c.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_i2c_ex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc_ex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi_ex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim_ex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_uart.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_uart_ex.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/croutine.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/event_groups.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/list.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/queue.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/stream_buffer.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/tasks.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/timers.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/portable/MemMang/heap_4.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c \
+C:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_gpio.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd_ex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_usb.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rcc.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rcc_ex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash_ex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_hsem.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_dma.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_dma_ex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr_ex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_cortex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_exti.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc_ex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_adc.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_i2c.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_i2c_ex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc_ex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi_ex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim_ex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_uart.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_uart_ex.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/croutine.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/event_groups.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/list.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/queue.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/stream_buffer.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/tasks.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/timers.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/portable/MemMang/heap_4.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c \
+Src/comp.c \
+/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_comp.c \
+Src/rf.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_gpio.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd_ex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_usb.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rcc.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rcc_ex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash_ex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_hsem.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_dma.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_dma_ex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr_ex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_cortex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_exti.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc_ex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_adc.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_comp.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_i2c.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_i2c_ex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc_ex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi_ex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim_ex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_uart.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_uart_ex.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/croutine.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/event_groups.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/list.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/queue.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/stream_buffer.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/tasks.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/timers.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/portable/MemMang/heap_4.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c \
+C:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c
+
+# ASM sources
+ASM_SOURCES = \
+startup_stm32wb55xx_cm4.s
+
+
+#######################################
+# binaries
+#######################################
+PREFIX = arm-none-eabi-
+# The gcc compiler bin path can be either defined in make command via GCC_PATH variable (> make GCC_PATH=xxx)
+# either it can be added to the PATH environment variable.
+ifdef GCC_PATH
+CC = $(GCC_PATH)/$(PREFIX)gcc
+AS = $(GCC_PATH)/$(PREFIX)gcc -x assembler-with-cpp
+CP = $(GCC_PATH)/$(PREFIX)objcopy
+SZ = $(GCC_PATH)/$(PREFIX)size
+else
+CC = $(PREFIX)gcc
+AS = $(PREFIX)gcc -x assembler-with-cpp
+CP = $(PREFIX)objcopy
+SZ = $(PREFIX)size
+endif
+HEX = $(CP) -O ihex
+BIN = $(CP) -O binary -S
+
+#######################################
+# CFLAGS
+#######################################
+# cpu
+CPU = -mcpu=cortex-m4
+
+# fpu
+FPU = -mfpu=fpv4-sp-d16
+
+# float-abi
+FLOAT-ABI = -mfloat-abi=hard
+
+# mcu
+MCU = $(CPU) -mthumb $(FPU) $(FLOAT-ABI)
+
+# macros for gcc
+# AS defines
+AS_DEFS =
+
+# C defines
+C_DEFS = \
+-DUSE_HAL_DRIVER \
+-DSTM32WB55xx
+
+
+# AS includes
+AS_INCLUDES = \
+-IInc
+
+# C includes
+C_INCLUDES = \
+-IInc \
+-I/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Inc \
+-I/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Inc/Legacy \
+-I/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/include \
+-I/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2 \
+-I/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F \
+-I/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Core/Inc \
+-I/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc \
+-I/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/CMSIS/Device/ST/STM32WBxx/Include \
+-I/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/CMSIS/Include \
+-I/Users/aku/Work/flipper/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/CMSIS/Include \
+-IC:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Inc \
+-IC:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/STM32WBxx_HAL_Driver/Inc/Legacy \
+-IC:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/include \
+-IC:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2 \
+-IC:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F \
+-IC:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Core/Inc \
+-IC:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc \
+-IC:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/CMSIS/Device/ST/STM32WBxx/Include \
+-IC:/work/cmake-stm32/projects/flipperzero-firmware-community/lib/STM32CubeWB/Drivers/CMSIS/Include \
+-I/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Inc \
+-I/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Inc/Legacy \
+-I/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/include \
+-I/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2 \
+-I/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F \
+-I/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Core/Inc \
+-I/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc \
+-I/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/CMSIS/Device/ST/STM32WBxx/Include \
+-I/Users/aku/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/CMSIS/Include \
+-IC:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Inc \
+-IC:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/STM32WBxx_HAL_Driver/Inc/Legacy \
+-IC:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/include \
+-IC:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2 \
+-IC:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F \
+-IC:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Core/Inc \
+-IC:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc \
+-IC:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/CMSIS/Device/ST/STM32WBxx/Include \
+-IC:/Users/whoju/STM32Cube/Repository/STM32Cube_FW_WB_V1.9.0/Drivers/CMSIS/Include
+
+
+# compile gcc flags
+ASFLAGS = $(MCU) $(AS_DEFS) $(AS_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
+
+CFLAGS = $(MCU) $(C_DEFS) $(C_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
+
+ifeq ($(DEBUG), 1)
+CFLAGS += -g -gdwarf-2
+endif
+
+
+# Generate dependency information
+CFLAGS += -MMD -MP -MF"$(@:%.o=%.d)"
+
+
+#######################################
+# LDFLAGS
+#######################################
+# link script
+LDSCRIPT = stm32wb55xx_flash_cm4.ld
+
+# libraries
+LIBS = -lc -lm -lnosys
+LIBDIR =
+LDFLAGS = $(MCU) -specs=nano.specs -T$(LDSCRIPT) $(LIBDIR) $(LIBS) -Wl,-Map=$(BUILD_DIR)/$(TARGET).map,--cref -Wl,--gc-sections
+
+# default action: build all
+all: $(BUILD_DIR)/$(TARGET).elf $(BUILD_DIR)/$(TARGET).hex $(BUILD_DIR)/$(TARGET).bin
+
+
+#######################################
+# build the application
+#######################################
+# list of objects
+OBJECTS = $(addprefix $(BUILD_DIR)/,$(notdir $(C_SOURCES:.c=.o)))
+vpath %.c $(sort $(dir $(C_SOURCES)))
+# list of ASM program objects
+OBJECTS += $(addprefix $(BUILD_DIR)/,$(notdir $(ASM_SOURCES:.s=.o)))
+vpath %.s $(sort $(dir $(ASM_SOURCES)))
+
+$(BUILD_DIR)/%.o: %.c Makefile | $(BUILD_DIR)
+ $(CC) -c $(CFLAGS) -Wa,-a,-ad,-alms=$(BUILD_DIR)/$(notdir $(<:.c=.lst)) $< -o $@
+
+$(BUILD_DIR)/%.o: %.s Makefile | $(BUILD_DIR)
+ $(AS) -c $(CFLAGS) $< -o $@
+
+$(BUILD_DIR)/$(TARGET).elf: $(OBJECTS) Makefile
+ $(CC) $(OBJECTS) $(LDFLAGS) -o $@
+ $(SZ) $@
+
+$(BUILD_DIR)/%.hex: $(BUILD_DIR)/%.elf | $(BUILD_DIR)
+ $(HEX) $< $@
+
+$(BUILD_DIR)/%.bin: $(BUILD_DIR)/%.elf | $(BUILD_DIR)
+ $(BIN) $< $@
+
+$(BUILD_DIR):
+ mkdir $@
+
+#######################################
+# clean up
+#######################################
+clean:
+ -rm -fR $(BUILD_DIR)
+
+#######################################
+# dependencies
+#######################################
+-include $(wildcard $(BUILD_DIR)/*.d)
+
+# *** EOF ***
diff --git a/firmware/targets/f3/Src/adc.c b/firmware/targets/f3/Src/adc.c
new file mode 100644
index 00000000..048e2462
--- /dev/null
+++ b/firmware/targets/f3/Src/adc.c
@@ -0,0 +1,106 @@
+/**
+ ******************************************************************************
+ * File Name : ADC.c
+ * Description : This file provides code for the configuration
+ * of the ADC instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "adc.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+ADC_HandleTypeDef hadc1;
+
+/* ADC1 init function */
+void MX_ADC1_Init(void)
+{
+ ADC_ChannelConfTypeDef sConfig = {0};
+
+ /** Common config
+ */
+ hadc1.Instance = ADC1;
+ hadc1.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1;
+ hadc1.Init.Resolution = ADC_RESOLUTION_12B;
+ hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
+ hadc1.Init.ScanConvMode = ADC_SCAN_DISABLE;
+ hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
+ hadc1.Init.LowPowerAutoWait = DISABLE;
+ hadc1.Init.ContinuousConvMode = DISABLE;
+ hadc1.Init.NbrOfConversion = 1;
+ hadc1.Init.DiscontinuousConvMode = DISABLE;
+ hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START;
+ hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
+ hadc1.Init.DMAContinuousRequests = DISABLE;
+ hadc1.Init.Overrun = ADC_OVR_DATA_PRESERVED;
+ hadc1.Init.OversamplingMode = DISABLE;
+ if (HAL_ADC_Init(&hadc1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /** Configure Regular Channel
+ */
+ sConfig.Channel = ADC_CHANNEL_TEMPSENSOR;
+ sConfig.Rank = ADC_REGULAR_RANK_1;
+ sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5;
+ sConfig.SingleDiff = ADC_SINGLE_ENDED;
+ sConfig.OffsetNumber = ADC_OFFSET_NONE;
+ sConfig.Offset = 0;
+ if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+
+void HAL_ADC_MspInit(ADC_HandleTypeDef* adcHandle)
+{
+
+ if(adcHandle->Instance==ADC1)
+ {
+ /* USER CODE BEGIN ADC1_MspInit 0 */
+
+ /* USER CODE END ADC1_MspInit 0 */
+ /* ADC1 clock enable */
+ __HAL_RCC_ADC_CLK_ENABLE();
+ /* USER CODE BEGIN ADC1_MspInit 1 */
+
+ /* USER CODE END ADC1_MspInit 1 */
+ }
+}
+
+void HAL_ADC_MspDeInit(ADC_HandleTypeDef* adcHandle)
+{
+
+ if(adcHandle->Instance==ADC1)
+ {
+ /* USER CODE BEGIN ADC1_MspDeInit 0 */
+
+ /* USER CODE END ADC1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_ADC_CLK_DISABLE();
+ /* USER CODE BEGIN ADC1_MspDeInit 1 */
+
+ /* USER CODE END ADC1_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/app_freertos.c b/firmware/targets/f3/Src/app_freertos.c
new file mode 100644
index 00000000..01623a9f
--- /dev/null
+++ b/firmware/targets/f3/Src/app_freertos.c
@@ -0,0 +1,181 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * File Name : app_freertos.c
+ * Description : Code for freertos applications
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "FreeRTOS.h"
+#include "task.h"
+#include "main.h"
+#include "cmsis_os.h"
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN PTD */
+
+/* USER CODE END PTD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN PD */
+
+/* USER CODE END PD */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN PM */
+
+/* USER CODE END PM */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN Variables */
+
+/* USER CODE END Variables */
+/* Definitions for defaultTask */
+osThreadId_t defaultTaskHandle;
+const osThreadAttr_t defaultTask_attributes = {
+ .name = "defaultTask",
+ .priority = (osPriority_t) osPriorityNormal,
+ .stack_size = 1024 * 4
+};
+/* Definitions for app_main */
+osThreadId_t app_mainHandle;
+const osThreadAttr_t app_main_attributes = {
+ .name = "app_main",
+ .priority = (osPriority_t) osPriorityLow,
+ .stack_size = 1024 * 4
+};
+
+/* Private function prototypes -----------------------------------------------*/
+/* USER CODE BEGIN FunctionPrototypes */
+
+/* USER CODE END FunctionPrototypes */
+
+void StartDefaultTask(void *argument);
+extern void app(void *argument);
+
+void MX_FREERTOS_Init(void); /* (MISRA C 2004 rule 8.1) */
+
+/* Hook prototypes */
+void configureTimerForRunTimeStats(void);
+unsigned long getRunTimeCounterValue(void);
+void vApplicationIdleHook(void);
+void vApplicationStackOverflowHook(xTaskHandle xTask, signed char *pcTaskName);
+
+/* USER CODE BEGIN 1 */
+/* Functions needed when configGENERATE_RUN_TIME_STATS is on */
+__weak void configureTimerForRunTimeStats(void)
+{
+
+}
+
+__weak unsigned long getRunTimeCounterValue(void)
+{
+return 0;
+}
+/* USER CODE END 1 */
+
+/* USER CODE BEGIN 2 */
+__weak void vApplicationIdleHook( void )
+{
+ /* vApplicationIdleHook() will only be called if configUSE_IDLE_HOOK is set
+ to 1 in FreeRTOSConfig.h. It will be called on each iteration of the idle
+ task. It is essential that code added to this hook function never attempts
+ to block in any way (for example, call xQueueReceive() with a block time
+ specified, or call vTaskDelay()). If the application makes use of the
+ vTaskDelete() API function (as this demo application does) then it is also
+ important that vApplicationIdleHook() is permitted to return to its calling
+ function, because it is the responsibility of the idle task to clean up
+ memory allocated by the kernel to any task that has since been deleted. */
+}
+/* USER CODE END 2 */
+
+/* USER CODE BEGIN 4 */
+__weak void vApplicationStackOverflowHook(xTaskHandle xTask, signed char *pcTaskName)
+{
+ /* Run time stack overflow checking is performed if
+ configCHECK_FOR_STACK_OVERFLOW is defined to 1 or 2. This hook function is
+ called if a stack overflow is detected. */
+}
+/* USER CODE END 4 */
+
+/**
+ * @brief FreeRTOS initialization
+ * @param None
+ * @retval None
+ */
+void MX_FREERTOS_Init(void) {
+ /* USER CODE BEGIN Init */
+
+ /* USER CODE END Init */
+
+ /* USER CODE BEGIN RTOS_MUTEX */
+ /* add mutexes, ... */
+ /* USER CODE END RTOS_MUTEX */
+
+ /* USER CODE BEGIN RTOS_SEMAPHORES */
+ /* add semaphores, ... */
+ /* USER CODE END RTOS_SEMAPHORES */
+
+ /* USER CODE BEGIN RTOS_TIMERS */
+ /* start timers, add new ones, ... */
+ /* USER CODE END RTOS_TIMERS */
+
+ /* USER CODE BEGIN RTOS_QUEUES */
+ /* add queues, ... */
+ /* USER CODE END RTOS_QUEUES */
+
+ /* Create the thread(s) */
+ /* creation of defaultTask */
+ defaultTaskHandle = osThreadNew(StartDefaultTask, NULL, &defaultTask_attributes);
+
+ /* creation of app_main */
+ app_mainHandle = osThreadNew(app, NULL, &app_main_attributes);
+
+ /* USER CODE BEGIN RTOS_THREADS */
+ /* add threads, ... */
+ /* USER CODE END RTOS_THREADS */
+
+}
+
+/* USER CODE BEGIN Header_StartDefaultTask */
+/**
+ * @brief Function implementing the defaultTask thread.
+ * @param argument: Not used
+ * @retval None
+ */
+/* USER CODE END Header_StartDefaultTask */
+void StartDefaultTask(void *argument)
+{
+ /* USER CODE BEGIN StartDefaultTask */
+ /* Infinite loop */
+ for(;;)
+ {
+ osDelay(1);
+ }
+ /* USER CODE END StartDefaultTask */
+}
+
+/* Private application code --------------------------------------------------*/
+/* USER CODE BEGIN Application */
+
+/* USER CODE END Application */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/comp.c b/firmware/targets/f3/Src/comp.c
new file mode 100644
index 00000000..f17c3e3f
--- /dev/null
+++ b/firmware/targets/f3/Src/comp.c
@@ -0,0 +1,98 @@
+/**
+ ******************************************************************************
+ * File Name : COMP.c
+ * Description : This file provides code for the configuration
+ * of the COMP instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "comp.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+COMP_HandleTypeDef hcomp1;
+
+/* COMP1 init function */
+void MX_COMP1_Init(void)
+{
+
+ hcomp1.Instance = COMP1;
+ hcomp1.Init.InputMinus = COMP_INPUT_MINUS_1_2VREFINT;
+ hcomp1.Init.InputPlus = COMP_INPUT_PLUS_IO1;
+ hcomp1.Init.OutputPol = COMP_OUTPUTPOL_NONINVERTED;
+ hcomp1.Init.Hysteresis = COMP_HYSTERESIS_NONE;
+ hcomp1.Init.BlankingSrce = COMP_BLANKINGSRC_NONE;
+ hcomp1.Init.Mode = COMP_POWERMODE_HIGHSPEED;
+ hcomp1.Init.WindowMode = COMP_WINDOWMODE_DISABLE;
+ hcomp1.Init.TriggerMode = COMP_TRIGGERMODE_NONE;
+ if (HAL_COMP_Init(&hcomp1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+
+void HAL_COMP_MspInit(COMP_HandleTypeDef* compHandle)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(compHandle->Instance==COMP1)
+ {
+ /* USER CODE BEGIN COMP1_MspInit 0 */
+
+ /* USER CODE END COMP1_MspInit 0 */
+
+ __HAL_RCC_GPIOC_CLK_ENABLE();
+ /**COMP1 GPIO Configuration
+ PC5 ------> COMP1_INP
+ */
+ GPIO_InitStruct.Pin = RFID_RF_IN_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(RFID_RF_IN_GPIO_Port, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN COMP1_MspInit 1 */
+
+ /* USER CODE END COMP1_MspInit 1 */
+ }
+}
+
+void HAL_COMP_MspDeInit(COMP_HandleTypeDef* compHandle)
+{
+
+ if(compHandle->Instance==COMP1)
+ {
+ /* USER CODE BEGIN COMP1_MspDeInit 0 */
+
+ /* USER CODE END COMP1_MspDeInit 0 */
+
+ /**COMP1 GPIO Configuration
+ PC5 ------> COMP1_INP
+ */
+ HAL_GPIO_DeInit(RFID_RF_IN_GPIO_Port, RFID_RF_IN_Pin);
+
+ /* USER CODE BEGIN COMP1_MspDeInit 1 */
+
+ /* USER CODE END COMP1_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/fatfs/fatfs.c b/firmware/targets/f3/Src/fatfs/fatfs.c
new file mode 100644
index 00000000..d52b3d4e
--- /dev/null
+++ b/firmware/targets/f3/Src/fatfs/fatfs.c
@@ -0,0 +1,56 @@
+/**
+ ******************************************************************************
+ * @file fatfs.c
+ * @brief Code for fatfs applications
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+#include "fatfs.h"
+
+uint8_t retUSER; /* Return value for USER */
+char USERPath[4]; /* USER logical drive path */
+FATFS USERFatFS; /* File system object for USER logical drive */
+FIL USERFile; /* File object for USER */
+
+/* USER CODE BEGIN Variables */
+
+/* USER CODE END Variables */
+
+void MX_FATFS_Init(void)
+{
+ /*## FatFS: Link the USER driver ###########################*/
+ retUSER = FATFS_LinkDriver(&USER_Driver, USERPath);
+
+ /* USER CODE BEGIN Init */
+ /* additional user code for init */
+ /* USER CODE END Init */
+}
+
+/**
+ * @brief Gets Time from RTC
+ * @param None
+ * @retval Time in DWORD
+ */
+DWORD get_fattime(void)
+{
+ /* USER CODE BEGIN get_fattime */
+ return 0;
+ /* USER CODE END get_fattime */
+}
+
+/* USER CODE BEGIN Application */
+
+/* USER CODE END Application */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/fatfs/fatfs.h b/firmware/targets/f3/Src/fatfs/fatfs.h
new file mode 100644
index 00000000..a0775d88
--- /dev/null
+++ b/firmware/targets/f3/Src/fatfs/fatfs.h
@@ -0,0 +1,49 @@
+/**
+ ******************************************************************************
+ * @file fatfs.h
+ * @brief Header for fatfs applications
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __fatfs_H
+#define __fatfs_H
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include "fatfs/ff.h"
+#include "fatfs/ff_gen_drv.h"
+#include "user_diskio.h" /* defines USER_Driver as external */
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern uint8_t retUSER; /* Return value for USER */
+extern char USERPath[4]; /* USER logical drive path */
+extern FATFS USERFatFS; /* File system object for USER logical drive */
+extern FIL USERFile; /* File object for USER */
+
+void MX_FATFS_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+#ifdef __cplusplus
+}
+#endif
+#endif /*__fatfs_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/fatfs/ffconf.h b/firmware/targets/f3/Src/fatfs/ffconf.h
new file mode 100644
index 00000000..316e7113
--- /dev/null
+++ b/firmware/targets/f3/Src/fatfs/ffconf.h
@@ -0,0 +1,270 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * FatFs - Generic FAT file system module R0.12c (C)ChaN, 2017
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+#ifndef _FFCONF
+#define _FFCONF 68300 /* Revision ID */
+
+/*-----------------------------------------------------------------------------/
+/ Additional user header to be used
+/-----------------------------------------------------------------------------*/
+
+#include "main.h"
+#include "stm32wbxx_hal.h"
+#include "cmsis_os.h" /* _FS_REENTRANT set to 1 and CMSIS API chosen */
+
+/*-----------------------------------------------------------------------------/
+/ Function Configurations
+/-----------------------------------------------------------------------------*/
+
+#define _FS_READONLY 0 /* 0:Read/Write or 1:Read only */
+/* This option switches read-only configuration. (0:Read/Write or 1:Read-only)
+/ Read-only configuration removes writing API functions, f_write(), f_sync(),
+/ f_unlink(), f_mkdir(), f_chmod(), f_rename(), f_truncate(), f_getfree()
+/ and optional writing functions as well. */
+
+#define _FS_MINIMIZE 0 /* 0 to 3 */
+/* This option defines minimization level to remove some basic API functions.
+/
+/ 0: All basic functions are enabled.
+/ 1: f_stat(), f_getfree(), f_unlink(), f_mkdir(), f_truncate() and f_rename()
+/ are removed.
+/ 2: f_opendir(), f_readdir() and f_closedir() are removed in addition to 1.
+/ 3: f_lseek() function is removed in addition to 2. */
+
+#define _USE_STRFUNC 2 /* 0:Disable or 1-2:Enable */
+/* This option switches string functions, f_gets(), f_putc(), f_puts() and
+/ f_printf().
+/
+/ 0: Disable string functions.
+/ 1: Enable without LF-CRLF conversion.
+/ 2: Enable with LF-CRLF conversion. */
+
+#define _USE_FIND 0
+/* This option switches filtered directory read functions, f_findfirst() and
+/ f_findnext(). (0:Disable, 1:Enable 2:Enable with matching altname[] too) */
+
+#define _USE_MKFS 1
+/* This option switches f_mkfs() function. (0:Disable or 1:Enable) */
+
+#define _USE_FASTSEEK 1
+/* This option switches fast seek feature. (0:Disable or 1:Enable) */
+
+#define _USE_EXPAND 0
+/* This option switches f_expand function. (0:Disable or 1:Enable) */
+
+#define _USE_CHMOD 0
+/* This option switches attribute manipulation functions, f_chmod() and f_utime().
+/ (0:Disable or 1:Enable) Also _FS_READONLY needs to be 0 to enable this option. */
+
+#define _USE_LABEL 0
+/* This option switches volume label functions, f_getlabel() and f_setlabel().
+/ (0:Disable or 1:Enable) */
+
+#define _USE_FORWARD 0
+/* This option switches f_forward() function. (0:Disable or 1:Enable) */
+
+/*-----------------------------------------------------------------------------/
+/ Locale and Namespace Configurations
+/-----------------------------------------------------------------------------*/
+
+#define _CODE_PAGE 850
+/* This option specifies the OEM code page to be used on the target system.
+/ Incorrect setting of the code page can cause a file open failure.
+/
+/ 1 - ASCII (No extended character. Non-LFN cfg. only)
+/ 437 - U.S.
+/ 720 - Arabic
+/ 737 - Greek
+/ 771 - KBL
+/ 775 - Baltic
+/ 850 - Latin 1
+/ 852 - Latin 2
+/ 855 - Cyrillic
+/ 857 - Turkish
+/ 860 - Portuguese
+/ 861 - Icelandic
+/ 862 - Hebrew
+/ 863 - Canadian French
+/ 864 - Arabic
+/ 865 - Nordic
+/ 866 - Russian
+/ 869 - Greek 2
+/ 932 - Japanese (DBCS)
+/ 936 - Simplified Chinese (DBCS)
+/ 949 - Korean (DBCS)
+/ 950 - Traditional Chinese (DBCS)
+*/
+
+#define _USE_LFN 2 /* 0 to 3 */
+#define _MAX_LFN 255 /* Maximum LFN length to handle (12 to 255) */
+/* The _USE_LFN switches the support of long file name (LFN).
+/
+/ 0: Disable support of LFN. _MAX_LFN has no effect.
+/ 1: Enable LFN with static working buffer on the BSS. Always NOT thread-safe.
+/ 2: Enable LFN with dynamic working buffer on the STACK.
+/ 3: Enable LFN with dynamic working buffer on the HEAP.
+/
+/ To enable the LFN, Unicode handling functions (option/unicode.c) must be added
+/ to the project. The working buffer occupies (_MAX_LFN + 1) * 2 bytes and
+/ additional 608 bytes at exFAT enabled. _MAX_LFN can be in range from 12 to 255.
+/ It should be set 255 to support full featured LFN operations.
+/ When use stack for the working buffer, take care on stack overflow. When use heap
+/ memory for the working buffer, memory management functions, ff_memalloc() and
+/ ff_memfree(), must be added to the project. */
+
+#define _LFN_UNICODE 0 /* 0:ANSI/OEM or 1:Unicode */
+/* This option switches character encoding on the API. (0:ANSI/OEM or 1:UTF-16)
+/ To use Unicode string for the path name, enable LFN and set _LFN_UNICODE = 1.
+/ This option also affects behavior of string I/O functions. */
+
+#define _STRF_ENCODE 3
+/* When _LFN_UNICODE == 1, this option selects the character encoding ON THE FILE to
+/ be read/written via string I/O functions, f_gets(), f_putc(), f_puts and f_printf().
+/
+/ 0: ANSI/OEM
+/ 1: UTF-16LE
+/ 2: UTF-16BE
+/ 3: UTF-8
+/
+/ This option has no effect when _LFN_UNICODE == 0. */
+
+#define _FS_RPATH 0 /* 0 to 2 */
+/* This option configures support of relative path.
+/
+/ 0: Disable relative path and remove related functions.
+/ 1: Enable relative path. f_chdir() and f_chdrive() are available.
+/ 2: f_getcwd() function is available in addition to 1.
+*/
+
+/*---------------------------------------------------------------------------/
+/ Drive/Volume Configurations
+/----------------------------------------------------------------------------*/
+
+#define _VOLUMES 1
+/* Number of volumes (logical drives) to be used. */
+
+/* USER CODE BEGIN Volumes */
+#define _STR_VOLUME_ID 0 /* 0:Use only 0-9 for drive ID, 1:Use strings for drive ID */
+#define _VOLUME_STRS "RAM","NAND","CF","SD1","SD2","USB1","USB2","USB3"
+/* _STR_VOLUME_ID switches string support of volume ID.
+/ When _STR_VOLUME_ID is set to 1, also pre-defined strings can be used as drive
+/ number in the path name. _VOLUME_STRS defines the drive ID strings for each
+/ logical drives. Number of items must be equal to _VOLUMES. Valid characters for
+/ the drive ID strings are: A-Z and 0-9. */
+/* USER CODE END Volumes */
+
+#define _MULTI_PARTITION 0 /* 0:Single partition, 1:Multiple partition */
+/* This option switches support of multi-partition on a physical drive.
+/ By default (0), each logical drive number is bound to the same physical drive
+/ number and only an FAT volume found on the physical drive will be mounted.
+/ When multi-partition is enabled (1), each logical drive number can be bound to
+/ arbitrary physical drive and partition listed in the VolToPart[]. Also f_fdisk()
+/ funciton will be available. */
+#define _MIN_SS 512 /* 512, 1024, 2048 or 4096 */
+#define _MAX_SS 512 /* 512, 1024, 2048 or 4096 */
+/* These options configure the range of sector size to be supported. (512, 1024,
+/ 2048 or 4096) Always set both 512 for most systems, all type of memory cards and
+/ harddisk. But a larger value may be required for on-board flash memory and some
+/ type of optical media. When _MAX_SS is larger than _MIN_SS, FatFs is configured
+/ to variable sector size and GET_SECTOR_SIZE command must be implemented to the
+/ disk_ioctl() function. */
+
+#define _USE_TRIM 0
+/* This option switches support of ATA-TRIM. (0:Disable or 1:Enable)
+/ To enable Trim function, also CTRL_TRIM command should be implemented to the
+/ disk_ioctl() function. */
+
+#define _FS_NOFSINFO 0 /* 0,1,2 or 3 */
+/* If you need to know correct free space on the FAT32 volume, set bit 0 of this
+/ option, and f_getfree() function at first time after volume mount will force
+/ a full FAT scan. Bit 1 controls the use of last allocated cluster number.
+/
+/ bit0=0: Use free cluster count in the FSINFO if available.
+/ bit0=1: Do not trust free cluster count in the FSINFO.
+/ bit1=0: Use last allocated cluster number in the FSINFO if available.
+/ bit1=1: Do not trust last allocated cluster number in the FSINFO.
+*/
+
+/*---------------------------------------------------------------------------/
+/ System Configurations
+/----------------------------------------------------------------------------*/
+
+#define _FS_TINY 0 /* 0:Normal or 1:Tiny */
+/* This option switches tiny buffer configuration. (0:Normal or 1:Tiny)
+/ At the tiny configuration, size of file object (FIL) is reduced _MAX_SS bytes.
+/ Instead of private sector buffer eliminated from the file object, common sector
+/ buffer in the file system object (FATFS) is used for the file data transfer. */
+
+#define _FS_EXFAT 0
+/* This option switches support of exFAT file system. (0:Disable or 1:Enable)
+/ When enable exFAT, also LFN needs to be enabled. (_USE_LFN >= 1)
+/ Note that enabling exFAT discards C89 compatibility. */
+
+#define _FS_NORTC 0
+#define _NORTC_MON 6
+#define _NORTC_MDAY 4
+#define _NORTC_YEAR 2015
+/* The option _FS_NORTC switches timestamp functiton. If the system does not have
+/ any RTC function or valid timestamp is not needed, set _FS_NORTC = 1 to disable
+/ the timestamp function. All objects modified by FatFs will have a fixed timestamp
+/ defined by _NORTC_MON, _NORTC_MDAY and _NORTC_YEAR in local time.
+/ To enable timestamp function (_FS_NORTC = 0), get_fattime() function need to be
+/ added to the project to get current time form real-time clock. _NORTC_MON,
+/ _NORTC_MDAY and _NORTC_YEAR have no effect.
+/ These options have no effect at read-only configuration (_FS_READONLY = 1). */
+
+#define _FS_LOCK 2 /* 0:Disable or >=1:Enable */
+/* The option _FS_LOCK switches file lock function to control duplicated file open
+/ and illegal operation to open objects. This option must be 0 when _FS_READONLY
+/ is 1.
+/
+/ 0: Disable file lock function. To avoid volume corruption, application program
+/ should avoid illegal open, remove and rename to the open objects.
+/ >0: Enable file lock function. The value defines how many files/sub-directories
+/ can be opened simultaneously under file lock control. Note that the file
+/ lock control is independent of re-entrancy. */
+
+#define _FS_REENTRANT 1 /* 0:Disable or 1:Enable */
+#define _FS_TIMEOUT 1000 /* Timeout period in unit of time ticks */
+#define _SYNC_t osMutexId_t
+/* The option _FS_REENTRANT switches the re-entrancy (thread safe) of the FatFs
+/ module itself. Note that regardless of this option, file access to different
+/ volume is always re-entrant and volume control functions, f_mount(), f_mkfs()
+/ and f_fdisk() function, are always not re-entrant. Only file/directory access
+/ to the same volume is under control of this function.
+/
+/ 0: Disable re-entrancy. _FS_TIMEOUT and _SYNC_t have no effect.
+/ 1: Enable re-entrancy. Also user provided synchronization handlers,
+/ ff_req_grant(), ff_rel_grant(), ff_del_syncobj() and ff_cre_syncobj()
+/ function, must be added to the project. Samples are available in
+/ option/syscall.c.
+/
+/ The _FS_TIMEOUT defines timeout period in unit of time tick.
+/ The _SYNC_t defines O/S dependent sync object type. e.g. HANDLE, ID, OS_EVENT*,
+/ SemaphoreHandle_t and etc.. A header file for O/S definitions needs to be
+/ included somewhere in the scope of ff.h. */
+
+/* define the ff_malloc ff_free macros as standard malloc free */
+#if !defined(ff_malloc) && !defined(ff_free)
+#include
+#define ff_malloc malloc
+#define ff_free free
+#endif
+
+#endif /* _FFCONF */
diff --git a/firmware/targets/f3/Src/fatfs/spi_sd_hal.c b/firmware/targets/f3/Src/fatfs/spi_sd_hal.c
new file mode 100644
index 00000000..0cad29f7
--- /dev/null
+++ b/firmware/targets/f3/Src/fatfs/spi_sd_hal.c
@@ -0,0 +1,124 @@
+#include "main.h"
+
+#define SD_DUMMY_BYTE 0xFF
+#define SD_CS_LOW() HAL_GPIO_WritePin(SD_CS_GPIO_Port, SD_CS_Pin, GPIO_PIN_RESET)
+#define SD_CS_HIGH() HAL_GPIO_WritePin(SD_CS_GPIO_Port, SD_CS_Pin, GPIO_PIN_SET)
+
+const uint32_t SpiTimeout = 1000;
+extern SPI_HandleTypeDef SPI_SD_HANDLE;
+uint8_t SD_IO_WriteByte(uint8_t Data);
+
+/******************************************************************************
+ BUS OPERATIONS
+ *******************************************************************************/
+
+/**
+ * @brief SPI error treatment function
+ * @retval None
+ */
+static void SPIx_Error(void) {
+ /* De-initialize the SPI communication BUS */
+ HAL_SPI_DeInit(&SPI_SD_HANDLE);
+
+ /* Re-Initiaize the SPI communication BUS */
+ HAL_SPI_Init(&SPI_SD_HANDLE);
+}
+
+/**
+ * @brief SPI Write byte(s) to device
+ * @param DataIn: Pointer to data buffer to write
+ * @param DataOut: Pointer to data buffer for read data
+ * @param DataLength: number of bytes to write
+ * @retval None
+ */
+static void SPIx_WriteReadData(const uint8_t* DataIn, uint8_t* DataOut, uint16_t DataLength) {
+ HAL_StatusTypeDef status = HAL_OK;
+ status =
+ HAL_SPI_TransmitReceive(&SPI_SD_HANDLE, (uint8_t*)DataIn, DataOut, DataLength, SpiTimeout);
+
+ /* Check the communication status */
+ if(status != HAL_OK) {
+ /* Execute user timeout callback */
+ SPIx_Error();
+ }
+}
+
+/**
+ * @brief SPI Write a byte to device
+ * @param Value: value to be written
+ * @retval None
+ */
+__attribute__((unused)) static void SPIx_Write(uint8_t Value) {
+ HAL_StatusTypeDef status = HAL_OK;
+ uint8_t data;
+
+ status = HAL_SPI_TransmitReceive(&SPI_SD_HANDLE, (uint8_t*)&Value, &data, 1, SpiTimeout);
+
+ /* Check the communication status */
+ if(status != HAL_OK) {
+ /* Execute user timeout callback */
+ SPIx_Error();
+ }
+}
+
+/******************************************************************************
+ LINK OPERATIONS
+ *******************************************************************************/
+
+/********************************* LINK SD ************************************/
+/**
+ * @brief Initialize the SD Card and put it into StandBy State (Ready for
+ * data transfer).
+ * @retval None
+ */
+void SD_IO_Init(void) {
+ uint8_t counter = 0;
+
+ /* SD chip select high */
+ SD_CS_HIGH();
+
+ /* Send dummy byte 0xFF, 10 times with CS high */
+ /* Rise CS and MOSI for 80 clocks cycles */
+ for(counter = 0; counter <= 200; counter++) {
+ /* Send dummy byte 0xFF */
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ }
+}
+
+/**
+ * @brief Set SD interface Chip Select state
+ * @param val: 0 (low) or 1 (high) state
+ * @retval None
+ */
+void SD_IO_CSState(uint8_t val) {
+ if(val == 1) {
+ SD_CS_HIGH();
+ } else {
+ SD_CS_LOW();
+ }
+}
+
+/**
+ * @brief Write byte(s) on the SD
+ * @param DataIn: Pointer to data buffer to write
+ * @param DataOut: Pointer to data buffer for read data
+ * @param DataLength: number of bytes to write
+ * @retval None
+ */
+void SD_IO_WriteReadData(const uint8_t* DataIn, uint8_t* DataOut, uint16_t DataLength) {
+ /* Send the byte */
+ SPIx_WriteReadData(DataIn, DataOut, DataLength);
+}
+
+/**
+ * @brief Write a byte on the SD.
+ * @param Data: byte to send.
+ * @retval Data written
+ */
+uint8_t SD_IO_WriteByte(uint8_t Data) {
+ uint8_t tmp;
+
+ /* Send the byte */
+ SPIx_WriteReadData(&Data, &tmp, 1);
+ return tmp;
+}
diff --git a/firmware/targets/f3/Src/fatfs/stm32_adafruit_sd.c b/firmware/targets/f3/Src/fatfs/stm32_adafruit_sd.c
new file mode 100644
index 00000000..cc71e98b
--- /dev/null
+++ b/firmware/targets/f3/Src/fatfs/stm32_adafruit_sd.c
@@ -0,0 +1,1013 @@
+/**
+ ******************************************************************************
+ * @file stm32_adafruit_sd.c
+ * @author MCD Application Team
+ * @version V3.0.0
+ * @date 23-December-2016
+ * @brief This file provides a set of functions needed to manage the SD card
+ * mounted on the Adafruit 1.8" TFT LCD shield (reference ID 802),
+ * that is used with the STM32 Nucleo board through SPI interface.
+ * It implements a high level communication layer for read and write
+ * from/to this memory. The needed STM32XXxx hardware resources (SPI and
+ * GPIO) are defined in stm32XXxx_nucleo.h file, and the initialization is
+ * performed in SD_IO_Init() function declared in stm32XXxx_nucleo.c
+ * file.
+ * You can easily tailor this driver to any other development board,
+ * by just adapting the defines for hardware resources and
+ * SD_IO_Init() function.
+ *
+ * +-------------------------------------------------------+
+ * | Pin assignment |
+ * +-------------------------+---------------+-------------+
+ * | STM32XXxx SPI Pins | SD | Pin |
+ * +-------------------------+---------------+-------------+
+ * | SD_SPI_CS_PIN | ChipSelect | 1 |
+ * | SD_SPI_MOSI_PIN / MOSI | DataIn | 2 |
+ * | | GND | 3 (0 V) |
+ * | | VDD | 4 (3.3 V)|
+ * | SD_SPI_SCK_PIN / SCLK | Clock | 5 |
+ * | | GND | 6 (0 V) |
+ * | SD_SPI_MISO_PIN / MISO | DataOut | 7 |
+ * +-------------------------+---------------+-------------+
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2016 STMicroelectronics
+ *
+ * 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.
+ *
+ ******************************************************************************
+ */
+
+/* File Info : -----------------------------------------------------------------
+ User NOTES
+1. How to use this driver:
+--------------------------
+ - This driver does not need a specific component driver for the micro SD device
+ to be included with.
+
+2. Driver description:
+---------------------
+ + Initialization steps:
+ o Initialize the micro SD card using the BSP_SD_Init() function.
+ o Checking the SD card presence is not managed because SD detection pin is
+ not physically mapped on the Adafruit shield.
+ o The function BSP_SD_GetCardInfo() is used to get the micro SD card information
+ which is stored in the structure "SD_CardInfo".
+
+ + Micro SD card operations
+ o The micro SD card can be accessed with read/write block(s) operations once
+ it is ready for access. The access can be performed in polling
+ mode by calling the functions BSP_SD_ReadBlocks()/BSP_SD_WriteBlocks()
+
+ o The SD erase block(s) is performed using the function BSP_SD_Erase() with
+ specifying the number of blocks to erase.
+ o The SD runtime status is returned when calling the function BSP_SD_GetStatus().
+
+------------------------------------------------------------------------------*/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32_adafruit_sd.h"
+#include "stdlib.h"
+#include "string.h"
+#include "stdio.h"
+#include "spi.h"
+
+/** @addtogroup BSP
+ * @{
+ */
+
+/** @addtogroup STM32_ADAFRUIT
+ * @{
+ */
+
+/** @defgroup STM32_ADAFRUIT_SD
+ * @{
+ */
+
+/* Private typedef -----------------------------------------------------------*/
+
+/** @defgroup STM32_ADAFRUIT_SD_Private_Types_Definitions
+ * @{
+ */
+typedef struct {
+ uint8_t r1;
+ uint8_t r2;
+ uint8_t r3;
+ uint8_t r4;
+ uint8_t r5;
+} SD_CmdAnswer_typedef;
+
+/**
+ * @}
+ */
+
+/* Private define ------------------------------------------------------------*/
+
+/** @defgroup STM32_ADAFRUIT_SD_Private_Defines
+ * @{
+ */
+#define SD_DUMMY_BYTE 0xFF
+
+#define SD_MAX_FRAME_LENGTH 17 /* Lenght = 16 + 1 */
+#define SD_CMD_LENGTH 6
+
+#define SD_MAX_TRY 100 /* Number of try */
+
+#define SD_CSD_STRUCT_V1 0x2 /* CSD struct version V1 */
+#define SD_CSD_STRUCT_V2 0x1 /* CSD struct version V2 */
+
+/**
+ * @brief SD ansewer format
+ */
+typedef enum {
+ SD_ANSWER_R1_EXPECTED,
+ SD_ANSWER_R1B_EXPECTED,
+ SD_ANSWER_R2_EXPECTED,
+ SD_ANSWER_R3_EXPECTED,
+ SD_ANSWER_R4R5_EXPECTED,
+ SD_ANSWER_R7_EXPECTED,
+} SD_Answer_type;
+
+/**
+ * @brief Start Data tokens:
+ * Tokens (necessary because at nop/idle (and CS active) only 0xff is
+ * on the data/command line)
+ */
+#define SD_TOKEN_START_DATA_SINGLE_BLOCK_READ \
+ 0xFE /* Data token start byte, Start Single Block Read */
+#define SD_TOKEN_START_DATA_MULTIPLE_BLOCK_READ \
+ 0xFE /* Data token start byte, Start Multiple Block Read */
+#define SD_TOKEN_START_DATA_SINGLE_BLOCK_WRITE \
+ 0xFE /* Data token start byte, Start Single Block Write */
+#define SD_TOKEN_START_DATA_MULTIPLE_BLOCK_WRITE \
+ 0xFD /* Data token start byte, Start Multiple Block Write */
+#define SD_TOKEN_STOP_DATA_MULTIPLE_BLOCK_WRITE \
+ 0xFD /* Data toke stop byte, Stop Multiple Block Write */
+
+/**
+ * @brief Commands: CMDxx = CMD-number | 0x40
+ */
+#define SD_CMD_GO_IDLE_STATE 0 /* CMD0 = 0x40 */
+#define SD_CMD_SEND_OP_COND 1 /* CMD1 = 0x41 */
+#define SD_CMD_SEND_IF_COND 8 /* CMD8 = 0x48 */
+#define SD_CMD_SEND_CSD 9 /* CMD9 = 0x49 */
+#define SD_CMD_SEND_CID 10 /* CMD10 = 0x4A */
+#define SD_CMD_STOP_TRANSMISSION 12 /* CMD12 = 0x4C */
+#define SD_CMD_SEND_STATUS 13 /* CMD13 = 0x4D */
+#define SD_CMD_SET_BLOCKLEN 16 /* CMD16 = 0x50 */
+#define SD_CMD_READ_SINGLE_BLOCK 17 /* CMD17 = 0x51 */
+#define SD_CMD_READ_MULT_BLOCK 18 /* CMD18 = 0x52 */
+#define SD_CMD_SET_BLOCK_COUNT 23 /* CMD23 = 0x57 */
+#define SD_CMD_WRITE_SINGLE_BLOCK 24 /* CMD24 = 0x58 */
+#define SD_CMD_WRITE_MULT_BLOCK 25 /* CMD25 = 0x59 */
+#define SD_CMD_PROG_CSD 27 /* CMD27 = 0x5B */
+#define SD_CMD_SET_WRITE_PROT 28 /* CMD28 = 0x5C */
+#define SD_CMD_CLR_WRITE_PROT 29 /* CMD29 = 0x5D */
+#define SD_CMD_SEND_WRITE_PROT 30 /* CMD30 = 0x5E */
+#define SD_CMD_SD_ERASE_GRP_START 32 /* CMD32 = 0x60 */
+#define SD_CMD_SD_ERASE_GRP_END 33 /* CMD33 = 0x61 */
+#define SD_CMD_UNTAG_SECTOR 34 /* CMD34 = 0x62 */
+#define SD_CMD_ERASE_GRP_START 35 /* CMD35 = 0x63 */
+#define SD_CMD_ERASE_GRP_END 36 /* CMD36 = 0x64 */
+#define SD_CMD_UNTAG_ERASE_GROUP 37 /* CMD37 = 0x65 */
+#define SD_CMD_ERASE 38 /* CMD38 = 0x66 */
+#define SD_CMD_SD_APP_OP_COND 41 /* CMD41 = 0x69 */
+#define SD_CMD_APP_CMD 55 /* CMD55 = 0x77 */
+#define SD_CMD_READ_OCR 58 /* CMD55 = 0x79 */
+
+/**
+ * @brief SD reponses and error flags
+ */
+typedef enum {
+ /* R1 answer value */
+ SD_R1_NO_ERROR = (0x00),
+ SD_R1_IN_IDLE_STATE = (0x01),
+ SD_R1_ERASE_RESET = (0x02),
+ SD_R1_ILLEGAL_COMMAND = (0x04),
+ SD_R1_COM_CRC_ERROR = (0x08),
+ SD_R1_ERASE_SEQUENCE_ERROR = (0x10),
+ SD_R1_ADDRESS_ERROR = (0x20),
+ SD_R1_PARAMETER_ERROR = (0x40),
+
+ /* R2 answer value */
+ SD_R2_NO_ERROR = 0x00,
+ SD_R2_CARD_LOCKED = 0x01,
+ SD_R2_LOCKUNLOCK_ERROR = 0x02,
+ SD_R2_ERROR = 0x04,
+ SD_R2_CC_ERROR = 0x08,
+ SD_R2_CARD_ECC_FAILED = 0x10,
+ SD_R2_WP_VIOLATION = 0x20,
+ SD_R2_ERASE_PARAM = 0x40,
+ SD_R2_OUTOFRANGE = 0x80,
+
+ /**
+ * @brief Data response error
+ */
+ SD_DATA_OK = (0x05),
+ SD_DATA_CRC_ERROR = (0x0B),
+ SD_DATA_WRITE_ERROR = (0x0D),
+ SD_DATA_OTHER_ERROR = (0xFF)
+} SD_Error;
+
+/**
+ * @}
+ */
+
+/* Private macro -------------------------------------------------------------*/
+
+/** @defgroup STM32_ADAFRUIT_SD_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/* Private variables ---------------------------------------------------------*/
+
+/** @defgroup STM32_ADAFRUIT_SD_Private_Variables
+ * @{
+ */
+__IO uint8_t SdStatus = SD_NOT_PRESENT;
+
+/* flag_SDHC :
+ 0 : Standard capacity
+ 1 : High capacity
+*/
+uint16_t flag_SDHC = 0;
+
+/**
+ * @}
+ */
+
+/* Private function prototypes -----------------------------------------------*/
+static uint8_t SD_GetCIDRegister(SD_CID* Cid);
+static uint8_t SD_GetCSDRegister(SD_CSD* Csd);
+static uint8_t SD_GetDataResponse(void);
+static uint8_t SD_GoIdleState(void);
+static SD_CmdAnswer_typedef SD_SendCmd(uint8_t Cmd, uint32_t Arg, uint8_t Crc, uint8_t Answer);
+static uint8_t SD_WaitData(uint8_t data);
+static uint8_t SD_ReadData(void);
+/** @defgroup STM32_ADAFRUIT_SD_Private_Function_Prototypes
+ * @{
+ */
+/**
+ * @}
+ */
+
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup STM32_ADAFRUIT_SD_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Initializes the SD/SD communication.
+ * @param None
+ * @retval The SD Response:
+ * - MSD_ERROR: Sequence failed
+ * - MSD_OK: Sequence succeed
+ */
+uint8_t BSP_SD_Init(void) {
+ /* Init to maximum slow speed */
+ SD_SPI_Reconfigure_Slow();
+
+ /* Configure IO functionalities for SD pin */
+ SD_IO_Init();
+
+ /* SD detection pin is not physically mapped on the Adafruit shield */
+ SdStatus = SD_PRESENT;
+ uint8_t res = SD_GoIdleState();
+
+ /* Init to maximum fastest speed */
+ SD_SPI_Reconfigure_Fast();
+
+ /* SD initialized and set to SPI mode properly */
+ return res;
+}
+
+/**
+ * @brief Returns information about specific card.
+ * @param pCardInfo: Pointer to a SD_CardInfo structure that contains all SD
+ * card information.
+ * @retval The SD Response:
+ * - MSD_ERROR: Sequence failed
+ * - MSD_OK: Sequence succeed
+ */
+uint8_t BSP_SD_GetCardInfo(SD_CardInfo* pCardInfo) {
+ uint8_t status;
+
+ status = SD_GetCSDRegister(&(pCardInfo->Csd));
+ status |= SD_GetCIDRegister(&(pCardInfo->Cid));
+ if(flag_SDHC == 1) {
+ pCardInfo->LogBlockSize = 512;
+ pCardInfo->CardBlockSize = 512;
+ pCardInfo->CardCapacity =
+ (pCardInfo->Csd.version.v2.DeviceSize + 1) * 1024 * pCardInfo->LogBlockSize;
+ pCardInfo->LogBlockNbr = (pCardInfo->CardCapacity) / (pCardInfo->LogBlockSize);
+ } else {
+ pCardInfo->CardCapacity = (pCardInfo->Csd.version.v1.DeviceSize + 1);
+ pCardInfo->CardCapacity *= (1 << (pCardInfo->Csd.version.v1.DeviceSizeMul + 2));
+ pCardInfo->LogBlockSize = 512;
+ pCardInfo->CardBlockSize = 1 << (pCardInfo->Csd.RdBlockLen);
+ pCardInfo->CardCapacity *= pCardInfo->CardBlockSize;
+ pCardInfo->LogBlockNbr = (pCardInfo->CardCapacity) / (pCardInfo->LogBlockSize);
+ }
+
+ return status;
+}
+
+/**
+ * @brief Reads block(s) from a specified address in the SD card, in polling mode.
+ * @param pData: Pointer to the buffer that will contain the data to transmit
+ * @param ReadAddr: Address from where data is to be read. The address is counted
+ * in blocks of 512bytes
+ * @param NumOfBlocks: Number of SD blocks to read
+ * @param Timeout: This parameter is used for compatibility with BSP implementation
+ * @retval SD status
+ */
+uint8_t
+BSP_SD_ReadBlocks(uint32_t* pData, uint32_t ReadAddr, uint32_t NumOfBlocks, uint32_t Timeout) {
+ uint32_t offset = 0;
+ uint8_t retr = BSP_SD_ERROR;
+ SD_CmdAnswer_typedef response;
+ uint16_t BlockSize = 512;
+
+ uint8_t* ptr = NULL;
+ // uint8_t ptr[512];
+
+ /* Send CMD16 (SD_CMD_SET_BLOCKLEN) to set the size of the block and
+ Check if the SD acknowledged the set block length command: R1 response (0x00: no errors) */
+ response = SD_SendCmd(SD_CMD_SET_BLOCKLEN, BlockSize, 0xFF, SD_ANSWER_R1_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ if(response.r1 != SD_R1_NO_ERROR) {
+ goto error;
+ }
+
+ ptr = malloc(sizeof(uint8_t) * BlockSize);
+ if(ptr == NULL) {
+ goto error;
+ }
+ memset(ptr, SD_DUMMY_BYTE, sizeof(uint8_t) * BlockSize);
+
+ /* Data transfer */
+ while(NumOfBlocks--) {
+ /* Send CMD17 (SD_CMD_READ_SINGLE_BLOCK) to read one block */
+ /* Check if the SD acknowledged the read block command: R1 response (0x00: no errors) */
+ response = SD_SendCmd(
+ SD_CMD_READ_SINGLE_BLOCK,
+ (ReadAddr + offset) * (flag_SDHC == 1 ? 1 : BlockSize),
+ 0xFF,
+ SD_ANSWER_R1_EXPECTED);
+ if(response.r1 != SD_R1_NO_ERROR) {
+ goto error;
+ }
+
+ /* Now look for the data token to signify the start of the data */
+ if(SD_WaitData(SD_TOKEN_START_DATA_SINGLE_BLOCK_READ) == BSP_SD_OK) {
+ /* Read the SD block data : read NumByteToRead data */
+ SD_IO_WriteReadData(ptr, (uint8_t*)pData + offset, BlockSize);
+
+ /* Set next read address*/
+ offset += BlockSize;
+ /* get CRC bytes (not really needed by us, but required by SD) */
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ } else {
+ goto error;
+ }
+
+ /* End the command data read cycle */
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ }
+
+ retr = BSP_SD_OK;
+
+error:
+ /* Send dummy byte: 8 Clock pulses of delay */
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ if(ptr != NULL) free(ptr);
+
+ /* Return the reponse */
+ return retr;
+}
+
+/**
+ * @brief Writes block(s) to a specified address in the SD card, in polling mode.
+ * @param pData: Pointer to the buffer that will contain the data to transmit
+ * @param WriteAddr: Address from where data is to be written. The address is counted
+ * in blocks of 512bytes
+ * @param NumOfBlocks: Number of SD blocks to write
+ * @param Timeout: This parameter is used for compatibility with BSP implementation
+ * @retval SD status
+ */
+uint8_t
+BSP_SD_WriteBlocks(uint32_t* pData, uint32_t WriteAddr, uint32_t NumOfBlocks, uint32_t Timeout) {
+ uint32_t offset = 0;
+ uint8_t retr = BSP_SD_ERROR;
+ uint8_t* ptr = NULL;
+ SD_CmdAnswer_typedef response;
+ uint16_t BlockSize = 512;
+
+ /* Send CMD16 (SD_CMD_SET_BLOCKLEN) to set the size of the block and
+ Check if the SD acknowledged the set block length command: R1 response (0x00: no errors) */
+ response = SD_SendCmd(SD_CMD_SET_BLOCKLEN, BlockSize, 0xFF, SD_ANSWER_R1_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ if(response.r1 != SD_R1_NO_ERROR) {
+ goto error;
+ }
+
+ ptr = malloc(sizeof(uint8_t) * BlockSize);
+ if(ptr == NULL) {
+ goto error;
+ }
+
+ /* Data transfer */
+ while(NumOfBlocks--) {
+ /* Send CMD24 (SD_CMD_WRITE_SINGLE_BLOCK) to write blocks and
+ Check if the SD acknowledged the write block command: R1 response (0x00: no errors) */
+ response = SD_SendCmd(
+ SD_CMD_WRITE_SINGLE_BLOCK,
+ (WriteAddr + offset) * (flag_SDHC == 1 ? 1 : BlockSize),
+ 0xFF,
+ SD_ANSWER_R1_EXPECTED);
+ if(response.r1 != SD_R1_NO_ERROR) {
+ goto error;
+ }
+
+ /* Send dummy byte for NWR timing : one byte between CMDWRITE and TOKEN */
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+
+ /* Send the data token to signify the start of the data */
+ SD_IO_WriteByte(SD_TOKEN_START_DATA_SINGLE_BLOCK_WRITE);
+
+ /* Write the block data to SD */
+ SD_IO_WriteReadData((uint8_t*)pData + offset, ptr, BlockSize);
+
+ /* Set next write address */
+ offset += BlockSize;
+
+ /* Put CRC bytes (not really needed by us, but required by SD) */
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+
+ /* Read data response */
+ if(SD_GetDataResponse() != SD_DATA_OK) {
+ /* Set response value to failure */
+ goto error;
+ }
+
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ }
+ retr = BSP_SD_OK;
+
+error:
+ if(ptr != NULL) free(ptr);
+ /* Send dummy byte: 8 Clock pulses of delay */
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+
+ /* Return the reponse */
+ return retr;
+}
+
+/**
+ * @brief Erases the specified memory area of the given SD card.
+ * @param StartAddr: Start address in Blocks (Size of a block is 512bytes)
+ * @param EndAddr: End address in Blocks (Size of a block is 512bytes)
+ * @retval SD status
+ */
+uint8_t BSP_SD_Erase(uint32_t StartAddr, uint32_t EndAddr) {
+ uint8_t retr = BSP_SD_ERROR;
+ SD_CmdAnswer_typedef response;
+ uint16_t BlockSize = 512;
+
+ /* Send CMD32 (Erase group start) and check if the SD acknowledged the erase command: R1 response (0x00: no errors) */
+ response = SD_SendCmd(
+ SD_CMD_SD_ERASE_GRP_START,
+ (StartAddr) * (flag_SDHC == 1 ? 1 : BlockSize),
+ 0xFF,
+ SD_ANSWER_R1_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ if(response.r1 == SD_R1_NO_ERROR) {
+ /* Send CMD33 (Erase group end) and Check if the SD acknowledged the erase command: R1 response (0x00: no errors) */
+ response = SD_SendCmd(
+ SD_CMD_SD_ERASE_GRP_END,
+ (EndAddr * 512) * (flag_SDHC == 1 ? 1 : BlockSize),
+ 0xFF,
+ SD_ANSWER_R1_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ if(response.r1 == SD_R1_NO_ERROR) {
+ /* Send CMD38 (Erase) and Check if the SD acknowledged the erase command: R1 response (0x00: no errors) */
+ response = SD_SendCmd(SD_CMD_ERASE, 0, 0xFF, SD_ANSWER_R1B_EXPECTED);
+ if(response.r1 == SD_R1_NO_ERROR) {
+ retr = BSP_SD_OK;
+ }
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ }
+ }
+
+ /* Return the reponse */
+ return retr;
+}
+
+/**
+ * @brief Returns the SD status.
+ * @param None
+ * @retval The SD status.
+ */
+uint8_t BSP_SD_GetCardState(void) {
+ SD_CmdAnswer_typedef retr;
+
+ /* Send CMD13 (SD_SEND_STATUS) to get SD status */
+ retr = SD_SendCmd(SD_CMD_SEND_STATUS, 0, 0xFF, SD_ANSWER_R2_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+
+ /* Find SD status according to card state */
+ if((retr.r1 == SD_R1_NO_ERROR) && (retr.r2 == SD_R2_NO_ERROR)) {
+ return BSP_SD_OK;
+ }
+
+ return BSP_SD_ERROR;
+}
+
+/**
+ * @brief Reads the SD card SCD register.
+ * Reading the contents of the CSD register in SPI mode is a simple
+ * read-block transaction.
+ * @param Csd: pointer on an SCD register structure
+ * @retval SD status
+ */
+uint8_t SD_GetCSDRegister(SD_CSD* Csd) {
+ uint16_t counter = 0;
+ uint8_t CSD_Tab[16];
+ uint8_t retr = BSP_SD_ERROR;
+ SD_CmdAnswer_typedef response;
+
+ /* Send CMD9 (CSD register) or CMD10(CSD register) and Wait for response in the R1 format (0x00 is no errors) */
+ response = SD_SendCmd(SD_CMD_SEND_CSD, 0, 0xFF, SD_ANSWER_R1_EXPECTED);
+ if(response.r1 == SD_R1_NO_ERROR) {
+ if(SD_WaitData(SD_TOKEN_START_DATA_SINGLE_BLOCK_READ) == BSP_SD_OK) {
+ for(counter = 0; counter < 16; counter++) {
+ /* Store CSD register value on CSD_Tab */
+ CSD_Tab[counter] = SD_IO_WriteByte(SD_DUMMY_BYTE);
+ }
+
+ /* Get CRC bytes (not really needed by us, but required by SD) */
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+
+ /*************************************************************************
+ CSD header decoding
+ *************************************************************************/
+
+ /* Byte 0 */
+ Csd->CSDStruct = (CSD_Tab[0] & 0xC0) >> 6;
+ Csd->Reserved1 = CSD_Tab[0] & 0x3F;
+
+ /* Byte 1 */
+ Csd->TAAC = CSD_Tab[1];
+
+ /* Byte 2 */
+ Csd->NSAC = CSD_Tab[2];
+
+ /* Byte 3 */
+ Csd->MaxBusClkFrec = CSD_Tab[3];
+
+ /* Byte 4/5 */
+ Csd->CardComdClasses = (CSD_Tab[4] << 4) | ((CSD_Tab[5] & 0xF0) >> 4);
+ Csd->RdBlockLen = CSD_Tab[5] & 0x0F;
+
+ /* Byte 6 */
+ Csd->PartBlockRead = (CSD_Tab[6] & 0x80) >> 7;
+ Csd->WrBlockMisalign = (CSD_Tab[6] & 0x40) >> 6;
+ Csd->RdBlockMisalign = (CSD_Tab[6] & 0x20) >> 5;
+ Csd->DSRImpl = (CSD_Tab[6] & 0x10) >> 4;
+
+ /*************************************************************************
+ CSD v1/v2 decoding
+ *************************************************************************/
+
+ if(flag_SDHC == 0) {
+ Csd->version.v1.Reserved1 = ((CSD_Tab[6] & 0x0C) >> 2);
+
+ Csd->version.v1.DeviceSize = ((CSD_Tab[6] & 0x03) << 10) | (CSD_Tab[7] << 2) |
+ ((CSD_Tab[8] & 0xC0) >> 6);
+ Csd->version.v1.MaxRdCurrentVDDMin = (CSD_Tab[8] & 0x38) >> 3;
+ Csd->version.v1.MaxRdCurrentVDDMax = (CSD_Tab[8] & 0x07);
+ Csd->version.v1.MaxWrCurrentVDDMin = (CSD_Tab[9] & 0xE0) >> 5;
+ Csd->version.v1.MaxWrCurrentVDDMax = (CSD_Tab[9] & 0x1C) >> 2;
+ Csd->version.v1.DeviceSizeMul = ((CSD_Tab[9] & 0x03) << 1) |
+ ((CSD_Tab[10] & 0x80) >> 7);
+ } else {
+ Csd->version.v2.Reserved1 = ((CSD_Tab[6] & 0x0F) << 2) |
+ ((CSD_Tab[7] & 0xC0) >> 6);
+ Csd->version.v2.DeviceSize = ((CSD_Tab[7] & 0x3F) << 16) | (CSD_Tab[8] << 8) |
+ CSD_Tab[9];
+ Csd->version.v2.Reserved2 = ((CSD_Tab[10] & 0x80) >> 8);
+ }
+
+ Csd->EraseSingleBlockEnable = (CSD_Tab[10] & 0x40) >> 6;
+ Csd->EraseSectorSize = ((CSD_Tab[10] & 0x3F) << 1) | ((CSD_Tab[11] & 0x80) >> 7);
+ Csd->WrProtectGrSize = (CSD_Tab[11] & 0x7F);
+ Csd->WrProtectGrEnable = (CSD_Tab[12] & 0x80) >> 7;
+ Csd->Reserved2 = (CSD_Tab[12] & 0x60) >> 5;
+ Csd->WrSpeedFact = (CSD_Tab[12] & 0x1C) >> 2;
+ Csd->MaxWrBlockLen = ((CSD_Tab[12] & 0x03) << 2) | ((CSD_Tab[13] & 0xC0) >> 6);
+ Csd->WriteBlockPartial = (CSD_Tab[13] & 0x20) >> 5;
+ Csd->Reserved3 = (CSD_Tab[13] & 0x1F);
+ Csd->FileFormatGrouop = (CSD_Tab[14] & 0x80) >> 7;
+ Csd->CopyFlag = (CSD_Tab[14] & 0x40) >> 6;
+ Csd->PermWrProtect = (CSD_Tab[14] & 0x20) >> 5;
+ Csd->TempWrProtect = (CSD_Tab[14] & 0x10) >> 4;
+ Csd->FileFormat = (CSD_Tab[14] & 0x0C) >> 2;
+ Csd->Reserved4 = (CSD_Tab[14] & 0x03);
+ Csd->crc = (CSD_Tab[15] & 0xFE) >> 1;
+ Csd->Reserved5 = (CSD_Tab[15] & 0x01);
+
+ retr = BSP_SD_OK;
+ }
+ }
+
+ /* Send dummy byte: 8 Clock pulses of delay */
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+
+ /* Return the reponse */
+ return retr;
+}
+
+/**
+ * @brief Reads the SD card CID register.
+ * Reading the contents of the CID register in SPI mode is a simple
+ * read-block transaction.
+ * @param Cid: pointer on an CID register structure
+ * @retval SD status
+ */
+uint8_t SD_GetCIDRegister(SD_CID* Cid) {
+ uint32_t counter = 0;
+ uint8_t retr = BSP_SD_ERROR;
+ uint8_t CID_Tab[16];
+ SD_CmdAnswer_typedef response;
+
+ /* Send CMD10 (CID register) and Wait for response in the R1 format (0x00 is no errors) */
+ response = SD_SendCmd(SD_CMD_SEND_CID, 0, 0xFF, SD_ANSWER_R1_EXPECTED);
+ if(response.r1 == SD_R1_NO_ERROR) {
+ if(SD_WaitData(SD_TOKEN_START_DATA_SINGLE_BLOCK_READ) == BSP_SD_OK) {
+ /* Store CID register value on CID_Tab */
+ for(counter = 0; counter < 16; counter++) {
+ CID_Tab[counter] = SD_IO_WriteByte(SD_DUMMY_BYTE);
+ }
+
+ /* Get CRC bytes (not really needed by us, but required by SD) */
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+
+ /* Byte 0 */
+ Cid->ManufacturerID = CID_Tab[0];
+
+ /* Byte 1 */
+ Cid->OEM_AppliID = CID_Tab[1] << 8;
+
+ /* Byte 2 */
+ Cid->OEM_AppliID |= CID_Tab[2];
+
+ /* Byte 3 */
+ Cid->ProdName1 = CID_Tab[3] << 24;
+
+ /* Byte 4 */
+ Cid->ProdName1 |= CID_Tab[4] << 16;
+
+ /* Byte 5 */
+ Cid->ProdName1 |= CID_Tab[5] << 8;
+
+ /* Byte 6 */
+ Cid->ProdName1 |= CID_Tab[6];
+
+ /* Byte 7 */
+ Cid->ProdName2 = CID_Tab[7];
+
+ /* Byte 8 */
+ Cid->ProdRev = CID_Tab[8];
+
+ /* Byte 9 */
+ Cid->ProdSN = CID_Tab[9] << 24;
+
+ /* Byte 10 */
+ Cid->ProdSN |= CID_Tab[10] << 16;
+
+ /* Byte 11 */
+ Cid->ProdSN |= CID_Tab[11] << 8;
+
+ /* Byte 12 */
+ Cid->ProdSN |= CID_Tab[12];
+
+ /* Byte 13 */
+ Cid->Reserved1 |= (CID_Tab[13] & 0xF0) >> 4;
+ Cid->ManufactDate = (CID_Tab[13] & 0x0F) << 8;
+
+ /* Byte 14 */
+ Cid->ManufactDate |= CID_Tab[14];
+
+ /* Byte 15 */
+ Cid->CID_CRC = (CID_Tab[15] & 0xFE) >> 1;
+ Cid->Reserved2 = 1;
+
+ retr = BSP_SD_OK;
+ }
+ }
+
+ /* Send dummy byte: 8 Clock pulses of delay */
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+
+ /* Return the reponse */
+ return retr;
+}
+
+/**
+ * @brief Sends 5 bytes command to the SD card and get response
+ * @param Cmd: The user expected command to send to SD card.
+ * @param Arg: The command argument.
+ * @param Crc: The CRC.
+ * @param Answer: SD_ANSWER_NOT_EXPECTED or SD_ANSWER_EXPECTED
+ * @retval SD status
+ */
+SD_CmdAnswer_typedef SD_SendCmd(uint8_t Cmd, uint32_t Arg, uint8_t Crc, uint8_t Answer) {
+ uint8_t frame[SD_CMD_LENGTH], frameout[SD_CMD_LENGTH];
+ SD_CmdAnswer_typedef retr = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF};
+
+ /* R1 Lenght = NCS(0)+ 6 Bytes command + NCR(min1 max8) + 1 Bytes answer + NEC(0) = 15bytes */
+ /* R1b identical to R1 + Busy information */
+ /* R2 Lenght = NCS(0)+ 6 Bytes command + NCR(min1 max8) + 2 Bytes answer + NEC(0) = 16bytes */
+
+ /* Prepare Frame to send */
+ frame[0] = (Cmd | 0x40); /* Construct byte 1 */
+ frame[1] = (uint8_t)(Arg >> 24); /* Construct byte 2 */
+ frame[2] = (uint8_t)(Arg >> 16); /* Construct byte 3 */
+ frame[3] = (uint8_t)(Arg >> 8); /* Construct byte 4 */
+ frame[4] = (uint8_t)(Arg); /* Construct byte 5 */
+ frame[5] = (Crc | 0x01); /* Construct byte 6 */
+
+ /* Send the command */
+ SD_IO_CSState(0);
+ SD_IO_WriteReadData(frame, frameout, SD_CMD_LENGTH); /* Send the Cmd bytes */
+
+ switch(Answer) {
+ case SD_ANSWER_R1_EXPECTED:
+ retr.r1 = SD_ReadData();
+ break;
+ case SD_ANSWER_R1B_EXPECTED:
+ retr.r1 = SD_ReadData();
+ retr.r2 = SD_IO_WriteByte(SD_DUMMY_BYTE);
+ /* Set CS High */
+ SD_IO_CSState(1);
+ HAL_Delay(1);
+ /* Set CS Low */
+ SD_IO_CSState(0);
+
+ /* Wait IO line return 0xFF */
+ while(SD_IO_WriteByte(SD_DUMMY_BYTE) != 0xFF)
+ ;
+ break;
+ case SD_ANSWER_R2_EXPECTED:
+ retr.r1 = SD_ReadData();
+ retr.r2 = SD_IO_WriteByte(SD_DUMMY_BYTE);
+ break;
+ case SD_ANSWER_R3_EXPECTED:
+ case SD_ANSWER_R7_EXPECTED:
+ retr.r1 = SD_ReadData();
+ retr.r2 = SD_IO_WriteByte(SD_DUMMY_BYTE);
+ retr.r3 = SD_IO_WriteByte(SD_DUMMY_BYTE);
+ retr.r4 = SD_IO_WriteByte(SD_DUMMY_BYTE);
+ retr.r5 = SD_IO_WriteByte(SD_DUMMY_BYTE);
+ break;
+ default:
+ break;
+ }
+ return retr;
+}
+
+/**
+ * @brief Gets the SD card data response and check the busy flag.
+ * @param None
+ * @retval The SD status: Read data response xxx01
+ * - status 010: Data accecpted
+ * - status 101: Data rejected due to a crc error
+ * - status 110: Data rejected due to a Write error.
+ * - status 111: Data rejected due to other error.
+ */
+uint8_t SD_GetDataResponse(void) {
+ uint8_t dataresponse;
+ uint8_t rvalue = SD_DATA_OTHER_ERROR;
+
+ dataresponse = SD_IO_WriteByte(SD_DUMMY_BYTE);
+ SD_IO_WriteByte(SD_DUMMY_BYTE); /* read the busy response byte*/
+
+ /* Mask unused bits */
+ switch(dataresponse & 0x1F) {
+ case SD_DATA_OK:
+ rvalue = SD_DATA_OK;
+
+ /* Set CS High */
+ SD_IO_CSState(1);
+ /* Set CS Low */
+ SD_IO_CSState(0);
+
+ /* Wait IO line return 0xFF */
+ while(SD_IO_WriteByte(SD_DUMMY_BYTE) != 0xFF)
+ ;
+ break;
+ case SD_DATA_CRC_ERROR:
+ rvalue = SD_DATA_CRC_ERROR;
+ break;
+ case SD_DATA_WRITE_ERROR:
+ rvalue = SD_DATA_WRITE_ERROR;
+ break;
+ default:
+ break;
+ }
+
+ /* Return response */
+ return rvalue;
+}
+
+/**
+ * @brief Put the SD in Idle state.
+ * @param None
+ * @retval SD status
+ */
+uint8_t SD_GoIdleState(void) {
+ SD_CmdAnswer_typedef response;
+ __IO uint8_t counter = 0;
+ /* Send CMD0 (SD_CMD_GO_IDLE_STATE) to put SD in SPI mode and
+ wait for In Idle State Response (R1 Format) equal to 0x01 */
+ do {
+ counter++;
+ response = SD_SendCmd(SD_CMD_GO_IDLE_STATE, 0, 0x95, SD_ANSWER_R1_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ if(counter >= SD_MAX_TRY) {
+ return BSP_SD_ERROR;
+ }
+ } while(response.r1 != SD_R1_IN_IDLE_STATE);
+
+ /* Send CMD8 (SD_CMD_SEND_IF_COND) to check the power supply status
+ and wait until response (R7 Format) equal to 0xAA and */
+ response = SD_SendCmd(SD_CMD_SEND_IF_COND, 0x1AA, 0x87, SD_ANSWER_R7_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ if((response.r1 & SD_R1_ILLEGAL_COMMAND) == SD_R1_ILLEGAL_COMMAND) {
+ /* initialise card V1 */
+ do {
+ /* initialise card V1 */
+ /* Send CMD55 (SD_CMD_APP_CMD) before any ACMD command: R1 response (0x00: no errors) */
+ response = SD_SendCmd(SD_CMD_APP_CMD, 0x00000000, 0xFF, SD_ANSWER_R1_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+
+ /* Send ACMD41 (SD_CMD_SD_APP_OP_COND) to initialize SDHC or SDXC cards: R1 response (0x00: no errors) */
+ response = SD_SendCmd(SD_CMD_SD_APP_OP_COND, 0x00000000, 0xFF, SD_ANSWER_R1_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ } while(response.r1 == SD_R1_IN_IDLE_STATE);
+ flag_SDHC = 0;
+ } else if(response.r1 == SD_R1_IN_IDLE_STATE) {
+ /* initialise card V2 */
+ do {
+ /* Send CMD55 (SD_CMD_APP_CMD) before any ACMD command: R1 response (0x00: no errors) */
+ response = SD_SendCmd(SD_CMD_APP_CMD, 0, 0xFF, SD_ANSWER_R1_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+
+ /* Send ACMD41 (SD_CMD_SD_APP_OP_COND) to initialize SDHC or SDXC cards: R1 response (0x00: no errors) */
+ response = SD_SendCmd(SD_CMD_SD_APP_OP_COND, 0x40000000, 0xFF, SD_ANSWER_R1_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ } while(response.r1 == SD_R1_IN_IDLE_STATE);
+
+ if((response.r1 & SD_R1_ILLEGAL_COMMAND) == SD_R1_ILLEGAL_COMMAND) {
+ do {
+ /* Send CMD55 (SD_CMD_APP_CMD) before any ACMD command: R1 response (0x00: no errors) */
+ response = SD_SendCmd(SD_CMD_APP_CMD, 0, 0xFF, SD_ANSWER_R1_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ if(response.r1 != SD_R1_IN_IDLE_STATE) {
+ return BSP_SD_ERROR;
+ }
+ /* Send ACMD41 (SD_CMD_SD_APP_OP_COND) to initialize SDHC or SDXC cards: R1 response (0x00: no errors) */
+ response =
+ SD_SendCmd(SD_CMD_SD_APP_OP_COND, 0x00000000, 0xFF, SD_ANSWER_R1_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ } while(response.r1 == SD_R1_IN_IDLE_STATE);
+ }
+
+ /* Send CMD58 (SD_CMD_READ_OCR) to initialize SDHC or SDXC cards: R3 response (0x00: no errors) */
+ response = SD_SendCmd(SD_CMD_READ_OCR, 0x00000000, 0xFF, SD_ANSWER_R3_EXPECTED);
+ SD_IO_CSState(1);
+ SD_IO_WriteByte(SD_DUMMY_BYTE);
+ if(response.r1 != SD_R1_NO_ERROR) {
+ return BSP_SD_ERROR;
+ }
+ flag_SDHC = (response.r2 & 0x40) >> 6;
+ } else {
+ return BSP_SD_ERROR;
+ }
+
+ return BSP_SD_OK;
+}
+
+/**
+ * @brief Waits a data until a value different from SD_DUMMY_BITE
+ * @param None
+ * @retval the value read
+ */
+uint8_t SD_ReadData(void) {
+ uint8_t timeout = 0x08;
+ uint8_t readvalue;
+
+ /* Check if response is got or a timeout is happen */
+ do {
+ readvalue = SD_IO_WriteByte(SD_DUMMY_BYTE);
+ timeout--;
+
+ } while((readvalue == SD_DUMMY_BYTE) && timeout);
+
+ /* Right response got */
+ return readvalue;
+}
+
+/**
+ * @brief Waits a data from the SD card
+ * @param data : Expected data from the SD card
+ * @retval BSP_SD_OK or BSP_SD_TIMEOUT
+ */
+uint8_t SD_WaitData(uint8_t data) {
+ uint16_t timeout = 0xFFFF;
+ uint8_t readvalue;
+
+ /* Check if response is got or a timeout is happen */
+
+ do {
+ readvalue = SD_IO_WriteByte(SD_DUMMY_BYTE);
+ timeout--;
+ } while((readvalue != data) && timeout);
+
+ if(timeout == 0) {
+ /* After time out */
+ return BSP_SD_TIMEOUT;
+ }
+
+ /* Right response got */
+ return BSP_SD_OK;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/fatfs/stm32_adafruit_sd.h b/firmware/targets/f3/Src/fatfs/stm32_adafruit_sd.h
new file mode 100644
index 00000000..3351e6b9
--- /dev/null
+++ b/firmware/targets/f3/Src/fatfs/stm32_adafruit_sd.h
@@ -0,0 +1,251 @@
+/**
+ ******************************************************************************
+ * @file stm32_adafruit_sd.h
+ * @author MCD Application Team
+ * @version V3.0.0
+ * @date 23-December-2016
+ * @brief This file contains the common defines and functions prototypes for
+ * the stm32_adafruit_sd.c driver.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2016 STMicroelectronics
+ *
+ * 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.
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32_ADAFRUIT_SD_H
+#define __STM32_ADAFRUIT_SD_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include
+
+/** @addtogroup BSP
+ * @{
+ */
+#define __IO volatile
+
+/** @addtogroup STM32_ADAFRUIT
+ * @{
+ */
+
+/** @defgroup STM32_ADAFRUIT_SD
+ * @{
+ */
+
+/** @defgroup STM32_ADAFRUIT_SD_Exported_Types
+ * @{
+ */
+
+/**
+ * @brief SD status structure definition
+ */
+enum {
+ BSP_SD_OK = 0x00,
+ MSD_OK = 0x00,
+ BSP_SD_ERROR = 0x01,
+ BSP_SD_TIMEOUT
+};
+
+typedef struct
+{
+ uint8_t Reserved1:2; /* Reserved */
+ uint16_t DeviceSize:12; /* Device Size */
+ uint8_t MaxRdCurrentVDDMin:3; /* Max. read current @ VDD min */
+ uint8_t MaxRdCurrentVDDMax:3; /* Max. read current @ VDD max */
+ uint8_t MaxWrCurrentVDDMin:3; /* Max. write current @ VDD min */
+ uint8_t MaxWrCurrentVDDMax:3; /* Max. write current @ VDD max */
+ uint8_t DeviceSizeMul:3; /* Device size multiplier */
+} struct_v1;
+
+
+typedef struct
+{
+ uint8_t Reserved1:6; /* Reserved */
+ uint32_t DeviceSize:22; /* Device Size */
+ uint8_t Reserved2:1; /* Reserved */
+} struct_v2;
+
+/**
+ * @brief Card Specific Data: CSD Register
+ */
+typedef struct
+{
+ /* Header part */
+ uint8_t CSDStruct:2; /* CSD structure */
+ uint8_t Reserved1:6; /* Reserved */
+ uint8_t TAAC:8; /* Data read access-time 1 */
+ uint8_t NSAC:8; /* Data read access-time 2 in CLK cycles */
+ uint8_t MaxBusClkFrec:8; /* Max. bus clock frequency */
+ uint16_t CardComdClasses:12; /* Card command classes */
+ uint8_t RdBlockLen:4; /* Max. read data block length */
+ uint8_t PartBlockRead:1; /* Partial blocks for read allowed */
+ uint8_t WrBlockMisalign:1; /* Write block misalignment */
+ uint8_t RdBlockMisalign:1; /* Read block misalignment */
+ uint8_t DSRImpl:1; /* DSR implemented */
+
+ /* v1 or v2 struct */
+ union csd_version {
+ struct_v1 v1;
+ struct_v2 v2;
+ } version;
+
+ uint8_t EraseSingleBlockEnable:1; /* Erase single block enable */
+ uint8_t EraseSectorSize:7; /* Erase group size multiplier */
+ uint8_t WrProtectGrSize:7; /* Write protect group size */
+ uint8_t WrProtectGrEnable:1; /* Write protect group enable */
+ uint8_t Reserved2:2; /* Reserved */
+ uint8_t WrSpeedFact:3; /* Write speed factor */
+ uint8_t MaxWrBlockLen:4; /* Max. write data block length */
+ uint8_t WriteBlockPartial:1; /* Partial blocks for write allowed */
+ uint8_t Reserved3:5; /* Reserved */
+ uint8_t FileFormatGrouop:1; /* File format group */
+ uint8_t CopyFlag:1; /* Copy flag (OTP) */
+ uint8_t PermWrProtect:1; /* Permanent write protection */
+ uint8_t TempWrProtect:1; /* Temporary write protection */
+ uint8_t FileFormat:2; /* File Format */
+ uint8_t Reserved4:2; /* Reserved */
+ uint8_t crc:7; /* Reserved */
+ uint8_t Reserved5:1; /* always 1*/
+
+} SD_CSD;
+
+/**
+ * @brief Card Identification Data: CID Register
+ */
+typedef struct
+{
+ __IO uint8_t ManufacturerID; /* ManufacturerID */
+ __IO uint16_t OEM_AppliID; /* OEM/Application ID */
+ __IO uint32_t ProdName1; /* Product Name part1 */
+ __IO uint8_t ProdName2; /* Product Name part2*/
+ __IO uint8_t ProdRev; /* Product Revision */
+ __IO uint32_t ProdSN; /* Product Serial Number */
+ __IO uint8_t Reserved1; /* Reserved1 */
+ __IO uint16_t ManufactDate; /* Manufacturing Date */
+ __IO uint8_t CID_CRC; /* CID CRC */
+ __IO uint8_t Reserved2; /* always 1 */
+} SD_CID;
+
+/**
+ * @brief SD Card information
+ */
+typedef struct
+{
+ SD_CSD Csd;
+ SD_CID Cid;
+ uint32_t CardCapacity; /*!< Card Capacity */
+ uint32_t CardBlockSize; /*!< Card Block Size */
+ uint32_t LogBlockNbr; /*!< Specifies the Card logical Capacity in blocks */
+ uint32_t LogBlockSize; /*!< Specifies logical block size in bytes */
+} SD_CardInfo;
+
+/**
+ * @}
+ */
+
+/** @defgroup STM32_ADAFRUIT_SPI_SD_Exported_Constants
+ * @{
+ */
+
+/**
+ * @brief Block Size
+ */
+#define SD_BLOCK_SIZE 0x200
+
+/**
+ * @brief SD detection on its memory slot
+ */
+#define SD_PRESENT ((uint8_t)0x01)
+#define SD_NOT_PRESENT ((uint8_t)0x00)
+
+#define SD_DATATIMEOUT ((uint32_t)100000000)
+
+/**
+ * @brief SD Card information structure
+ */
+#define BSP_SD_CardInfo SD_CardInfo
+
+/**
+ * @}
+ */
+
+/** @defgroup STM32_ADAFRUIT_SD_Exported_Macro
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup STM32_ADAFRUIT_SD_Exported_Functions
+ * @{
+ */
+uint8_t BSP_SD_Init(void);
+uint8_t BSP_SD_ReadBlocks(uint32_t *pData, uint32_t ReadAddr, uint32_t NumOfBlocks, uint32_t Timeout);
+uint8_t BSP_SD_WriteBlocks(uint32_t *pData, uint32_t WriteAddr, uint32_t NumOfBlocks, uint32_t Timeout);
+uint8_t BSP_SD_Erase(uint32_t StartAddr, uint32_t EndAddr);
+uint8_t BSP_SD_GetCardState(void);
+uint8_t BSP_SD_GetCardInfo(SD_CardInfo *pCardInfo);
+
+/* Link functions for SD Card peripheral*/
+void SD_SPI_Slow_Init(void);
+void SD_SPI_Fast_Init(void);
+void SD_IO_Init(void);
+void SD_IO_CSState(uint8_t state);
+void SD_IO_WriteReadData(const uint8_t *DataIn, uint8_t *DataOut, uint16_t DataLength);
+uint8_t SD_IO_WriteByte(uint8_t Data);
+
+/* Link function for HAL delay */
+void HAL_Delay(__IO uint32_t Delay);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32_ADAFRUIT_SD_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/fatfs/syscall.c b/firmware/targets/f3/Src/fatfs/syscall.c
new file mode 100644
index 00000000..8d488dc7
--- /dev/null
+++ b/firmware/targets/f3/Src/fatfs/syscall.c
@@ -0,0 +1,138 @@
+/*------------------------------------------------------------------------*/
+/* Sample code of OS dependent controls for FatFs */
+/* (C)ChaN, 2014 */
+/* Portions COPYRIGHT 2017 STMicroelectronics */
+/* Portions Copyright (C) 2014, ChaN, all right reserved */
+/*------------------------------------------------------------------------*/
+
+/**
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2017 STMicroelectronics. All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+**/
+
+
+
+#include "fatfs/ff.h"
+
+
+#if _FS_REENTRANT
+/*------------------------------------------------------------------------*/
+/* Create a Synchronization Object */
+/*------------------------------------------------------------------------*/
+/* This function is called in f_mount() function to create a new
+/ synchronization object, such as semaphore and mutex. When a 0 is returned,
+/ the f_mount() function fails with FR_INT_ERR.
+*/
+
+int ff_cre_syncobj ( /* 1:Function succeeded, 0:Could not create the sync object */
+ BYTE vol, /* Corresponding volume (logical drive number) */
+ _SYNC_t *sobj /* Pointer to return the created sync object */
+)
+{
+
+ int ret;
+
+ //osSemaphoreDef(SEM);
+ //*sobj = osSemaphoreCreate(osSemaphore(SEM), 1);
+ *sobj = osMutexNew(NULL);
+ ret = (*sobj != NULL);
+
+ return ret;
+}
+
+
+
+/*------------------------------------------------------------------------*/
+/* Delete a Synchronization Object */
+/*------------------------------------------------------------------------*/
+/* This function is called in f_mount() function to delete a synchronization
+/ object that created with ff_cre_syncobj() function. When a 0 is returned,
+/ the f_mount() function fails with FR_INT_ERR.
+*/
+
+int ff_del_syncobj ( /* 1:Function succeeded, 0:Could not delete due to any error */
+ _SYNC_t sobj /* Sync object tied to the logical drive to be deleted */
+)
+{
+ osMutexDelete(sobj);
+ return 1;
+}
+
+
+
+/*------------------------------------------------------------------------*/
+/* Request Grant to Access the Volume */
+/*------------------------------------------------------------------------*/
+/* This function is called on entering file functions to lock the volume.
+/ When a 0 is returned, the file function fails with FR_TIMEOUT.
+*/
+
+int ff_req_grant ( /* 1:Got a grant to access the volume, 0:Could not get a grant */
+ _SYNC_t sobj /* Sync object to wait */
+)
+{
+ int ret = 0;
+
+ if(osMutexAcquire(sobj, _FS_TIMEOUT) == osOK) {
+ ret = 1;
+ }
+
+ return ret;
+}
+
+
+
+/*------------------------------------------------------------------------*/
+/* Release Grant to Access the Volume */
+/*------------------------------------------------------------------------*/
+/* This function is called on leaving file functions to unlock the volume.
+*/
+
+void ff_rel_grant (
+ _SYNC_t sobj /* Sync object to be signaled */
+)
+{
+ osMutexRelease(sobj);
+}
+
+#endif
+
+
+
+
+#if _USE_LFN == 3 /* LFN with a working buffer on the heap */
+/*------------------------------------------------------------------------*/
+/* Allocate a memory block */
+/*------------------------------------------------------------------------*/
+/* If a NULL is returned, the file function fails with FR_NOT_ENOUGH_CORE.
+*/
+
+void* ff_memalloc ( /* Returns pointer to the allocated memory block */
+ UINT msize /* Number of bytes to allocate */
+)
+{
+ return ff_malloc(msize); /* Allocate a new memory block with POSIX API */
+}
+
+
+/*------------------------------------------------------------------------*/
+/* Free a memory block */
+/*------------------------------------------------------------------------*/
+
+void ff_memfree (
+ void* mblock /* Pointer to the memory block to free */
+)
+{
+ ff_free(mblock); /* Discard the memory block with POSIX API */
+}
+
+#endif
diff --git a/firmware/targets/f3/Src/fatfs/user_diskio.c b/firmware/targets/f3/Src/fatfs/user_diskio.c
new file mode 100644
index 00000000..843e1506
--- /dev/null
+++ b/firmware/targets/f3/Src/fatfs/user_diskio.c
@@ -0,0 +1,219 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file user_diskio.c
+ * @brief This file includes a diskio driver skeleton to be completed by the user.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+#ifdef USE_OBSOLETE_USER_CODE_SECTION_0
+/*
+ * Warning: the user section 0 is no more in use (starting from CubeMx version 4.16.0)
+ * To be suppressed in the future.
+ * Kept to ensure backward compatibility with previous CubeMx versions when
+ * migrating projects.
+ * User code previously added there should be copied in the new user sections before
+ * the section contents can be deleted.
+ */
+/* USER CODE BEGIN 0 */
+/* USER CODE END 0 */
+#endif
+
+/* USER CODE BEGIN DECL */
+
+/* Includes ------------------------------------------------------------------*/
+#include "user_diskio.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* Private variables ---------------------------------------------------------*/
+/* Disk status */
+static volatile DSTATUS Stat = STA_NOINIT;
+
+static DSTATUS User_CheckStatus(BYTE lun) {
+ Stat = STA_NOINIT;
+
+ if(BSP_SD_GetCardState() == MSD_OK) {
+ Stat &= ~STA_NOINIT;
+ }
+
+ return Stat;
+}
+/* USER CODE END DECL */
+
+/* Private function prototypes -----------------------------------------------*/
+DSTATUS USER_initialize(BYTE pdrv);
+DSTATUS USER_status(BYTE pdrv);
+DRESULT USER_read(BYTE pdrv, BYTE* buff, DWORD sector, UINT count);
+#if _USE_WRITE == 1
+DRESULT USER_write(BYTE pdrv, const BYTE* buff, DWORD sector, UINT count);
+#endif /* _USE_WRITE == 1 */
+#if _USE_IOCTL == 1
+DRESULT USER_ioctl(BYTE pdrv, BYTE cmd, void* buff);
+#endif /* _USE_IOCTL == 1 */
+
+Diskio_drvTypeDef USER_Driver = {
+ USER_initialize,
+ USER_status,
+ USER_read,
+#if _USE_WRITE
+ USER_write,
+#endif /* _USE_WRITE == 1 */
+#if _USE_IOCTL == 1
+ USER_ioctl,
+#endif /* _USE_IOCTL == 1 */
+};
+
+/* Private functions ---------------------------------------------------------*/
+
+/**
+ * @brief Initializes a Drive
+ * @param pdrv: Physical drive number (0..)
+ * @retval DSTATUS: Operation status
+ */
+DSTATUS USER_initialize(BYTE pdrv /* Physical drive nmuber to identify the drive */
+) {
+ /* USER CODE BEGIN INIT */
+ return User_CheckStatus(pdrv);
+ /* USER CODE END INIT */
+}
+
+/**
+ * @brief Gets Disk Status
+ * @param pdrv: Physical drive number (0..)
+ * @retval DSTATUS: Operation status
+ */
+DSTATUS USER_status(BYTE pdrv /* Physical drive number to identify the drive */
+) {
+ /* USER CODE BEGIN STATUS */
+ return Stat;
+ /* USER CODE END STATUS */
+}
+
+/**
+ * @brief Reads Sector(s)
+ * @param pdrv: Physical drive number (0..)
+ * @param *buff: Data buffer to store read data
+ * @param sector: Sector address (LBA)
+ * @param count: Number of sectors to read (1..128)
+ * @retval DRESULT: Operation result
+ */
+DRESULT USER_read(
+ BYTE pdrv, /* Physical drive nmuber to identify the drive */
+ BYTE* buff, /* Data buffer to store read data */
+ DWORD sector, /* Sector address in LBA */
+ UINT count /* Number of sectors to read */
+) {
+ /* USER CODE BEGIN READ */
+ DRESULT res = RES_ERROR;
+ if(BSP_SD_ReadBlocks((uint32_t*)buff, (uint32_t)(sector), count, SD_DATATIMEOUT) == MSD_OK) {
+ /* wait until the read operation is finished */
+ while(BSP_SD_GetCardState() != MSD_OK) {
+ }
+ res = RES_OK;
+ }
+
+ return res;
+ /* USER CODE END READ */
+}
+
+/**
+ * @brief Writes Sector(s)
+ * @param pdrv: Physical drive number (0..)
+ * @param *buff: Data to be written
+ * @param sector: Sector address (LBA)
+ * @param count: Number of sectors to write (1..128)
+ * @retval DRESULT: Operation result
+ */
+#if _USE_WRITE == 1
+DRESULT USER_write(
+ BYTE pdrv, /* Physical drive nmuber to identify the drive */
+ const BYTE* buff, /* Data to be written */
+ DWORD sector, /* Sector address in LBA */
+ UINT count /* Number of sectors to write */
+) {
+ /* USER CODE BEGIN WRITE */
+ /* USER CODE HERE */
+ DRESULT res = RES_ERROR;
+
+ if(BSP_SD_WriteBlocks((uint32_t*)buff, (uint32_t)(sector), count, SD_DATATIMEOUT) == MSD_OK) {
+ /* wait until the Write operation is finished */
+ while(BSP_SD_GetCardState() != MSD_OK) {
+ }
+ res = RES_OK;
+ }
+
+ return res;
+ /* USER CODE END WRITE */
+}
+#endif /* _USE_WRITE == 1 */
+
+/**
+ * @brief I/O control operation
+ * @param pdrv: Physical drive number (0..)
+ * @param cmd: Control code
+ * @param *buff: Buffer to send/receive control data
+ * @retval DRESULT: Operation result
+ */
+#if _USE_IOCTL == 1
+DRESULT USER_ioctl(
+ BYTE pdrv, /* Physical drive nmuber (0..) */
+ BYTE cmd, /* Control code */
+ void* buff /* Buffer to send/receive control data */
+) {
+ /* USER CODE BEGIN IOCTL */
+ DRESULT res = RES_ERROR;
+ BSP_SD_CardInfo CardInfo;
+
+ if(Stat & STA_NOINIT) return RES_NOTRDY;
+
+ switch(cmd) {
+ /* Make sure that no pending write process */
+ case CTRL_SYNC:
+ res = RES_OK;
+ break;
+
+ /* Get number of sectors on the disk (DWORD) */
+ case GET_SECTOR_COUNT:
+ BSP_SD_GetCardInfo(&CardInfo);
+ *(DWORD*)buff = CardInfo.LogBlockNbr;
+ res = RES_OK;
+ break;
+
+ /* Get R/W sector size (WORD) */
+ case GET_SECTOR_SIZE:
+ BSP_SD_GetCardInfo(&CardInfo);
+ *(WORD*)buff = CardInfo.LogBlockSize;
+ res = RES_OK;
+ break;
+
+ /* Get erase block size in unit of sector (DWORD) */
+ case GET_BLOCK_SIZE:
+ BSP_SD_GetCardInfo(&CardInfo);
+ *(DWORD*)buff = CardInfo.LogBlockSize;
+ res = RES_OK;
+ break;
+
+ default:
+ res = RES_PARERR;
+ }
+
+ return res;
+ /* USER CODE END IOCTL */
+}
+#endif /* _USE_IOCTL == 1 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
\ No newline at end of file
diff --git a/firmware/targets/f3/Src/fatfs/user_diskio.h b/firmware/targets/f3/Src/fatfs/user_diskio.h
new file mode 100644
index 00000000..177723be
--- /dev/null
+++ b/firmware/targets/f3/Src/fatfs/user_diskio.h
@@ -0,0 +1,48 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file user_diskio.h
+ * @brief This file contains the common defines and functions prototypes for
+ * the user_diskio driver.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USER_DISKIO_H
+#define __USER_DISKIO_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* USER CODE BEGIN 0 */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32_adafruit_sd.h"
+#include "fatfs/ff_gen_drv.h"
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+extern Diskio_drvTypeDef USER_Driver;
+
+/* USER CODE END 0 */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USER_DISKIO_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/freertos-openocd.c b/firmware/targets/f3/Src/freertos-openocd.c
new file mode 100644
index 00000000..abde4411
--- /dev/null
+++ b/firmware/targets/f3/Src/freertos-openocd.c
@@ -0,0 +1,21 @@
+
+/*
+ * Since at least FreeRTOS V7.5.3 uxTopUsedPriority is no longer
+ * present in the kernel, so it has to be supplied by other means for
+ * OpenOCD's threads awareness.
+ *
+ * Add this file to your project, and, if you're using --gc-sections,
+ * ``--undefined=uxTopUsedPriority'' (or
+ * ``-Wl,--undefined=uxTopUsedPriority'' when using gcc for final
+ * linking) to your LDFLAGS; same with all the other symbols you need.
+ */
+
+#include "FreeRTOS.h"
+
+#ifdef __GNUC__
+#define USED __attribute__((used))
+#else
+#define USED
+#endif
+
+const int USED uxTopUsedPriority = configMAX_PRIORITIES - 1;
\ No newline at end of file
diff --git a/firmware/targets/f3/Src/gpio.c b/firmware/targets/f3/Src/gpio.c
new file mode 100644
index 00000000..100209d9
--- /dev/null
+++ b/firmware/targets/f3/Src/gpio.c
@@ -0,0 +1,190 @@
+/**
+ ******************************************************************************
+ * File Name : gpio.c
+ * Description : This file provides code for the configuration
+ * of all used GPIO pins.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "gpio.h"
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/*----------------------------------------------------------------------------*/
+/* Configure GPIO */
+/*----------------------------------------------------------------------------*/
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/** Configure pins as
+ * Analog
+ * Input
+ * Output
+ * EVENT_OUT
+ * EXTI
+*/
+void MX_GPIO_Init(void)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /* GPIO Ports Clock Enable */
+ __HAL_RCC_GPIOC_CLK_ENABLE();
+ __HAL_RCC_GPIOH_CLK_ENABLE();
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ __HAL_RCC_GPIOE_CLK_ENABLE();
+ __HAL_RCC_GPIOD_CLK_ENABLE();
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(GPIOA, LED_RED_Pin|LED_GREEN_Pin|LED_BLUE_Pin, GPIO_PIN_SET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(DISPLAY_RST_GPIO_Port, DISPLAY_RST_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(NFC_CS_GPIO_Port, NFC_CS_Pin, GPIO_PIN_SET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(DISPLAY_DI_GPIO_Port, DISPLAY_DI_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(DISPLAY_BACKLIGHT_GPIO_Port, DISPLAY_BACKLIGHT_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(GPIOC, DISPLAY_CS_Pin|SD_CS_Pin, GPIO_PIN_SET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(CC1101_CS_GPIO_Port, CC1101_CS_Pin, GPIO_PIN_SET);
+
+ /*Configure GPIO pins : PCPin PCPin */
+ GPIO_InitStruct.Pin = BUTTON_BACK_Pin|BUTTON_OK_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING_FALLING;
+ GPIO_InitStruct.Pull = GPIO_PULLUP;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = BOOT0_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(BOOT0_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : PCPin PCPin PCPin PCPin */
+ GPIO_InitStruct.Pin = PC0_Pin|PC1_Pin|PC3_Pin|PC10_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : PAPin PAPin PAPin */
+ GPIO_InitStruct.Pin = LED_RED_Pin|LED_GREEN_Pin|LED_BLUE_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_OD;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : PAPin PAPin PAPin PAPin */
+ GPIO_InitStruct.Pin = PA4_Pin|PA5_Pin|PA6_Pin|PA7_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = RFID_PULL_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(RFID_PULL_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = CC1101_G0_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(CC1101_G0_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : PBPin PBPin */
+ GPIO_InitStruct.Pin = PB2_Pin|iBTN_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : PBPin PBPin PBPin PBPin */
+ GPIO_InitStruct.Pin = BUTTON_UP_Pin|BUTTON_LEFT_Pin|BUTTON_DOWN_Pin|BUTTON_RIGHT_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING_FALLING;
+ GPIO_InitStruct.Pull = GPIO_PULLUP;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = DISPLAY_RST_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(DISPLAY_RST_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = NFC_CS_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ HAL_GPIO_Init(NFC_CS_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : PCPin PCPin */
+ GPIO_InitStruct.Pin = DISPLAY_DI_Pin|DISPLAY_CS_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = DISPLAY_BACKLIGHT_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_PULLDOWN;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(DISPLAY_BACKLIGHT_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = SD_CS_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ HAL_GPIO_Init(SD_CS_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = CC1101_CS_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ HAL_GPIO_Init(CC1101_CS_GPIO_Port, &GPIO_InitStruct);
+
+ /* EXTI interrupt init*/
+ HAL_NVIC_SetPriority(EXTI1_IRQn, 5, 0);
+ HAL_NVIC_EnableIRQ(EXTI1_IRQn);
+
+ HAL_NVIC_SetPriority(EXTI2_IRQn, 5, 0);
+ HAL_NVIC_EnableIRQ(EXTI2_IRQn);
+
+ HAL_NVIC_SetPriority(EXTI9_5_IRQn, 5, 0);
+ HAL_NVIC_EnableIRQ(EXTI9_5_IRQn);
+
+ HAL_NVIC_SetPriority(EXTI15_10_IRQn, 5, 0);
+ HAL_NVIC_EnableIRQ(EXTI15_10_IRQn);
+
+}
+
+/* USER CODE BEGIN 2 */
+
+/* USER CODE END 2 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/i2c.c b/firmware/targets/f3/Src/i2c.c
new file mode 100644
index 00000000..32712c56
--- /dev/null
+++ b/firmware/targets/f3/Src/i2c.c
@@ -0,0 +1,120 @@
+/**
+ ******************************************************************************
+ * File Name : I2C.c
+ * Description : This file provides code for the configuration
+ * of the I2C instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "i2c.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+I2C_HandleTypeDef hi2c1;
+
+/* I2C1 init function */
+void MX_I2C1_Init(void)
+{
+
+ hi2c1.Instance = I2C1;
+ hi2c1.Init.Timing = 0x10707DBC;
+ hi2c1.Init.OwnAddress1 = 0;
+ hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
+ hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
+ hi2c1.Init.OwnAddress2 = 0;
+ hi2c1.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
+ hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
+ hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
+ if (HAL_I2C_Init(&hi2c1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /** Configure Analogue filter
+ */
+ if (HAL_I2CEx_ConfigAnalogFilter(&hi2c1, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /** Configure Digital filter
+ */
+ if (HAL_I2CEx_ConfigDigitalFilter(&hi2c1, 0) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+
+void HAL_I2C_MspInit(I2C_HandleTypeDef* i2cHandle)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(i2cHandle->Instance==I2C1)
+ {
+ /* USER CODE BEGIN I2C1_MspInit 0 */
+
+ /* USER CODE END I2C1_MspInit 0 */
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**I2C1 GPIO Configuration
+ PA9 ------> I2C1_SCL
+ PA10 ------> I2C1_SDA
+ */
+ GPIO_InitStruct.Pin = I2C_SCL_Pin|I2C_SDA_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
+ GPIO_InitStruct.Pull = GPIO_PULLUP;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF4_I2C1;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* I2C1 clock enable */
+ __HAL_RCC_I2C1_CLK_ENABLE();
+ /* USER CODE BEGIN I2C1_MspInit 1 */
+
+ /* USER CODE END I2C1_MspInit 1 */
+ }
+}
+
+void HAL_I2C_MspDeInit(I2C_HandleTypeDef* i2cHandle)
+{
+
+ if(i2cHandle->Instance==I2C1)
+ {
+ /* USER CODE BEGIN I2C1_MspDeInit 0 */
+
+ /* USER CODE END I2C1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_I2C1_CLK_DISABLE();
+
+ /**I2C1 GPIO Configuration
+ PA9 ------> I2C1_SCL
+ PA10 ------> I2C1_SDA
+ */
+ HAL_GPIO_DeInit(I2C_SCL_GPIO_Port, I2C_SCL_Pin);
+
+ HAL_GPIO_DeInit(I2C_SDA_GPIO_Port, I2C_SDA_Pin);
+
+ /* USER CODE BEGIN I2C1_MspDeInit 1 */
+
+ /* USER CODE END I2C1_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/main.c b/firmware/targets/f3/Src/main.c
new file mode 100644
index 00000000..43f82d5a
--- /dev/null
+++ b/firmware/targets/f3/Src/main.c
@@ -0,0 +1,272 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : main.c
+ * @brief : Main program body
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+#include "cmsis_os.h"
+#include "adc.h"
+#include "comp.h"
+#include "i2c.h"
+#include "rf.h"
+#include "rtc.h"
+#include "spi.h"
+#include "tim.h"
+#include "usart.h"
+#include "usb_device.h"
+#include "gpio.h"
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+#include "fatfs/fatfs.h"
+#include "api-hal.h"
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN PTD */
+
+/* USER CODE END PTD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN PD */
+/* USER CODE END PD */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN PM */
+
+/* USER CODE END PM */
+
+/* Private variables ---------------------------------------------------------*/
+
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+void SystemClock_Config(void);
+void MX_FREERTOS_Init(void);
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* Private user code ---------------------------------------------------------*/
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/**
+ * @brief The application entry point.
+ * @retval int
+ */
+int main(void)
+{
+ /* USER CODE BEGIN 1 */
+
+ /* USER CODE END 1 */
+
+ /* MCU Configuration--------------------------------------------------------*/
+
+ /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
+ HAL_Init();
+
+ /* USER CODE BEGIN Init */
+ /* USER CODE END Init */
+
+ /* Configure the system clock */
+ SystemClock_Config();
+
+ /* USER CODE BEGIN SysInit */
+
+ /* USER CODE END SysInit */
+
+ /* Initialize all configured peripherals */
+ MX_GPIO_Init();
+ MX_ADC1_Init();
+ MX_I2C1_Init();
+ MX_RTC_Init();
+ MX_SPI1_Init();
+ MX_SPI2_Init();
+ MX_USART1_UART_Init();
+ MX_USB_Device_Init();
+ MX_TIM1_Init();
+ MX_TIM2_Init();
+ MX_TIM16_Init();
+ MX_COMP1_Init();
+ MX_RF_Init();
+ /* USER CODE BEGIN 2 */
+ MX_FATFS_Init();
+ delay_us_init_DWT();
+ /* USER CODE END 2 */
+
+ /* Init scheduler */
+ osKernelInitialize(); /* Call init function for freertos objects (in freertos.c) */
+ MX_FREERTOS_Init();
+ /* Start scheduler */
+ osKernelStart();
+
+ /* We should never get here as control is now taken by the scheduler */
+ /* Infinite loop */
+ /* USER CODE BEGIN WHILE */
+ while (1)
+ {
+ /* USER CODE END WHILE */
+
+ /* USER CODE BEGIN 3 */
+ }
+ /* USER CODE END 3 */
+}
+
+/**
+ * @brief System Clock Configuration
+ * @retval None
+ */
+void SystemClock_Config(void)
+{
+ RCC_OscInitTypeDef RCC_OscInitStruct = {0};
+ RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
+ RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
+
+ /** Configure LSE Drive Capability
+ */
+ HAL_PWR_EnableBkUpAccess();
+ __HAL_RCC_LSEDRIVE_CONFIG(RCC_LSEDRIVE_LOW);
+ /** Configure the main internal regulator output voltage
+ */
+ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
+ /** Initializes the RCC Oscillators according to the specified parameters
+ * in the RCC_OscInitTypeDef structure.
+ */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI|RCC_OSCILLATORTYPE_HSE
+ |RCC_OSCILLATORTYPE_LSE;
+ RCC_OscInitStruct.HSEState = RCC_HSE_ON;
+ RCC_OscInitStruct.LSEState = RCC_LSE_ON;
+ RCC_OscInitStruct.HSIState = RCC_HSI_ON;
+ RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
+ RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV2;
+ RCC_OscInitStruct.PLL.PLLN = 8;
+ RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
+ RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;
+ RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2;
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /** Configure the SYSCLKSource, HCLK, PCLK1 and PCLK2 clocks dividers
+ */
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK4|RCC_CLOCKTYPE_HCLK2
+ |RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
+ |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
+ RCC_ClkInitStruct.AHBCLK2Divider = RCC_SYSCLK_DIV2;
+ RCC_ClkInitStruct.AHBCLK4Divider = RCC_SYSCLK_DIV1;
+
+ if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /** Initializes the peripherals clocks
+ */
+ PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_SMPS|RCC_PERIPHCLK_RFWAKEUP
+ |RCC_PERIPHCLK_RTC|RCC_PERIPHCLK_USART1
+ |RCC_PERIPHCLK_I2C1|RCC_PERIPHCLK_USB
+ |RCC_PERIPHCLK_ADC;
+ PeriphClkInitStruct.PLLSAI1.PLLN = 6;
+ PeriphClkInitStruct.PLLSAI1.PLLP = RCC_PLLP_DIV2;
+ PeriphClkInitStruct.PLLSAI1.PLLQ = RCC_PLLQ_DIV2;
+ PeriphClkInitStruct.PLLSAI1.PLLR = RCC_PLLR_DIV2;
+ PeriphClkInitStruct.PLLSAI1.PLLSAI1ClockOut = RCC_PLLSAI1_USBCLK|RCC_PLLSAI1_ADCCLK;
+ PeriphClkInitStruct.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2;
+ PeriphClkInitStruct.I2c1ClockSelection = RCC_I2C1CLKSOURCE_PCLK1;
+ PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_PLLSAI1;
+ PeriphClkInitStruct.AdcClockSelection = RCC_ADCCLKSOURCE_PLLSAI1;
+ PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSE;
+ PeriphClkInitStruct.RFWakeUpClockSelection = RCC_RFWKPCLKSOURCE_HSE_DIV1024;
+ PeriphClkInitStruct.SmpsClockSelection = RCC_SMPSCLKSOURCE_HSE;
+ PeriphClkInitStruct.SmpsDivSelection = RCC_SMPSCLKDIV_RANGE0;
+ if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN Smps */
+
+ /* USER CODE END Smps */
+ /** Enables the Clock Security System
+ */
+ HAL_RCC_EnableCSS();
+}
+
+/* USER CODE BEGIN 4 */
+
+/* USER CODE END 4 */
+
+/**
+ * @brief Period elapsed callback in non blocking mode
+ * @note This function is called when TIM17 interrupt took place, inside
+ * HAL_TIM_IRQHandler(). It makes a direct call to HAL_IncTick() to increment
+ * a global variable "uwTick" used as application time base.
+ * @param htim : TIM handle
+ * @retval None
+ */
+void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
+{
+ /* USER CODE BEGIN Callback 0 */
+
+ /* USER CODE END Callback 0 */
+ if (htim->Instance == TIM17) {
+ HAL_IncTick();
+ }
+ /* USER CODE BEGIN Callback 1 */
+
+ /* USER CODE END Callback 1 */
+}
+
+/**
+ * @brief This function is executed in case of error occurrence.
+ * @retval None
+ */
+void Error_Handler(void)
+{
+ /* USER CODE BEGIN Error_Handler_Debug */
+ /* User can add his own implementation to report the HAL error return state */
+
+ /* USER CODE END Error_Handler_Debug */
+}
+
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief Reports the name of the source file and the source line number
+ * where the assert_param error has occurred.
+ * @param file: pointer to the source file name
+ * @param line: assert_param error line source number
+ * @retval None
+ */
+void assert_failed(uint8_t *file, uint32_t line)
+{
+ /* USER CODE BEGIN 6 */
+ /* User can add his own implementation to report the file name and line number,
+ tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+ /* USER CODE END 6 */
+}
+#endif /* USE_FULL_ASSERT */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/rf.c b/firmware/targets/f3/Src/rf.c
new file mode 100644
index 00000000..fe014fec
--- /dev/null
+++ b/firmware/targets/f3/Src/rf.c
@@ -0,0 +1,37 @@
+/**
+ ******************************************************************************
+ * File Name : RF.c
+ * Description : This file provides code for the configuration
+ * of the RF instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "rf.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/* RF init function */
+void MX_RF_Init(void)
+{
+
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/rtc.c b/firmware/targets/f3/Src/rtc.c
new file mode 100644
index 00000000..05a624b3
--- /dev/null
+++ b/firmware/targets/f3/Src/rtc.c
@@ -0,0 +1,116 @@
+/**
+ ******************************************************************************
+ * File Name : RTC.c
+ * Description : This file provides code for the configuration
+ * of the RTC instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "rtc.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+RTC_HandleTypeDef hrtc;
+
+/* RTC init function */
+void MX_RTC_Init(void)
+{
+ RTC_TimeTypeDef sTime = {0};
+ RTC_DateTypeDef sDate = {0};
+
+ /** Initialize RTC Only
+ */
+ hrtc.Instance = RTC;
+ hrtc.Init.HourFormat = RTC_HOURFORMAT_24;
+ hrtc.Init.AsynchPrediv = 127;
+ hrtc.Init.SynchPrediv = 255;
+ hrtc.Init.OutPut = RTC_OUTPUT_DISABLE;
+ hrtc.Init.OutPutPolarity = RTC_OUTPUT_POLARITY_HIGH;
+ hrtc.Init.OutPutType = RTC_OUTPUT_TYPE_OPENDRAIN;
+ hrtc.Init.OutPutRemap = RTC_OUTPUT_REMAP_NONE;
+ if (HAL_RTC_Init(&hrtc) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ /* USER CODE BEGIN Check_RTC_BKUP */
+
+ /* USER CODE END Check_RTC_BKUP */
+
+ /** Initialize RTC and set the Time and Date
+ */
+ sTime.Hours = 0x0;
+ sTime.Minutes = 0x0;
+ sTime.Seconds = 0x0;
+ sTime.SubSeconds = 0x0;
+ sTime.DayLightSaving = RTC_DAYLIGHTSAVING_NONE;
+ sTime.StoreOperation = RTC_STOREOPERATION_RESET;
+ if (HAL_RTC_SetTime(&hrtc, &sTime, RTC_FORMAT_BCD) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sDate.WeekDay = RTC_WEEKDAY_MONDAY;
+ sDate.Month = RTC_MONTH_JANUARY;
+ sDate.Date = 0x1;
+ sDate.Year = 0x0;
+
+ if (HAL_RTC_SetDate(&hrtc, &sDate, RTC_FORMAT_BCD) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+
+void HAL_RTC_MspInit(RTC_HandleTypeDef* rtcHandle)
+{
+
+ if(rtcHandle->Instance==RTC)
+ {
+ /* USER CODE BEGIN RTC_MspInit 0 */
+
+ /* USER CODE END RTC_MspInit 0 */
+ /* RTC clock enable */
+ __HAL_RCC_RTC_ENABLE();
+ __HAL_RCC_RTCAPB_CLK_ENABLE();
+ /* USER CODE BEGIN RTC_MspInit 1 */
+
+ /* USER CODE END RTC_MspInit 1 */
+ }
+}
+
+void HAL_RTC_MspDeInit(RTC_HandleTypeDef* rtcHandle)
+{
+
+ if(rtcHandle->Instance==RTC)
+ {
+ /* USER CODE BEGIN RTC_MspDeInit 0 */
+
+ /* USER CODE END RTC_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_RTC_DISABLE();
+ __HAL_RCC_RTCAPB_CLK_DISABLE();
+ /* USER CODE BEGIN RTC_MspDeInit 1 */
+
+ /* USER CODE END RTC_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/spi.c b/firmware/targets/f3/Src/spi.c
new file mode 100644
index 00000000..5eff3b00
--- /dev/null
+++ b/firmware/targets/f3/Src/spi.c
@@ -0,0 +1,290 @@
+/**
+ ******************************************************************************
+ * File Name : SPI.c
+ * Description : This file provides code for the configuration
+ * of the SPI instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "spi.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+SPI_HandleTypeDef hspi1;
+SPI_HandleTypeDef hspi2;
+
+/* SPI1 init function */
+void MX_SPI1_Init(void)
+{
+
+ hspi1.Instance = SPI1;
+ hspi1.Init.Mode = SPI_MODE_MASTER;
+ hspi1.Init.Direction = SPI_DIRECTION_2LINES;
+ hspi1.Init.DataSize = SPI_DATASIZE_8BIT;
+ hspi1.Init.CLKPolarity = SPI_POLARITY_LOW;
+ hspi1.Init.CLKPhase = SPI_PHASE_2EDGE;
+ hspi1.Init.NSS = SPI_NSS_SOFT;
+ hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16;
+ hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ hspi1.Init.TIMode = SPI_TIMODE_DISABLE;
+ hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ hspi1.Init.CRCPolynomial = 7;
+ hspi1.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
+ hspi1.Init.NSSPMode = SPI_NSS_PULSE_DISABLE;
+ if (HAL_SPI_Init(&hspi1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+/* SPI2 init function */
+void MX_SPI2_Init(void)
+{
+
+ hspi2.Instance = SPI2;
+ hspi2.Init.Mode = SPI_MODE_MASTER;
+ hspi2.Init.Direction = SPI_DIRECTION_2LINES;
+ hspi2.Init.DataSize = SPI_DATASIZE_8BIT;
+ hspi2.Init.CLKPolarity = SPI_POLARITY_LOW;
+ hspi2.Init.CLKPhase = SPI_PHASE_1EDGE;
+ hspi2.Init.NSS = SPI_NSS_SOFT;
+ hspi2.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16;
+ hspi2.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ hspi2.Init.TIMode = SPI_TIMODE_DISABLE;
+ hspi2.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ hspi2.Init.CRCPolynomial = 7;
+ hspi2.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
+ hspi2.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
+ if (HAL_SPI_Init(&hspi2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+
+void HAL_SPI_MspInit(SPI_HandleTypeDef* spiHandle)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(spiHandle->Instance==SPI1)
+ {
+ /* USER CODE BEGIN SPI1_MspInit 0 */
+
+ /* USER CODE END SPI1_MspInit 0 */
+ /* SPI1 clock enable */
+ __HAL_RCC_SPI1_CLK_ENABLE();
+
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ /**SPI1 GPIO Configuration
+ PB3 ------> SPI1_SCK
+ PB4 ------> SPI1_MISO
+ PB5 ------> SPI1_MOSI
+ */
+ GPIO_InitStruct.Pin = SPI_R_SCK_Pin|SPI_R_MISO_Pin|SPI_R_MOSI_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF5_SPI1;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN SPI1_MspInit 1 */
+
+ // SD Card need faster spi gpio
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* USER CODE END SPI1_MspInit 1 */
+ }
+ else if(spiHandle->Instance==SPI2)
+ {
+ /* USER CODE BEGIN SPI2_MspInit 0 */
+
+ /* USER CODE END SPI2_MspInit 0 */
+ /* SPI2 clock enable */
+ __HAL_RCC_SPI2_CLK_ENABLE();
+
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ __HAL_RCC_GPIOD_CLK_ENABLE();
+ /**SPI2 GPIO Configuration
+ PB15 ------> SPI2_MOSI
+ PD1 ------> SPI2_SCK
+ */
+ GPIO_InitStruct.Pin = SPI_D_MOSI_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF5_SPI2;
+ HAL_GPIO_Init(SPI_D_MOSI_GPIO_Port, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = SPI_D_SCK_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF5_SPI2;
+ HAL_GPIO_Init(SPI_D_SCK_GPIO_Port, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN SPI2_MspInit 1 */
+
+ /* USER CODE END SPI2_MspInit 1 */
+ }
+}
+
+void HAL_SPI_MspDeInit(SPI_HandleTypeDef* spiHandle)
+{
+
+ if(spiHandle->Instance==SPI1)
+ {
+ /* USER CODE BEGIN SPI1_MspDeInit 0 */
+
+ /* USER CODE END SPI1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_SPI1_CLK_DISABLE();
+
+ /**SPI1 GPIO Configuration
+ PB3 ------> SPI1_SCK
+ PB4 ------> SPI1_MISO
+ PB5 ------> SPI1_MOSI
+ */
+ HAL_GPIO_DeInit(GPIOB, SPI_R_SCK_Pin|SPI_R_MISO_Pin|SPI_R_MOSI_Pin);
+
+ /* USER CODE BEGIN SPI1_MspDeInit 1 */
+
+ /* USER CODE END SPI1_MspDeInit 1 */
+ }
+ else if(spiHandle->Instance==SPI2)
+ {
+ /* USER CODE BEGIN SPI2_MspDeInit 0 */
+
+ /* USER CODE END SPI2_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_SPI2_CLK_DISABLE();
+
+ /**SPI2 GPIO Configuration
+ PB15 ------> SPI2_MOSI
+ PD1 ------> SPI2_SCK
+ */
+ HAL_GPIO_DeInit(SPI_D_MOSI_GPIO_Port, SPI_D_MOSI_Pin);
+
+ HAL_GPIO_DeInit(SPI_D_SCK_GPIO_Port, SPI_D_SCK_Pin);
+
+ /* USER CODE BEGIN SPI2_MspDeInit 1 */
+
+ /* USER CODE END SPI2_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+void NFC_SPI_Reconfigure() {
+ if (HAL_SPI_DeInit(&SPI_R) != HAL_OK) {
+ Error_Handler();
+ }
+
+ SPI_R.Init.Mode = SPI_MODE_MASTER;
+ SPI_R.Init.Direction = SPI_DIRECTION_2LINES;
+ SPI_R.Init.DataSize = SPI_DATASIZE_8BIT;
+ SPI_R.Init.CLKPolarity = SPI_POLARITY_LOW;
+ SPI_R.Init.CLKPhase = SPI_PHASE_2EDGE;
+ SPI_R.Init.NSS = SPI_NSS_SOFT;
+ SPI_R.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8; // 8mhz, 10mhz is max
+ SPI_R.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ SPI_R.Init.TIMode = SPI_TIMODE_DISABLE;
+ SPI_R.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ SPI_R.Init.CRCPolynomial = 7;
+ SPI_R.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
+ SPI_R.Init.NSSPMode = SPI_NSS_PULSE_DISABLE;
+
+ if (HAL_SPI_Init(&SPI_R) != HAL_OK) {
+ Error_Handler();
+ }
+}
+
+void SD_SPI_Reconfigure_Slow(void) {
+ if (HAL_SPI_DeInit(&SPI_SD_HANDLE) != HAL_OK) {
+ Error_Handler();
+ }
+
+ SPI_SD_HANDLE.Init.Mode = SPI_MODE_MASTER;
+ SPI_SD_HANDLE.Init.Direction = SPI_DIRECTION_2LINES;
+ SPI_SD_HANDLE.Init.DataSize = SPI_DATASIZE_8BIT;
+ SPI_SD_HANDLE.Init.CLKPolarity = SPI_POLARITY_LOW;
+ SPI_SD_HANDLE.Init.CLKPhase = SPI_PHASE_1EDGE;
+ SPI_SD_HANDLE.Init.NSS = SPI_NSS_SOFT;
+ SPI_SD_HANDLE.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256;
+ SPI_SD_HANDLE.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ SPI_SD_HANDLE.Init.TIMode = SPI_TIMODE_DISABLE;
+ SPI_SD_HANDLE.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ SPI_SD_HANDLE.Init.CRCPolynomial = 7;
+ SPI_SD_HANDLE.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
+ SPI_SD_HANDLE.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
+
+ if(HAL_SPI_Init(&SPI_SD_HANDLE) != HAL_OK) {
+ Error_Handler();
+ }
+}
+
+void SD_SPI_Reconfigure_Fast(void) {
+ if(HAL_SPI_DeInit(&SPI_SD_HANDLE) != HAL_OK) {
+ Error_Handler();
+ }
+
+ SPI_SD_HANDLE.Init.Mode = SPI_MODE_MASTER;
+ SPI_SD_HANDLE.Init.Direction = SPI_DIRECTION_2LINES;
+ SPI_SD_HANDLE.Init.DataSize = SPI_DATASIZE_8BIT;
+ SPI_SD_HANDLE.Init.CLKPolarity = SPI_POLARITY_LOW;
+ SPI_SD_HANDLE.Init.CLKPhase = SPI_PHASE_1EDGE;
+ SPI_SD_HANDLE.Init.NSS = SPI_NSS_SOFT;
+ SPI_SD_HANDLE.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
+ SPI_SD_HANDLE.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ SPI_SD_HANDLE.Init.TIMode = SPI_TIMODE_DISABLE;
+ SPI_SD_HANDLE.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ SPI_SD_HANDLE.Init.CRCPolynomial = 7;
+ SPI_SD_HANDLE.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
+ SPI_SD_HANDLE.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
+
+ if(HAL_SPI_Init(&SPI_SD_HANDLE) != HAL_OK) {
+ Error_Handler();
+ }
+}
+
+void CC1101_SPI_Reconfigure(void) {
+ if(HAL_SPI_DeInit(&SPI_R) != HAL_OK) {
+ Error_Handler();
+ }
+
+ SPI_R.Init.Mode = SPI_MODE_MASTER;
+ SPI_R.Init.Direction = SPI_DIRECTION_2LINES;
+ SPI_R.Init.DataSize = SPI_DATASIZE_8BIT;
+ SPI_R.Init.CLKPolarity = SPI_POLARITY_LOW;
+ SPI_R.Init.CLKPhase = SPI_PHASE_1EDGE;
+ SPI_R.Init.NSS = SPI_NSS_SOFT;
+ SPI_R.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_64;
+ SPI_R.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ SPI_R.Init.TIMode = SPI_TIMODE_DISABLE;
+ SPI_R.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ SPI_R.Init.CRCPolynomial = 7;
+ SPI_R.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
+ SPI_R.Init.NSSPMode = SPI_NSS_PULSE_DISABLE;
+
+ if(HAL_SPI_Init(&SPI_R) != HAL_OK) {
+ Error_Handler();
+ }
+}
+
+/* USER CODE END 1 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/stm32wbxx_hal_msp.c b/firmware/targets/f3/Src/stm32wbxx_hal_msp.c
new file mode 100644
index 00000000..83887d1b
--- /dev/null
+++ b/firmware/targets/f3/Src/stm32wbxx_hal_msp.c
@@ -0,0 +1,88 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * File Name : stm32wbxx_hal_msp.c
+ * Description : This file provides code for the MSP Initialization
+ * and de-Initialization codes.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN TD */
+
+/* USER CODE END TD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN Define */
+
+/* USER CODE END Define */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN Macro */
+
+/* USER CODE END Macro */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* External functions --------------------------------------------------------*/
+/* USER CODE BEGIN ExternalFunctions */
+
+/* USER CODE END ExternalFunctions */
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+/**
+ * Initializes the Global MSP.
+ */
+void HAL_MspInit(void)
+{
+ /* USER CODE BEGIN MspInit 0 */
+
+ /* USER CODE END MspInit 0 */
+
+ __HAL_RCC_HSEM_CLK_ENABLE();
+
+ /* System interrupt init*/
+
+ /* Peripheral interrupt init */
+ /* HSEM_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(HSEM_IRQn, 5, 0);
+ HAL_NVIC_EnableIRQ(HSEM_IRQn);
+
+ /* USER CODE BEGIN MspInit 1 */
+
+ /* USER CODE END MspInit 1 */
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/stm32wbxx_hal_timebase_tim.c b/firmware/targets/f3/Src/stm32wbxx_hal_timebase_tim.c
new file mode 100644
index 00000000..72af9eeb
--- /dev/null
+++ b/firmware/targets/f3/Src/stm32wbxx_hal_timebase_tim.c
@@ -0,0 +1,112 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32wbxx_hal_timebase_TIM.c
+ * @brief HAL time base based on the hardware TIM.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32wbxx_hal.h"
+#include "stm32wbxx_hal_tim.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_HandleTypeDef htim17;
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/**
+ * @brief This function configures the TIM17 as a time base source.
+ * The time source is configured to have 1ms time base with a dedicated
+ * Tick interrupt priority.
+ * @note This function is called automatically at the beginning of program after
+ * reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig().
+ * @param TickPriority: Tick interrupt priority.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
+{
+ RCC_ClkInitTypeDef clkconfig;
+ uint32_t uwTimclock = 0;
+ uint32_t uwPrescalerValue = 0;
+ uint32_t pFLatency;
+ /*Configure the TIM17 IRQ priority */
+ HAL_NVIC_SetPriority(TIM1_TRG_COM_TIM17_IRQn, TickPriority ,0);
+
+ /* Enable the TIM17 global Interrupt */
+ HAL_NVIC_EnableIRQ(TIM1_TRG_COM_TIM17_IRQn);
+ /* Enable TIM17 clock */
+ __HAL_RCC_TIM17_CLK_ENABLE();
+
+ /* Get clock configuration */
+ HAL_RCC_GetClockConfig(&clkconfig, &pFLatency);
+
+ /* Compute TIM17 clock */
+ uwTimclock = HAL_RCC_GetPCLK2Freq();
+
+ /* Compute the prescaler value to have TIM17 counter clock equal to 1MHz */
+ uwPrescalerValue = (uint32_t) ((uwTimclock / 1000000) - 1);
+
+ /* Initialize TIM17 */
+ htim17.Instance = TIM17;
+
+ /* Initialize TIMx peripheral as follow:
+ + Period = [(TIM17CLK/1000) - 1]. to have a (1/1000) s time base.
+ + Prescaler = (uwTimclock/1000000 - 1) to have a 1MHz counter clock.
+ + ClockDivision = 0
+ + Counter direction = Up
+ */
+ htim17.Init.Period = (1000000 / 1000) - 1;
+ htim17.Init.Prescaler = uwPrescalerValue;
+ htim17.Init.ClockDivision = 0;
+ htim17.Init.CounterMode = TIM_COUNTERMODE_UP;
+ if(HAL_TIM_Base_Init(&htim17) == HAL_OK)
+ {
+ /* Start the TIM time Base generation in interrupt mode */
+ return HAL_TIM_Base_Start_IT(&htim17);
+ }
+
+ /* Return function status */
+ return HAL_ERROR;
+}
+
+/**
+ * @brief Suspend Tick increment.
+ * @note Disable the tick increment by disabling TIM17 update interrupt.
+ * @param None
+ * @retval None
+ */
+void HAL_SuspendTick(void)
+{
+ /* Disable TIM17 update Interrupt */
+ __HAL_TIM_DISABLE_IT(&htim17, TIM_IT_UPDATE);
+}
+
+/**
+ * @brief Resume Tick increment.
+ * @note Enable the tick increment by Enabling TIM17 update interrupt.
+ * @param None
+ * @retval None
+ */
+void HAL_ResumeTick(void)
+{
+ /* Enable TIM17 Update interrupt */
+ __HAL_TIM_ENABLE_IT(&htim17, TIM_IT_UPDATE);
+}
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/stm32wbxx_it.c b/firmware/targets/f3/Src/stm32wbxx_it.c
new file mode 100644
index 00000000..09e2a940
--- /dev/null
+++ b/firmware/targets/f3/Src/stm32wbxx_it.c
@@ -0,0 +1,286 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32wbxx_it.c
+ * @brief Interrupt Service Routines.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+#include "stm32wbxx_it.h"
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN TD */
+
+/* USER CODE END TD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN PD */
+
+/* USER CODE END PD */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN PM */
+
+/* USER CODE END PM */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* Private user code ---------------------------------------------------------*/
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/* External variables --------------------------------------------------------*/
+extern PCD_HandleTypeDef hpcd_USB_FS;
+extern TIM_HandleTypeDef htim1;
+extern TIM_HandleTypeDef htim2;
+extern TIM_HandleTypeDef htim17;
+
+/* USER CODE BEGIN EV */
+
+/* USER CODE END EV */
+
+/******************************************************************************/
+/* Cortex Processor Interruption and Exception Handlers */
+/******************************************************************************/
+/**
+ * @brief This function handles Non maskable interrupt.
+ */
+void NMI_Handler(void)
+{
+ /* USER CODE BEGIN NonMaskableInt_IRQn 0 */
+
+ /* USER CODE END NonMaskableInt_IRQn 0 */
+ HAL_RCC_NMI_IRQHandler();
+ /* USER CODE BEGIN NonMaskableInt_IRQn 1 */
+
+ /* USER CODE END NonMaskableInt_IRQn 1 */
+}
+
+/**
+ * @brief This function handles Hard fault interrupt.
+ */
+void HardFault_Handler(void)
+{
+ /* USER CODE BEGIN HardFault_IRQn 0 */
+ if ((*(volatile uint32_t *)CoreDebug_BASE) & (1 << 0)) {
+ __asm("bkpt 1");
+ }
+ /* USER CODE END HardFault_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_HardFault_IRQn 0 */
+ /* USER CODE END W1_HardFault_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles Memory management fault.
+ */
+void MemManage_Handler(void)
+{
+ /* USER CODE BEGIN MemoryManagement_IRQn 0 */
+
+ /* USER CODE END MemoryManagement_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */
+ /* USER CODE END W1_MemoryManagement_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles Prefetch fault, memory access fault.
+ */
+void BusFault_Handler(void)
+{
+ /* USER CODE BEGIN BusFault_IRQn 0 */
+
+ /* USER CODE END BusFault_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_BusFault_IRQn 0 */
+ /* USER CODE END W1_BusFault_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles Undefined instruction or illegal state.
+ */
+void UsageFault_Handler(void)
+{
+ /* USER CODE BEGIN UsageFault_IRQn 0 */
+
+ /* USER CODE END UsageFault_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_UsageFault_IRQn 0 */
+ /* USER CODE END W1_UsageFault_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles Debug monitor.
+ */
+void DebugMon_Handler(void)
+{
+ /* USER CODE BEGIN DebugMonitor_IRQn 0 */
+
+ /* USER CODE END DebugMonitor_IRQn 0 */
+ /* USER CODE BEGIN DebugMonitor_IRQn 1 */
+
+ /* USER CODE END DebugMonitor_IRQn 1 */
+}
+
+/******************************************************************************/
+/* STM32WBxx Peripheral Interrupt Handlers */
+/* Add here the Interrupt Handlers for the used peripherals. */
+/* For the available peripheral interrupt handler names, */
+/* please refer to the startup file (startup_stm32wbxx.s). */
+/******************************************************************************/
+
+/**
+ * @brief This function handles EXTI line1 interrupt.
+ */
+void EXTI1_IRQHandler(void)
+{
+ /* USER CODE BEGIN EXTI1_IRQn 0 */
+
+ /* USER CODE END EXTI1_IRQn 0 */
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_1);
+ /* USER CODE BEGIN EXTI1_IRQn 1 */
+
+ /* USER CODE END EXTI1_IRQn 1 */
+}
+
+/**
+ * @brief This function handles EXTI line2 interrupt.
+ */
+void EXTI2_IRQHandler(void)
+{
+ /* USER CODE BEGIN EXTI2_IRQn 0 */
+
+ /* USER CODE END EXTI2_IRQn 0 */
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_2);
+ /* USER CODE BEGIN EXTI2_IRQn 1 */
+
+ /* USER CODE END EXTI2_IRQn 1 */
+}
+
+/**
+ * @brief This function handles USB low priority interrupt, USB wake-up interrupt through EXTI line 28.
+ */
+void USB_LP_IRQHandler(void)
+{
+ /* USER CODE BEGIN USB_LP_IRQn 0 */
+
+ /* USER CODE END USB_LP_IRQn 0 */
+ HAL_PCD_IRQHandler(&hpcd_USB_FS);
+ /* USER CODE BEGIN USB_LP_IRQn 1 */
+
+ /* USER CODE END USB_LP_IRQn 1 */
+}
+
+/**
+ * @brief This function handles EXTI line[9:5] interrupts.
+ */
+void EXTI9_5_IRQHandler(void)
+{
+ /* USER CODE BEGIN EXTI9_5_IRQn 0 */
+
+ /* USER CODE END EXTI9_5_IRQn 0 */
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_8);
+ /* USER CODE BEGIN EXTI9_5_IRQn 1 */
+
+ /* USER CODE END EXTI9_5_IRQn 1 */
+}
+
+/**
+ * @brief This function handles TIM1 trigger and commutation interrupts and TIM17 global interrupt.
+ */
+void TIM1_TRG_COM_TIM17_IRQHandler(void)
+{
+ /* USER CODE BEGIN TIM1_TRG_COM_TIM17_IRQn 0 */
+
+ /* USER CODE END TIM1_TRG_COM_TIM17_IRQn 0 */
+ HAL_TIM_IRQHandler(&htim1);
+ HAL_TIM_IRQHandler(&htim17);
+ /* USER CODE BEGIN TIM1_TRG_COM_TIM17_IRQn 1 */
+
+ /* USER CODE END TIM1_TRG_COM_TIM17_IRQn 1 */
+}
+
+/**
+ * @brief This function handles TIM2 global interrupt.
+ */
+void TIM2_IRQHandler(void)
+{
+ /* USER CODE BEGIN TIM2_IRQn 0 */
+
+ /* USER CODE END TIM2_IRQn 0 */
+ HAL_TIM_IRQHandler(&htim2);
+ /* USER CODE BEGIN TIM2_IRQn 1 */
+
+ /* USER CODE END TIM2_IRQn 1 */
+}
+
+/**
+ * @brief This function handles EXTI line[15:10] interrupts.
+ */
+void EXTI15_10_IRQHandler(void)
+{
+ /* USER CODE BEGIN EXTI15_10_IRQn 0 */
+
+ /* USER CODE END EXTI15_10_IRQn 0 */
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_10);
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_11);
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_12);
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_13);
+ /* USER CODE BEGIN EXTI15_10_IRQn 1 */
+
+ /* USER CODE END EXTI15_10_IRQn 1 */
+}
+
+/**
+ * @brief This function handles HSEM global interrupt.
+ */
+void HSEM_IRQHandler(void)
+{
+ /* USER CODE BEGIN HSEM_IRQn 0 */
+
+ /* USER CODE END HSEM_IRQn 0 */
+ HAL_HSEM_IRQHandler();
+ /* USER CODE BEGIN HSEM_IRQn 1 */
+
+ /* USER CODE END HSEM_IRQn 1 */
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/system_stm32wbxx.c b/firmware/targets/f3/Src/system_stm32wbxx.c
new file mode 100644
index 00000000..38db6ece
--- /dev/null
+++ b/firmware/targets/f3/Src/system_stm32wbxx.c
@@ -0,0 +1,357 @@
+/**
+ ******************************************************************************
+ * @file system_stm32wbxx.c
+ * @author MCD Application Team
+ * @brief CMSIS Cortex Device Peripheral Access Layer System Source File
+ *
+ * This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32wbxx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * After each device reset the MSI (4 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32wbxx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * This file configures the system clock as follows:
+ *=============================================================================
+ *-----------------------------------------------------------------------------
+ * System Clock source | MSI
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 4000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 4000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * PLL_M | 1
+ *-----------------------------------------------------------------------------
+ * PLL_N | 8
+ *-----------------------------------------------------------------------------
+ * PLL_P | 7
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 2
+ *-----------------------------------------------------------------------------
+ * PLL_R | 2
+ *-----------------------------------------------------------------------------
+ * PLLSAI1_P | NA
+ *-----------------------------------------------------------------------------
+ * PLLSAI1_Q | NA
+ *-----------------------------------------------------------------------------
+ * PLLSAI1_R | NA
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32WBxx_system
+ * @{
+ */
+
+/** @addtogroup stm32WBxx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32wbxx.h"
+
+#if !defined (HSE_VALUE)
+ #define HSE_VALUE (32000000UL) /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#if !defined (MSI_VALUE)
+ #define MSI_VALUE (4000000UL) /*!< Value of the Internal oscillator in Hz*/
+#endif /* MSI_VALUE */
+
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE (16000000UL) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+#if !defined (LSI_VALUE)
+ #define LSI_VALUE (32000UL) /*!< Value of LSI in Hz*/
+#endif /* LSI_VALUE */
+
+#if !defined (LSE_VALUE)
+ #define LSE_VALUE (32768UL) /*!< Value of LSE in Hz*/
+#endif /* LSE_VALUE */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32WBxx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32WBxx_System_Private_Defines
+ * @{
+ */
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET OS_OFFSET /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+
+#define VECT_TAB_BASE_ADDRESS SRAM1_BASE /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+/**
+ * @}
+ */
+
+/** @addtogroup STM32WBxx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32WBxx_System_Private_Variables
+ * @{
+ */
+ /* The SystemCoreClock variable is updated in three ways:
+ 1) by calling CMSIS function SystemCoreClockUpdate()
+ 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
+ 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
+ Note: If you use this function to configure the system clock; then there
+ is no need to call the 2 first functions listed above, since SystemCoreClock
+ variable is updated automatically.
+ */
+ uint32_t SystemCoreClock = 4000000UL ; /*CPU1: M4 on MSI clock after startup (4MHz)*/
+
+ const uint32_t AHBPrescTable[16UL] = {1UL, 3UL, 5UL, 1UL, 1UL, 6UL, 10UL, 32UL, 2UL, 4UL, 8UL, 16UL, 64UL, 128UL, 256UL, 512UL};
+
+ const uint32_t APBPrescTable[8UL] = {0UL, 0UL, 0UL, 0UL, 1UL, 2UL, 3UL, 4UL};
+
+ const uint32_t MSIRangeTable[16UL] = {100000UL, 200000UL, 400000UL, 800000UL, 1000000UL, 2000000UL, \
+ 4000000UL, 8000000UL, 16000000UL, 24000000UL, 32000000UL, 48000000UL, 0UL, 0UL, 0UL, 0UL}; /* 0UL values are incorrect cases */
+
+#if defined(STM32WB55xx) || defined(STM32WB5Mxx) || defined(STM32WB35xx)
+ const uint32_t SmpsPrescalerTable[4UL][6UL]={{1UL,3UL,2UL,2UL,1UL,2UL}, \
+ {2UL,6UL,4UL,3UL,2UL,4UL}, \
+ {4UL,12UL,8UL,6UL,4UL,8UL}, \
+ {4UL,12UL,8UL,6UL,4UL,8UL}};
+#endif
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32WBxx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32WBxx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system.
+ * @param None
+ * @retval None
+ */
+void SystemInit(void)
+{
+ /* Configure the Vector Table location add offset address ------------------*/
+#if defined(VECT_TAB_SRAM) && defined(VECT_TAB_BASE_ADDRESS)
+ /* program in SRAMx */
+ SCB->VTOR = VECT_TAB_BASE_ADDRESS | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAMx for CPU1 */
+#else /* program in FLASH */
+ SCB->VTOR = VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
+#endif
+
+ /* FPU settings ------------------------------------------------------------*/
+ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ SCB->CPACR |= ((3UL << (10UL*2UL))|(3UL << (11UL*2UL))); /* set CP10 and CP11 Full Access */
+ #endif
+
+ /* Reset the RCC clock configuration to the default reset state ------------*/
+ /* Set MSION bit */
+ RCC->CR |= RCC_CR_MSION;
+
+ /* Reset CFGR register */
+ RCC->CFGR = 0x00070000U;
+
+ /* Reset PLLSAI1ON, PLLON, HSECSSON, HSEON, HSION, and MSIPLLON bits */
+ RCC->CR &= (uint32_t)0xFAF6FEFBU;
+
+ /*!< Reset LSI1 and LSI2 bits */
+ RCC->CSR &= (uint32_t)0xFFFFFFFAU;
+
+ /*!< Reset HSI48ON bit */
+ RCC->CRRCR &= (uint32_t)0xFFFFFFFEU;
+
+ /* Reset PLLCFGR register */
+ RCC->PLLCFGR = 0x22041000U;
+
+#if defined(STM32WB55xx) || defined(STM32WB5Mxx)
+ /* Reset PLLSAI1CFGR register */
+ RCC->PLLSAI1CFGR = 0x22041000U;
+#endif
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= 0xFFFBFFFFU;
+
+ /* Disable all interrupts */
+ RCC->CIER = 0x00000000;
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is MSI, SystemCoreClock will contain the MSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(***)
+ * or HSI_VALUE(*) or MSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (*) MSI_VALUE is a constant defined in stm32wbxx_hal.h file (default value
+ * 4 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSI_VALUE is a constant defined in stm32wbxx_hal_conf.h file (default value
+ * 16 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (***) HSE_VALUE is a constant defined in stm32wbxx_hal_conf.h file (default value
+ * 32 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate(void)
+{
+ uint32_t tmp, msirange, pllvco, pllr, pllsource , pllm;
+
+ /* Get MSI Range frequency--------------------------------------------------*/
+
+ /*MSI frequency range in Hz*/
+ msirange = MSIRangeTable[(RCC->CR & RCC_CR_MSIRANGE) >> RCC_CR_MSIRANGE_Pos];
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ switch (RCC->CFGR & RCC_CFGR_SWS)
+ {
+ case 0x00: /* MSI used as system clock source */
+ SystemCoreClock = msirange;
+ break;
+
+ case 0x04: /* HSI used as system clock source */
+ /* HSI used as system clock source */
+ SystemCoreClock = HSI_VALUE;
+ break;
+
+ case 0x08: /* HSE used as system clock source */
+ SystemCoreClock = HSE_VALUE;
+ break;
+
+ case 0x0C: /* PLL used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE or MSI_VALUE/ PLLM) * PLLN
+ SYSCLK = PLL_VCO / PLLR
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC);
+ pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> RCC_PLLCFGR_PLLM_Pos) + 1UL ;
+
+ if(pllsource == 0x02UL) /* HSI used as PLL clock source */
+ {
+ pllvco = (HSI_VALUE / pllm);
+ }
+ else if(pllsource == 0x03UL) /* HSE used as PLL clock source */
+ {
+ pllvco = (HSE_VALUE / pllm);
+ }
+ else /* MSI used as PLL clock source */
+ {
+ pllvco = (msirange / pllm);
+ }
+
+ pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
+ pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos) + 1UL);
+
+ SystemCoreClock = pllvco/pllr;
+ break;
+
+ default:
+ SystemCoreClock = msirange;
+ break;
+ }
+
+ /* Compute HCLK clock frequency --------------------------------------------*/
+ /* Get HCLK1 prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos)];
+ /* HCLK clock frequency */
+ SystemCoreClock = SystemCoreClock / tmp;
+
+}
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/tim.c b/firmware/targets/f3/Src/tim.c
new file mode 100644
index 00000000..f5448cb0
--- /dev/null
+++ b/firmware/targets/f3/Src/tim.c
@@ -0,0 +1,361 @@
+/**
+ ******************************************************************************
+ * File Name : TIM.c
+ * Description : This file provides code for the configuration
+ * of the TIM instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "tim.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+TIM_HandleTypeDef htim1;
+TIM_HandleTypeDef htim2;
+TIM_HandleTypeDef htim16;
+
+/* TIM1 init function */
+void MX_TIM1_Init(void)
+{
+ TIM_ClockConfigTypeDef sClockSourceConfig = {0};
+ TIM_MasterConfigTypeDef sMasterConfig = {0};
+ TIM_OC_InitTypeDef sConfigOC = {0};
+ TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
+
+ htim1.Instance = TIM1;
+ htim1.Init.Prescaler = 0;
+ htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
+ htim1.Init.Period = 65535;
+ htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+ htim1.Init.RepetitionCounter = 0;
+ htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
+ if (HAL_TIM_Base_Init(&htim1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
+ if (HAL_TIM_ConfigClockSource(&htim1, &sClockSourceConfig) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_TIM_OC_Init(&htim1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_TIM_PWM_Init(&htim1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
+ sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;
+ sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
+ if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sConfigOC.OCMode = TIM_OCMODE_TIMING;
+ sConfigOC.Pulse = 0;
+ sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
+ sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
+ sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
+ sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
+ sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
+ if (HAL_TIM_OC_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sConfigOC.OCMode = TIM_OCMODE_PWM1;
+ if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
+ sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
+ sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
+ sBreakDeadTimeConfig.DeadTime = 0;
+ sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
+ sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
+ sBreakDeadTimeConfig.BreakFilter = 0;
+ sBreakDeadTimeConfig.BreakAFMode = TIM_BREAK_AFMODE_INPUT;
+ sBreakDeadTimeConfig.Break2State = TIM_BREAK2_DISABLE;
+ sBreakDeadTimeConfig.Break2Polarity = TIM_BREAK2POLARITY_HIGH;
+ sBreakDeadTimeConfig.Break2Filter = 0;
+ sBreakDeadTimeConfig.Break2AFMode = TIM_BREAK_AFMODE_INPUT;
+ sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
+ if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ HAL_TIM_MspPostInit(&htim1);
+
+}
+/* TIM2 init function */
+void MX_TIM2_Init(void)
+{
+ TIM_ClockConfigTypeDef sClockSourceConfig = {0};
+ TIM_MasterConfigTypeDef sMasterConfig = {0};
+ TIM_IC_InitTypeDef sConfigIC = {0};
+
+ htim2.Instance = TIM2;
+ htim2.Init.Prescaler = 64-1;
+ htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
+ htim2.Init.Period = 4294967295;
+ htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+ htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
+ if (HAL_TIM_Base_Init(&htim2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
+ if (HAL_TIM_ConfigClockSource(&htim2, &sClockSourceConfig) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_TIM_IC_Init(&htim2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
+ sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
+ if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sConfigIC.ICPolarity = TIM_INPUTCHANNELPOLARITY_FALLING;
+ sConfigIC.ICSelection = TIM_ICSELECTION_DIRECTTI;
+ sConfigIC.ICPrescaler = TIM_ICPSC_DIV1;
+ sConfigIC.ICFilter = 0;
+ if (HAL_TIM_IC_ConfigChannel(&htim2, &sConfigIC, TIM_CHANNEL_1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sConfigIC.ICPolarity = TIM_INPUTCHANNELPOLARITY_RISING;
+ sConfigIC.ICSelection = TIM_ICSELECTION_INDIRECTTI;
+ if (HAL_TIM_IC_ConfigChannel(&htim2, &sConfigIC, TIM_CHANNEL_2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+/* TIM16 init function */
+void MX_TIM16_Init(void)
+{
+ TIM_OC_InitTypeDef sConfigOC = {0};
+ TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
+
+ htim16.Instance = TIM16;
+ htim16.Init.Prescaler = 500 - 1;
+ htim16.Init.CounterMode = TIM_COUNTERMODE_UP;
+ htim16.Init.Period = 291;
+ htim16.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+ htim16.Init.RepetitionCounter = 0;
+ htim16.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
+ if (HAL_TIM_Base_Init(&htim16) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_TIM_PWM_Init(&htim16) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sConfigOC.OCMode = TIM_OCMODE_PWM1;
+ sConfigOC.Pulse = 145;
+ sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
+ sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
+ sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
+ sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
+ sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
+ if (HAL_TIM_PWM_ConfigChannel(&htim16, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
+ sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
+ sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
+ sBreakDeadTimeConfig.DeadTime = 0;
+ sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
+ sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
+ sBreakDeadTimeConfig.BreakFilter = 0;
+ sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
+ if (HAL_TIMEx_ConfigBreakDeadTime(&htim16, &sBreakDeadTimeConfig) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ HAL_TIM_MspPostInit(&htim16);
+
+}
+
+void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* tim_baseHandle)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(tim_baseHandle->Instance==TIM1)
+ {
+ /* USER CODE BEGIN TIM1_MspInit 0 */
+
+ /* USER CODE END TIM1_MspInit 0 */
+ /* TIM1 clock enable */
+ __HAL_RCC_TIM1_CLK_ENABLE();
+
+ /* TIM1 interrupt Init */
+ HAL_NVIC_SetPriority(TIM1_TRG_COM_TIM17_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(TIM1_TRG_COM_TIM17_IRQn);
+ /* USER CODE BEGIN TIM1_MspInit 1 */
+
+ /* USER CODE END TIM1_MspInit 1 */
+ }
+ else if(tim_baseHandle->Instance==TIM2)
+ {
+ /* USER CODE BEGIN TIM2_MspInit 0 */
+
+ /* USER CODE END TIM2_MspInit 0 */
+ /* TIM2 clock enable */
+ __HAL_RCC_TIM2_CLK_ENABLE();
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**TIM2 GPIO Configuration
+ PA0 ------> TIM2_CH1
+ */
+ GPIO_InitStruct.Pin = IR_RX_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF1_TIM2;
+ HAL_GPIO_Init(IR_RX_GPIO_Port, &GPIO_InitStruct);
+
+ /* TIM2 interrupt Init */
+ HAL_NVIC_SetPriority(TIM2_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(TIM2_IRQn);
+ /* USER CODE BEGIN TIM2_MspInit 1 */
+
+ /* USER CODE END TIM2_MspInit 1 */
+ }
+ else if(tim_baseHandle->Instance==TIM16)
+ {
+ /* USER CODE BEGIN TIM16_MspInit 0 */
+
+ /* USER CODE END TIM16_MspInit 0 */
+ /* TIM16 clock enable */
+ __HAL_RCC_TIM16_CLK_ENABLE();
+ /* USER CODE BEGIN TIM16_MspInit 1 */
+
+ /* USER CODE END TIM16_MspInit 1 */
+ }
+}
+void HAL_TIM_MspPostInit(TIM_HandleTypeDef* timHandle)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(timHandle->Instance==TIM1)
+ {
+ /* USER CODE BEGIN TIM1_MspPostInit 0 */
+
+ /* USER CODE END TIM1_MspPostInit 0 */
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ /**TIM1 GPIO Configuration
+ PB9 ------> TIM1_CH3N
+ PB13 ------> TIM1_CH1N
+ */
+ GPIO_InitStruct.Pin = IR_TX_Pin|RFID_OUT_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF1_TIM1;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN TIM1_MspPostInit 1 */
+
+ /* USER CODE END TIM1_MspPostInit 1 */
+ }
+ else if(timHandle->Instance==TIM16)
+ {
+ /* USER CODE BEGIN TIM16_MspPostInit 0 */
+
+ /* USER CODE END TIM16_MspPostInit 0 */
+
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ /**TIM16 GPIO Configuration
+ PB8 ------> TIM16_CH1
+ */
+ GPIO_InitStruct.Pin = SPEAKER_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF14_TIM16;
+ HAL_GPIO_Init(SPEAKER_GPIO_Port, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN TIM16_MspPostInit 1 */
+
+ /* USER CODE END TIM16_MspPostInit 1 */
+ }
+
+}
+
+void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* tim_baseHandle)
+{
+
+ if(tim_baseHandle->Instance==TIM1)
+ {
+ /* USER CODE BEGIN TIM1_MspDeInit 0 */
+
+ /* USER CODE END TIM1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_TIM1_CLK_DISABLE();
+
+ /* TIM1 interrupt Deinit */
+ HAL_NVIC_DisableIRQ(TIM1_TRG_COM_TIM17_IRQn);
+ /* USER CODE BEGIN TIM1_MspDeInit 1 */
+
+ /* USER CODE END TIM1_MspDeInit 1 */
+ }
+ else if(tim_baseHandle->Instance==TIM2)
+ {
+ /* USER CODE BEGIN TIM2_MspDeInit 0 */
+
+ /* USER CODE END TIM2_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_TIM2_CLK_DISABLE();
+
+ /**TIM2 GPIO Configuration
+ PA0 ------> TIM2_CH1
+ */
+ HAL_GPIO_DeInit(IR_RX_GPIO_Port, IR_RX_Pin);
+
+ /* TIM2 interrupt Deinit */
+ HAL_NVIC_DisableIRQ(TIM2_IRQn);
+ /* USER CODE BEGIN TIM2_MspDeInit 1 */
+
+ /* USER CODE END TIM2_MspDeInit 1 */
+ }
+ else if(tim_baseHandle->Instance==TIM16)
+ {
+ /* USER CODE BEGIN TIM16_MspDeInit 0 */
+
+ /* USER CODE END TIM16_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_TIM16_CLK_DISABLE();
+ /* USER CODE BEGIN TIM16_MspDeInit 1 */
+
+ /* USER CODE END TIM16_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/usart.c b/firmware/targets/f3/Src/usart.c
new file mode 100644
index 00000000..bfe6303f
--- /dev/null
+++ b/firmware/targets/f3/Src/usart.c
@@ -0,0 +1,121 @@
+/**
+ ******************************************************************************
+ * File Name : USART.c
+ * Description : This file provides code for the configuration
+ * of the USART instances.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usart.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+UART_HandleTypeDef huart1;
+
+/* USART1 init function */
+
+void MX_USART1_UART_Init(void)
+{
+
+ huart1.Instance = USART1;
+ huart1.Init.BaudRate = 115200;
+ huart1.Init.WordLength = UART_WORDLENGTH_8B;
+ huart1.Init.StopBits = UART_STOPBITS_1;
+ huart1.Init.Parity = UART_PARITY_NONE;
+ huart1.Init.Mode = UART_MODE_TX_RX;
+ huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
+ huart1.Init.OverSampling = UART_OVERSAMPLING_16;
+ huart1.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
+ huart1.Init.ClockPrescaler = UART_PRESCALER_DIV1;
+ huart1.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
+ if (HAL_UART_Init(&huart1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_UARTEx_SetTxFifoThreshold(&huart1, UART_TXFIFO_THRESHOLD_1_8) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_UARTEx_SetRxFifoThreshold(&huart1, UART_RXFIFO_THRESHOLD_1_8) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_UARTEx_DisableFifoMode(&huart1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+
+void HAL_UART_MspInit(UART_HandleTypeDef* uartHandle)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(uartHandle->Instance==USART1)
+ {
+ /* USER CODE BEGIN USART1_MspInit 0 */
+
+ /* USER CODE END USART1_MspInit 0 */
+ /* USART1 clock enable */
+ __HAL_RCC_USART1_CLK_ENABLE();
+
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ /**USART1 GPIO Configuration
+ PB6 ------> USART1_TX
+ PB7 ------> USART1_RX
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF7_USART1;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN USART1_MspInit 1 */
+
+ /* USER CODE END USART1_MspInit 1 */
+ }
+}
+
+void HAL_UART_MspDeInit(UART_HandleTypeDef* uartHandle)
+{
+
+ if(uartHandle->Instance==USART1)
+ {
+ /* USER CODE BEGIN USART1_MspDeInit 0 */
+
+ /* USER CODE END USART1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_USART1_CLK_DISABLE();
+
+ /**USART1 GPIO Configuration
+ PB6 ------> USART1_TX
+ PB7 ------> USART1_RX
+ */
+ HAL_GPIO_DeInit(GPIOB, GPIO_PIN_6|GPIO_PIN_7);
+
+ /* USER CODE BEGIN USART1_MspDeInit 1 */
+
+ /* USER CODE END USART1_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/usb_device.c b/firmware/targets/f3/Src/usb_device.c
new file mode 100644
index 00000000..2cbfa7dd
--- /dev/null
+++ b/firmware/targets/f3/Src/usb_device.c
@@ -0,0 +1,99 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : usb_device.c
+ * @version : v3.0_Cube
+ * @brief : This file implements the USB Device
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+
+#include "usb_device.h"
+#include "usbd_core.h"
+#include "usbd_desc.h"
+#include "usbd_cdc.h"
+#include "usbd_cdc_if.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* USER CODE BEGIN PV */
+/* Private variables ---------------------------------------------------------*/
+
+/* USER CODE END PV */
+
+/* USER CODE BEGIN PFP */
+/* Private function prototypes -----------------------------------------------*/
+
+/* USER CODE END PFP */
+
+extern void Error_Handler(void);
+/* USB Device Core handle declaration. */
+USBD_HandleTypeDef hUsbDeviceFS;
+extern USBD_DescriptorsTypeDef CDC_Desc;
+
+/*
+ * -- Insert your variables declaration here --
+ */
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/*
+ * -- Insert your external function declaration here --
+ */
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/**
+ * Init USB device Library, add supported class and start the library
+ * @retval None
+ */
+void MX_USB_Device_Init(void)
+{
+ /* USER CODE BEGIN USB_Device_Init_PreTreatment */
+
+ /* USER CODE END USB_Device_Init_PreTreatment */
+
+ /* Init Device Library, add supported class and start the library. */
+ if (USBD_Init(&hUsbDeviceFS, &CDC_Desc, DEVICE_FS) != USBD_OK) {
+ Error_Handler();
+ }
+ if (USBD_RegisterClass(&hUsbDeviceFS, &USBD_CDC) != USBD_OK) {
+ Error_Handler();
+ }
+ if (USBD_CDC_RegisterInterface(&hUsbDeviceFS, &USBD_Interface_fops_FS) != USBD_OK) {
+ Error_Handler();
+ }
+ if (USBD_Start(&hUsbDeviceFS) != USBD_OK) {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN USB_Device_Init_PostTreatment */
+
+ /* USER CODE END USB_Device_Init_PostTreatment */
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/usbd_cdc_if.c b/firmware/targets/f3/Src/usbd_cdc_if.c
new file mode 100644
index 00000000..2141aec8
--- /dev/null
+++ b/firmware/targets/f3/Src/usbd_cdc_if.c
@@ -0,0 +1,331 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : usbd_cdc_if.c
+ * @version : v3.0_Cube
+ * @brief : Usb device for Virtual Com Port.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_cdc_if.h"
+
+/* USER CODE BEGIN INCLUDE */
+
+/* USER CODE END INCLUDE */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+
+/* USER CODE BEGIN PV */
+/* Private variables ---------------------------------------------------------*/
+
+/* USER CODE END PV */
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+ * @brief Usb device library.
+ * @{
+ */
+
+/** @addtogroup USBD_CDC_IF
+ * @{
+ */
+
+/** @defgroup USBD_CDC_IF_Private_TypesDefinitions USBD_CDC_IF_Private_TypesDefinitions
+ * @brief Private types.
+ * @{
+ */
+
+/* USER CODE BEGIN PRIVATE_TYPES */
+
+/* USER CODE END PRIVATE_TYPES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_IF_Private_Defines USBD_CDC_IF_Private_Defines
+ * @brief Private defines.
+ * @{
+ */
+
+/* USER CODE BEGIN PRIVATE_DEFINES */
+/* USER CODE END PRIVATE_DEFINES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_IF_Private_Macros USBD_CDC_IF_Private_Macros
+ * @brief Private macros.
+ * @{
+ */
+
+/* USER CODE BEGIN PRIVATE_MACRO */
+
+/* USER CODE END PRIVATE_MACRO */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_IF_Private_Variables USBD_CDC_IF_Private_Variables
+ * @brief Private variables.
+ * @{
+ */
+/* Create buffer for reception and transmission */
+/* It's up to user to redefine and/or remove those define */
+/** Received data over USB are stored in this buffer */
+uint8_t UserRxBufferFS[APP_RX_DATA_SIZE];
+
+/** Data to send over USB CDC are stored in this buffer */
+uint8_t UserTxBufferFS[APP_TX_DATA_SIZE];
+
+/* USER CODE BEGIN PRIVATE_VARIABLES */
+
+/* USER CODE END PRIVATE_VARIABLES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_IF_Exported_Variables USBD_CDC_IF_Exported_Variables
+ * @brief Public variables.
+ * @{
+ */
+
+extern USBD_HandleTypeDef hUsbDeviceFS;
+
+/* USER CODE BEGIN EXPORTED_VARIABLES */
+
+/* USER CODE END EXPORTED_VARIABLES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_IF_Private_FunctionPrototypes USBD_CDC_IF_Private_FunctionPrototypes
+ * @brief Private functions declaration.
+ * @{
+ */
+
+static int8_t CDC_Init_FS(void);
+static int8_t CDC_DeInit_FS(void);
+static int8_t CDC_Control_FS(uint8_t cmd, uint8_t* pbuf, uint16_t length);
+static int8_t CDC_Receive_FS(uint8_t* pbuf, uint32_t *Len);
+static int8_t CDC_TransmitCplt_FS(uint8_t *pbuf, uint32_t *Len, uint8_t epnum);
+
+/* USER CODE BEGIN PRIVATE_FUNCTIONS_DECLARATION */
+
+/* USER CODE END PRIVATE_FUNCTIONS_DECLARATION */
+
+/**
+ * @}
+ */
+
+USBD_CDC_ItfTypeDef USBD_Interface_fops_FS =
+{
+ CDC_Init_FS,
+ CDC_DeInit_FS,
+ CDC_Control_FS,
+ CDC_Receive_FS,
+ CDC_TransmitCplt_FS
+};
+
+/* Private functions ---------------------------------------------------------*/
+/**
+ * @brief Initializes the CDC media low layer over the FS USB IP
+ * @retval USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_Init_FS(void)
+{
+ /* USER CODE BEGIN 3 */
+ /* Set Application Buffers */
+ USBD_CDC_SetTxBuffer(&hUsbDeviceFS, UserTxBufferFS, 0);
+ USBD_CDC_SetRxBuffer(&hUsbDeviceFS, UserRxBufferFS);
+ return (USBD_OK);
+ /* USER CODE END 3 */
+}
+
+/**
+ * @brief DeInitializes the CDC media low layer
+ * @retval USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_DeInit_FS(void)
+{
+ /* USER CODE BEGIN 4 */
+ return (USBD_OK);
+ /* USER CODE END 4 */
+}
+
+/**
+ * @brief Manage the CDC class requests
+ * @param cmd: Command code
+ * @param pbuf: Buffer containing command data (request parameters)
+ * @param length: Number of data to be sent (in bytes)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_Control_FS(uint8_t cmd, uint8_t* pbuf, uint16_t length)
+{
+ /* USER CODE BEGIN 5 */
+ switch(cmd)
+ {
+ case CDC_SEND_ENCAPSULATED_COMMAND:
+
+ break;
+
+ case CDC_GET_ENCAPSULATED_RESPONSE:
+
+ break;
+
+ case CDC_SET_COMM_FEATURE:
+
+ break;
+
+ case CDC_GET_COMM_FEATURE:
+
+ break;
+
+ case CDC_CLEAR_COMM_FEATURE:
+
+ break;
+
+ /*******************************************************************************/
+ /* Line Coding Structure */
+ /*-----------------------------------------------------------------------------*/
+ /* Offset | Field | Size | Value | Description */
+ /* 0 | dwDTERate | 4 | Number |Data terminal rate, in bits per second*/
+ /* 4 | bCharFormat | 1 | Number | Stop bits */
+ /* 0 - 1 Stop bit */
+ /* 1 - 1.5 Stop bits */
+ /* 2 - 2 Stop bits */
+ /* 5 | bParityType | 1 | Number | Parity */
+ /* 0 - None */
+ /* 1 - Odd */
+ /* 2 - Even */
+ /* 3 - Mark */
+ /* 4 - Space */
+ /* 6 | bDataBits | 1 | Number Data bits (5, 6, 7, 8 or 16). */
+ /*******************************************************************************/
+ case CDC_SET_LINE_CODING:
+
+ break;
+
+ case CDC_GET_LINE_CODING:
+
+ break;
+
+ case CDC_SET_CONTROL_LINE_STATE:
+
+ break;
+
+ case CDC_SEND_BREAK:
+
+ break;
+
+ default:
+ break;
+ }
+
+ return (USBD_OK);
+ /* USER CODE END 5 */
+}
+
+/**
+ * @brief Data received over USB OUT endpoint are sent over CDC interface
+ * through this function.
+ *
+ * @note
+ * This function will issue a NAK packet on any OUT packet received on
+ * USB endpoint until exiting this function. If you exit this function
+ * before transfer is complete on CDC interface (ie. using DMA controller)
+ * it will result in receiving more data while previous ones are still
+ * not sent.
+ *
+ * @param Buf: Buffer of data to be received
+ * @param Len: Number of data received (in bytes)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_Receive_FS(uint8_t* Buf, uint32_t *Len)
+{
+ /* USER CODE BEGIN 6 */
+ USBD_CDC_SetRxBuffer(&hUsbDeviceFS, &Buf[0]);
+ USBD_CDC_ReceivePacket(&hUsbDeviceFS);
+ return (USBD_OK);
+ /* USER CODE END 6 */
+}
+
+/**
+ * @brief CDC_Transmit_FS
+ * Data to send over USB IN endpoint are sent over CDC interface
+ * through this function.
+ * @note
+ *
+ *
+ * @param Buf: Buffer of data to be sent
+ * @param Len: Number of data to be sent (in bytes)
+ * @retval USBD_OK if all operations are OK else USBD_FAIL or USBD_BUSY
+ */
+uint8_t CDC_Transmit_FS(uint8_t* Buf, uint16_t Len)
+{
+ uint8_t result = USBD_OK;
+ /* USER CODE BEGIN 7 */
+ USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)hUsbDeviceFS.pClassData;
+ if (hcdc->TxState != 0){
+ return USBD_BUSY;
+ }
+ USBD_CDC_SetTxBuffer(&hUsbDeviceFS, Buf, Len);
+ result = USBD_CDC_TransmitPacket(&hUsbDeviceFS);
+ /* USER CODE END 7 */
+ return result;
+}
+
+/**
+ * @brief CDC_TransmitCplt_FS
+ * Data transmited callback
+ *
+ * @note
+ * This function is IN transfer complete callback used to inform user that
+ * the submitted Data is successfully sent over USB.
+ *
+ * @param Buf: Buffer of data to be received
+ * @param Len: Number of data received (in bytes)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_TransmitCplt_FS(uint8_t *Buf, uint32_t *Len, uint8_t epnum)
+{
+ uint8_t result = USBD_OK;
+ /* USER CODE BEGIN 13 */
+ UNUSED(Buf);
+ UNUSED(Len);
+ UNUSED(epnum);
+ /* USER CODE END 13 */
+ return result;
+}
+
+/* USER CODE BEGIN PRIVATE_FUNCTIONS_IMPLEMENTATION */
+
+/* USER CODE END PRIVATE_FUNCTIONS_IMPLEMENTATION */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/usbd_conf.c b/firmware/targets/f3/Src/usbd_conf.c
new file mode 100644
index 00000000..757ef43b
--- /dev/null
+++ b/firmware/targets/f3/Src/usbd_conf.c
@@ -0,0 +1,810 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : usbd_conf.c
+ * @version : v3.0_Cube
+ * @brief : This file implements the board support package for the USB device library
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32wbxx.h"
+#include "stm32wbxx_hal.h"
+#include "usbd_def.h"
+#include "usbd_core.h"
+
+#include "usbd_cdc.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+PCD_HandleTypeDef hpcd_USB_FS;
+void Error_Handler(void);
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/* Exported function prototypes ----------------------------------------------*/
+
+/* USER CODE BEGIN PFP */
+/* Private function prototypes -----------------------------------------------*/
+
+/* USER CODE END PFP */
+
+/* Private functions ---------------------------------------------------------*/
+static USBD_StatusTypeDef USBD_Get_USB_Status(HAL_StatusTypeDef hal_status);
+/* USER CODE BEGIN 1 */
+static void SystemClockConfig_Resume(void);
+
+/* USER CODE END 1 */
+extern void SystemClock_Config(void);
+
+/*******************************************************************************
+ LL Driver Callbacks (PCD -> USB Device Library)
+*******************************************************************************/
+/* MSP Init */
+
+#if (USE_HAL_PCD_REGISTER_CALLBACK == 1U)
+static void HAL_PCD_MspInit(PCD_HandleTypeDef* pcdHandle)
+#else
+void HAL_PCD_MspInit(PCD_HandleTypeDef* pcdHandle)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACK */
+{
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(pcdHandle->Instance==USB)
+ {
+ /* USER CODE BEGIN USB_MspInit 0 */
+
+ /* USER CODE END USB_MspInit 0 */
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**USB GPIO Configuration
+ PA11 ------> USB_DM
+ PA12 ------> USB_DP
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_12;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF10_USB;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* Peripheral clock enable */
+ __HAL_RCC_USB_CLK_ENABLE();
+
+ /* Peripheral interrupt init */
+ HAL_NVIC_SetPriority(USB_LP_IRQn, 5, 0);
+ HAL_NVIC_EnableIRQ(USB_LP_IRQn);
+ /* USER CODE BEGIN USB_MspInit 1 */
+
+ /* USER CODE END USB_MspInit 1 */
+ }
+}
+
+#if (USE_HAL_PCD_REGISTER_CALLBACK == 1U)
+static void HAL_PCD_MspDeInit(PCD_HandleTypeDef* pcdHandle)
+#else
+void HAL_PCD_MspDeInit(PCD_HandleTypeDef* pcdHandle)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACK */
+{
+ if(pcdHandle->Instance==USB)
+ {
+ /* USER CODE BEGIN USB_MspDeInit 0 */
+
+ /* USER CODE END USB_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_USB_CLK_DISABLE();
+
+ /**USB GPIO Configuration
+ PA11 ------> USB_DM
+ PA12 ------> USB_DP
+ */
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
+
+ /* Peripheral interrupt Deinit*/
+ HAL_NVIC_DisableIRQ(USB_LP_IRQn);
+
+ /* USER CODE BEGIN USB_MspDeInit 1 */
+
+ /* USER CODE END USB_MspDeInit 1 */
+ }
+}
+
+/**
+ * @brief Setup stage callback
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd)
+#else
+void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN HAL_PCD_SetupStageCallback_PreTreatment */
+
+ /* USER CODE END HAL_PCD_SetupStageCallback_PreTreatment */
+ USBD_LL_SetupStage((USBD_HandleTypeDef*)hpcd->pData, (uint8_t *)hpcd->Setup);
+ /* USER CODE BEGIN HAL_PCD_SetupStageCallback_PostTreatment */
+
+ /* USER CODE END HAL_PCD_SetupStageCallback_PostTreatment */
+}
+
+/**
+ * @brief Data Out stage callback.
+ * @param hpcd: PCD handle
+ * @param epnum: Endpoint number
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+#else
+void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN HAL_PCD_DataOutStageCallback_PreTreatment */
+
+ /* USER CODE END HAL_PCD_DataOutStageCallback_PreTreatment */
+ USBD_LL_DataOutStage((USBD_HandleTypeDef*)hpcd->pData, epnum, hpcd->OUT_ep[epnum].xfer_buff);
+ /* USER CODE BEGIN HAL_PCD_DataOutStageCallback_PostTreatment */
+
+ /* USER CODE END HAL_PCD_DataOutStageCallback_PostTreatment */
+}
+
+/**
+ * @brief Data In stage callback.
+ * @param hpcd: PCD handle
+ * @param epnum: Endpoint number
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+#else
+void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN HAL_PCD_DataInStageCallback_PreTreatment */
+
+ /* USER CODE END HAL_PCD_DataInStageCallback_PreTreatment */
+ USBD_LL_DataInStage((USBD_HandleTypeDef*)hpcd->pData, epnum, hpcd->IN_ep[epnum].xfer_buff);
+ /* USER CODE BEGIN HAL_PCD_DataInStageCallback_PostTreatment */
+
+ /* USER CODE END HAL_PCD_DataInStageCallback_PostTreatment */
+}
+
+/**
+ * @brief SOF callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCD_SOFCallback(PCD_HandleTypeDef *hpcd)
+#else
+void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN HAL_PCD_SOFCallback_PreTreatment */
+
+ /* USER CODE END HAL_PCD_SOFCallback_PreTreatment */
+ USBD_LL_SOF((USBD_HandleTypeDef*)hpcd->pData);
+ /* USER CODE BEGIN HAL_PCD_SOFCallback_PostTreatment */
+
+ /* USER CODE END HAL_PCD_SOFCallback_PostTreatment */
+}
+
+/**
+ * @brief Reset callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCD_ResetCallback(PCD_HandleTypeDef *hpcd)
+#else
+void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN HAL_PCD_ResetCallback_PreTreatment */
+
+ /* USER CODE END HAL_PCD_ResetCallback_PreTreatment */
+ USBD_SpeedTypeDef speed = USBD_SPEED_FULL;
+
+ if ( hpcd->Init.speed != PCD_SPEED_FULL)
+ {
+ Error_Handler();
+ }
+ /* Set Speed. */
+ USBD_LL_SetSpeed((USBD_HandleTypeDef*)hpcd->pData, speed);
+
+ /* Reset Device. */
+ USBD_LL_Reset((USBD_HandleTypeDef*)hpcd->pData);
+ /* USER CODE BEGIN HAL_PCD_ResetCallback_PostTreatment */
+
+ /* USER CODE END HAL_PCD_ResetCallback_PostTreatment */
+}
+
+/**
+ * @brief Suspend callback.
+ * When Low power mode is enabled the debug cannot be used (IAR, Keil doesn't support it)
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCD_SuspendCallback(PCD_HandleTypeDef *hpcd)
+#else
+void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN HAL_PCD_SuspendCallback_PreTreatment */
+
+ /* USER CODE END HAL_PCD_SuspendCallback_PreTreatment */
+ /* Inform USB library that core enters in suspend Mode. */
+ USBD_LL_Suspend((USBD_HandleTypeDef*)hpcd->pData);
+ /* Enter in STOP mode. */
+ /* USER CODE BEGIN 2 */
+ if (hpcd->Init.low_power_enable)
+ {
+ /* Set SLEEPDEEP bit and SleepOnExit of Cortex System Control Register. */
+ SCB->SCR |= (uint32_t)((uint32_t)(SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk));
+ }
+ /* USER CODE END 2 */
+ /* USER CODE BEGIN HAL_PCD_SuspendCallback_PostTreatment */
+
+ /* USER CODE END HAL_PCD_SuspendCallback_PostTreatment */
+}
+
+/**
+ * @brief Resume callback.
+ * When Low power mode is enabled the debug cannot be used (IAR, Keil doesn't support it)
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCD_ResumeCallback(PCD_HandleTypeDef *hpcd)
+#else
+void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN HAL_PCD_ResumeCallback_PreTreatment */
+
+ /* USER CODE END HAL_PCD_ResumeCallback_PreTreatment */
+
+ /* USER CODE BEGIN 3 */
+ if (hpcd->Init.low_power_enable)
+ {
+ /* Reset SLEEPDEEP bit of Cortex System Control Register. */
+ SCB->SCR &= (uint32_t)~((uint32_t)(SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk));
+ SystemClockConfig_Resume();
+ }
+ /* USER CODE END 3 */
+
+ USBD_LL_Resume((USBD_HandleTypeDef*)hpcd->pData);
+ /* USER CODE BEGIN HAL_PCD_ResumeCallback_PostTreatment */
+
+ /* USER CODE END HAL_PCD_ResumeCallback_PostTreatment */
+}
+
+/**
+ * @brief ISOOUTIncomplete callback.
+ * @param hpcd: PCD handle
+ * @param epnum: Endpoint number
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+#else
+void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN HAL_PCD_ISOOUTIncompleteCallback_PreTreatment */
+
+ /* USER CODE END HAL_PCD_ISOOUTIncompleteCallback_PreTreatment */
+ USBD_LL_IsoOUTIncomplete((USBD_HandleTypeDef*)hpcd->pData, epnum);
+ /* USER CODE BEGIN HAL_PCD_ISOOUTIncompleteCallback_PostTreatment */
+
+ /* USER CODE END HAL_PCD_ISOOUTIncompleteCallback_PostTreatment */
+}
+
+/**
+ * @brief ISOINIncomplete callback.
+ * @param hpcd: PCD handle
+ * @param epnum: Endpoint number
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+#else
+void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN HAL_PCD_ISOINIncompleteCallback_PreTreatment */
+
+ /* USER CODE END HAL_PCD_ISOINIncompleteCallback_PreTreatment */
+ USBD_LL_IsoINIncomplete((USBD_HandleTypeDef*)hpcd->pData, epnum);
+ /* USER CODE BEGIN HAL_PCD_ISOINIncompleteCallback_PostTreatment */
+
+ /* USER CODE END HAL_PCD_ISOINIncompleteCallback_PostTreatment */
+}
+
+/**
+ * @brief Connect callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCD_ConnectCallback(PCD_HandleTypeDef *hpcd)
+#else
+void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN HAL_PCD_ConnectCallback_PreTreatment */
+
+ /* USER CODE END HAL_PCD_ConnectCallback_PreTreatment */
+ USBD_LL_DevConnected((USBD_HandleTypeDef*)hpcd->pData);
+ /* USER CODE BEGIN HAL_PCD_ConnectCallback_PostTreatment */
+
+ /* USER CODE END HAL_PCD_ConnectCallback_PostTreatment */
+}
+
+/**
+ * @brief Disconnect callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd)
+#else
+void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN HAL_PCD_DisconnectCallback_PreTreatment */
+
+ /* USER CODE END HAL_PCD_DisconnectCallback_PreTreatment */
+ USBD_LL_DevDisconnected((USBD_HandleTypeDef*)hpcd->pData);
+ /* USER CODE BEGIN HAL_PCD_DisconnectCallback_PostTreatment */
+
+ /* USER CODE END HAL_PCD_DisconnectCallback_PostTreatment */
+}
+
+ /* USER CODE BEGIN LowLevelInterface */
+
+ /* USER CODE END LowLevelInterface */
+
+/*******************************************************************************
+ LL Driver Interface (USB Device Library --> PCD)
+*******************************************************************************/
+
+/**
+ * @brief Initializes the low level portion of the device driver.
+ * @param pdev: Device handle
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef *pdev)
+{
+ /* Init USB Ip. */
+ hpcd_USB_FS.pData = pdev;
+ /* Link the driver to the stack. */
+ pdev->pData = &hpcd_USB_FS;
+/* Enable USB power on Pwrctrl CR2 register. */
+ HAL_PWREx_EnableVddUSB();
+
+ hpcd_USB_FS.Instance = USB;
+ hpcd_USB_FS.Init.dev_endpoints = 8;
+ hpcd_USB_FS.Init.speed = PCD_SPEED_FULL;
+ hpcd_USB_FS.Init.phy_itface = PCD_PHY_EMBEDDED;
+ hpcd_USB_FS.Init.Sof_enable = DISABLE;
+ hpcd_USB_FS.Init.low_power_enable = DISABLE;
+ hpcd_USB_FS.Init.lpm_enable = DISABLE;
+ hpcd_USB_FS.Init.battery_charging_enable = DISABLE;
+
+ #if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+ /* register Msp Callbacks (before the Init) */
+ HAL_PCD_RegisterCallback(&hpcd_USB_FS, HAL_PCD_MSPINIT_CB_ID, PCD_MspInit);
+ HAL_PCD_RegisterCallback(&hpcd_USB_FS, HAL_PCD_MSPDEINIT_CB_ID, PCD_MspDeInit);
+ #endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+
+ if (HAL_PCD_Init(&hpcd_USB_FS) != HAL_OK)
+ {
+ Error_Handler( );
+ }
+
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+ /* Register USB PCD CallBacks */
+ HAL_PCD_RegisterCallback(&hpcd_USB_FS, HAL_PCD_SOF_CB_ID, PCD_SOFCallback);
+ HAL_PCD_RegisterCallback(&hpcd_USB_FS, HAL_PCD_SETUPSTAGE_CB_ID, PCD_SetupStageCallback);
+ HAL_PCD_RegisterCallback(&hpcd_USB_FS, HAL_PCD_RESET_CB_ID, PCD_ResetCallback);
+ HAL_PCD_RegisterCallback(&hpcd_USB_FS, HAL_PCD_SUSPEND_CB_ID, PCD_SuspendCallback);
+ HAL_PCD_RegisterCallback(&hpcd_USB_FS, HAL_PCD_RESUME_CB_ID, PCD_ResumeCallback);
+ HAL_PCD_RegisterCallback(&hpcd_USB_FS, HAL_PCD_CONNECT_CB_ID, PCD_ConnectCallback);
+ HAL_PCD_RegisterCallback(&hpcd_USB_FS, HAL_PCD_DISCONNECT_CB_ID, PCD_DisconnectCallback);
+ /* USER CODE BEGIN RegisterCallBackFirstPart */
+
+ /* USER CODE END RegisterCallBackFirstPart */
+ HAL_PCD_RegisterLpmCallback(&hpcd_USB_FS, PCDEx_LPM_Callback);
+ HAL_PCD_RegisterDataOutStageCallback(&hpcd_USB_FS, PCD_DataOutStageCallback);
+ HAL_PCD_RegisterDataInStageCallback(&hpcd_USB_FS, PCD_DataInStageCallback);
+ HAL_PCD_RegisterIsoOutIncpltCallback(&hpcd_USB_FS, PCD_ISOOUTIncompleteCallback);
+ HAL_PCD_RegisterIsoInIncpltCallback(&hpcd_USB_FS, PCD_ISOINIncompleteCallback);
+ /* USER CODE BEGIN RegisterCallBackSecondPart */
+
+ /* USER CODE END RegisterCallBackSecondPart */
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+ /* USER CODE BEGIN EndPoint_Configuration */
+ HAL_PCDEx_PMAConfig((PCD_HandleTypeDef*)pdev->pData , 0x00 , PCD_SNG_BUF, 0x18);
+ HAL_PCDEx_PMAConfig((PCD_HandleTypeDef*)pdev->pData , 0x80 , PCD_SNG_BUF, 0x58);
+ /* USER CODE END EndPoint_Configuration */
+ /* USER CODE BEGIN EndPoint_Configuration_CDC */
+ HAL_PCDEx_PMAConfig((PCD_HandleTypeDef*)pdev->pData , 0x81 , PCD_SNG_BUF, 0xC0);
+ HAL_PCDEx_PMAConfig((PCD_HandleTypeDef*)pdev->pData , 0x01 , PCD_SNG_BUF, 0x110);
+ HAL_PCDEx_PMAConfig((PCD_HandleTypeDef*)pdev->pData , 0x82 , PCD_SNG_BUF, 0x100);
+ /* USER CODE END EndPoint_Configuration_CDC */
+ return USBD_OK;
+}
+
+/**
+ * @brief De-Initializes the low level portion of the device driver.
+ * @param pdev: Device handle
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_DeInit(USBD_HandleTypeDef *pdev)
+{
+ HAL_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_DeInit(pdev->pData);
+
+ usb_status = USBD_Get_USB_Status(hal_status);
+
+ return usb_status;
+}
+
+/**
+ * @brief Starts the low level portion of the device driver.
+ * @param pdev: Device handle
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_Start(USBD_HandleTypeDef *pdev)
+{
+ HAL_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_Start(pdev->pData);
+
+ usb_status = USBD_Get_USB_Status(hal_status);
+
+ return usb_status;
+}
+
+/**
+ * @brief Stops the low level portion of the device driver.
+ * @param pdev: Device handle
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_Stop(USBD_HandleTypeDef *pdev)
+{
+ HAL_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_Stop(pdev->pData);
+
+ usb_status = USBD_Get_USB_Status(hal_status);
+
+ return usb_status;
+}
+
+/**
+ * @brief Opens an endpoint of the low level driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint number
+ * @param ep_type: Endpoint type
+ * @param ep_mps: Endpoint max packet size
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_OpenEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr, uint8_t ep_type, uint16_t ep_mps)
+{
+ HAL_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_Open(pdev->pData, ep_addr, ep_mps, ep_type);
+
+ usb_status = USBD_Get_USB_Status(hal_status);
+
+ return usb_status;
+}
+
+/**
+ * @brief Closes an endpoint of the low level driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint number
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_CloseEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ HAL_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_Close(pdev->pData, ep_addr);
+
+ usb_status = USBD_Get_USB_Status(hal_status);
+
+ return usb_status;
+}
+
+/**
+ * @brief Flushes an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint number
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_FlushEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ HAL_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_Flush(pdev->pData, ep_addr);
+
+ usb_status = USBD_Get_USB_Status(hal_status);
+
+ return usb_status;
+}
+
+/**
+ * @brief Sets a Stall condition on an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint number
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_StallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ HAL_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_SetStall(pdev->pData, ep_addr);
+
+ usb_status = USBD_Get_USB_Status(hal_status);
+
+ return usb_status;
+}
+
+/**
+ * @brief Clears a Stall condition on an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint number
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_ClearStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ HAL_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_ClrStall(pdev->pData, ep_addr);
+
+ usb_status = USBD_Get_USB_Status(hal_status);
+
+ return usb_status;
+}
+
+/**
+ * @brief Returns Stall condition.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint number
+ * @retval Stall (1: Yes, 0: No)
+ */
+uint8_t USBD_LL_IsStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ PCD_HandleTypeDef *hpcd = (PCD_HandleTypeDef*) pdev->pData;
+
+ if((ep_addr & 0x80) == 0x80)
+ {
+ return hpcd->IN_ep[ep_addr & 0x7F].is_stall;
+ }
+ else
+ {
+ return hpcd->OUT_ep[ep_addr & 0x7F].is_stall;
+ }
+}
+
+/**
+ * @brief Assigns a USB address to the device.
+ * @param pdev: Device handle
+ * @param dev_addr: Device address
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_SetUSBAddress(USBD_HandleTypeDef *pdev, uint8_t dev_addr)
+{
+ HAL_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_SetAddress(pdev->pData, dev_addr);
+
+ usb_status = USBD_Get_USB_Status(hal_status);
+
+ return usb_status;
+}
+
+/**
+ * @brief Transmits data over an endpoint.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint number
+ * @param pbuf: Pointer to data to be sent
+ * @param size: Data size
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_Transmit(USBD_HandleTypeDef *pdev, uint8_t ep_addr, uint8_t *pbuf, uint32_t size)
+{
+ HAL_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_Transmit(pdev->pData, ep_addr, pbuf, size);
+
+ usb_status = USBD_Get_USB_Status(hal_status);
+
+ return usb_status;
+}
+
+/**
+ * @brief Prepares an endpoint for reception.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint number
+ * @param pbuf: Pointer to data to be received
+ * @param size: Data size
+ * @retval USBD status
+ */
+USBD_StatusTypeDef USBD_LL_PrepareReceive(USBD_HandleTypeDef *pdev, uint8_t ep_addr, uint8_t *pbuf, uint32_t size)
+{
+ HAL_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_Receive(pdev->pData, ep_addr, pbuf, size);
+
+ usb_status = USBD_Get_USB_Status(hal_status);
+
+ return usb_status;
+}
+
+/**
+ * @brief Returns the last transfered packet size.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint number
+ * @retval Recived Data Size
+ */
+uint32_t USBD_LL_GetRxDataSize(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ return HAL_PCD_EP_GetRxCount((PCD_HandleTypeDef*) pdev->pData, ep_addr);
+}
+
+/**
+ * @brief Send LPM message to user layer
+ * @param hpcd: PCD handle
+ * @param msg: LPM message
+ * @retval None
+ */
+#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U)
+static void PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg)
+#else
+void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg)
+#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */
+{
+ /* USER CODE BEGIN LPM_Callback */
+ switch (msg)
+ {
+ case PCD_LPM_L0_ACTIVE:
+ if (hpcd->Init.low_power_enable)
+ {
+ SystemClockConfig_Resume();
+
+ /* Reset SLEEPDEEP bit of Cortex System Control Register. */
+ SCB->SCR &= (uint32_t)~((uint32_t)(SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk));
+ }
+ USBD_LL_Resume(hpcd->pData);
+ break;
+
+ case PCD_LPM_L1_ACTIVE:
+ USBD_LL_Suspend(hpcd->pData);
+
+ /* Enter in STOP mode. */
+ if (hpcd->Init.low_power_enable)
+ {
+ /* Set SLEEPDEEP bit and SleepOnExit of Cortex System Control Register. */
+ SCB->SCR |= (uint32_t)((uint32_t)(SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk));
+ }
+ break;
+ }
+ /* USER CODE END LPM_Callback */
+}
+
+/**
+ * @brief Delays routine for the USB Device Library.
+ * @param Delay: Delay in ms
+ * @retval None
+ */
+void USBD_LL_Delay(uint32_t Delay)
+{
+ HAL_Delay(Delay);
+}
+
+/**
+ * @brief Static single allocation.
+ * @param size: Size of allocated memory
+ * @retval None
+ */
+void *USBD_static_malloc(uint32_t size)
+{
+ static uint32_t mem[(sizeof(USBD_CDC_HandleTypeDef)/4)+1];/* On 32-bit boundary */
+ return mem;
+}
+
+/**
+ * @brief Dummy memory free
+ * @param p: Pointer to allocated memory address
+ * @retval None
+ */
+void USBD_static_free(void *p)
+{
+
+}
+
+/* USER CODE BEGIN 5 */
+/**
+ * @brief Configures system clock after wake-up from USB resume callBack:
+ * enable HSI, PLL and select PLL as system clock source.
+ * @retval None
+ */
+static void SystemClockConfig_Resume(void)
+{
+ SystemClock_Config();
+}
+/* USER CODE END 5 */
+
+/**
+ * @brief Retuns the USB status depending on the HAL status:
+ * @param hal_status: HAL status
+ * @retval USB status
+ */
+USBD_StatusTypeDef USBD_Get_USB_Status(HAL_StatusTypeDef hal_status)
+{
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ switch (hal_status)
+ {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/Src/usbd_desc.c b/firmware/targets/f3/Src/usbd_desc.c
new file mode 100644
index 00000000..821be8ee
--- /dev/null
+++ b/firmware/targets/f3/Src/usbd_desc.c
@@ -0,0 +1,396 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : usbd_desc.c
+ * @version : v3.0_Cube
+ * @brief : This file implements the USB device descriptors.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_core.h"
+#include "usbd_desc.h"
+#include "usbd_conf.h"
+
+/* USER CODE BEGIN INCLUDE */
+
+/* USER CODE END INCLUDE */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+
+/* USER CODE BEGIN PV */
+/* Private variables ---------------------------------------------------------*/
+
+/* USER CODE END PV */
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @addtogroup USBD_DESC
+ * @{
+ */
+
+/** @defgroup USBD_DESC_Private_TypesDefinitions USBD_DESC_Private_TypesDefinitions
+ * @brief Private types.
+ * @{
+ */
+
+/* USER CODE BEGIN PRIVATE_TYPES */
+
+/* USER CODE END PRIVATE_TYPES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Private_Defines USBD_DESC_Private_Defines
+ * @brief Private defines.
+ * @{
+ */
+
+#define USBD_VID 1155
+#define USBD_LANGID_STRING 1033
+#define USBD_MANUFACTURER_STRING "Flipper"
+#define USBD_PID 22336
+#define USBD_PRODUCT_STRING "Flipper Control Virtual ComPort"
+#define USBD_CONFIGURATION_STRING "CDC Config"
+#define USBD_INTERFACE_STRING "CDC Interface"
+
+/* USER CODE BEGIN PRIVATE_DEFINES */
+
+/* USER CODE END PRIVATE_DEFINES */
+
+/**
+ * @}
+ */
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/** @defgroup USBD_DESC_Private_Macros USBD_DESC_Private_Macros
+ * @brief Private macros.
+ * @{
+ */
+
+/* USER CODE BEGIN PRIVATE_MACRO */
+
+/* USER CODE END PRIVATE_MACRO */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Private_FunctionPrototypes USBD_DESC_Private_FunctionPrototypes
+ * @brief Private functions declaration.
+ * @{
+ */
+
+static void Get_SerialNum(void);
+static void IntToUnicode(uint32_t value, uint8_t * pbuf, uint8_t len);
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Private_FunctionPrototypes USBD_DESC_Private_FunctionPrototypes
+ * @brief Private functions declaration.
+ * @{
+ */
+
+uint8_t * USBD_CDC_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
+uint8_t * USBD_CDC_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
+uint8_t * USBD_CDC_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
+uint8_t * USBD_CDC_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
+uint8_t * USBD_CDC_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
+uint8_t * USBD_CDC_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
+uint8_t * USBD_CDC_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Private_Variables USBD_DESC_Private_Variables
+ * @brief Private variables.
+ * @{
+ */
+
+USBD_DescriptorsTypeDef CDC_Desc =
+{
+ USBD_CDC_DeviceDescriptor,
+ USBD_CDC_LangIDStrDescriptor,
+ USBD_CDC_ManufacturerStrDescriptor,
+ USBD_CDC_ProductStrDescriptor,
+ USBD_CDC_SerialStrDescriptor,
+ USBD_CDC_ConfigStrDescriptor,
+ USBD_CDC_InterfaceStrDescriptor
+};
+
+#if defined ( __ICCARM__ ) /* IAR Compiler */
+ #pragma data_alignment=4
+#endif /* defined ( __ICCARM__ ) */
+/** USB standard device descriptor. */
+__ALIGN_BEGIN uint8_t USBD_CDC_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END =
+{
+ 0x12, /*bLength */
+ USB_DESC_TYPE_DEVICE, /*bDescriptorType*/
+ 0x00, /*bcdUSB */
+ 0x02,
+ 0x02, /*bDeviceClass*/
+ 0x02, /*bDeviceSubClass*/
+ 0x00, /*bDeviceProtocol*/
+ USB_MAX_EP0_SIZE, /*bMaxPacketSize*/
+ LOBYTE(USBD_VID), /*idVendor*/
+ HIBYTE(USBD_VID), /*idVendor*/
+ LOBYTE(USBD_PID), /*idProduct*/
+ HIBYTE(USBD_PID), /*idProduct*/
+ 0x00, /*bcdDevice rel. 2.00*/
+ 0x02,
+ USBD_IDX_MFC_STR, /*Index of manufacturer string*/
+ USBD_IDX_PRODUCT_STR, /*Index of product string*/
+ USBD_IDX_SERIAL_STR, /*Index of serial number string*/
+ USBD_MAX_NUM_CONFIGURATION /*bNumConfigurations*/
+};
+
+/* USB_DeviceDescriptor */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Private_Variables USBD_DESC_Private_Variables
+ * @brief Private variables.
+ * @{
+ */
+
+#if defined ( __ICCARM__ ) /* IAR Compiler */
+ #pragma data_alignment=4
+#endif /* defined ( __ICCARM__ ) */
+
+/** USB lang indentifier descriptor. */
+__ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_LEN_LANGID_STR_DESC] __ALIGN_END =
+{
+ USB_LEN_LANGID_STR_DESC,
+ USB_DESC_TYPE_STRING,
+ LOBYTE(USBD_LANGID_STRING),
+ HIBYTE(USBD_LANGID_STRING)
+};
+
+#if defined ( __ICCARM__ ) /* IAR Compiler */
+ #pragma data_alignment=4
+#endif /* defined ( __ICCARM__ ) */
+/* Internal string descriptor. */
+__ALIGN_BEGIN uint8_t USBD_StrDesc[USBD_MAX_STR_DESC_SIZ] __ALIGN_END;
+
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #pragma data_alignment=4
+#endif
+__ALIGN_BEGIN uint8_t USBD_StringSerial[USB_SIZ_STRING_SERIAL] __ALIGN_END = {
+ USB_SIZ_STRING_SERIAL,
+ USB_DESC_TYPE_STRING,
+};
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Private_Functions USBD_DESC_Private_Functions
+ * @brief Private functions.
+ * @{
+ */
+
+/**
+ * @brief Return the device descriptor
+ * @param speed : Current device speed
+ * @param length : Pointer to data length variable
+ * @retval Pointer to descriptor buffer
+ */
+uint8_t * USBD_CDC_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
+{
+ UNUSED(speed);
+ *length = sizeof(USBD_CDC_DeviceDesc);
+ return USBD_CDC_DeviceDesc;
+}
+
+/**
+ * @brief Return the LangID string descriptor
+ * @param speed : Current device speed
+ * @param length : Pointer to data length variable
+ * @retval Pointer to descriptor buffer
+ */
+uint8_t * USBD_CDC_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
+{
+ UNUSED(speed);
+ *length = sizeof(USBD_LangIDDesc);
+ return USBD_LangIDDesc;
+}
+
+/**
+ * @brief Return the product string descriptor
+ * @param speed : Current device speed
+ * @param length : Pointer to data length variable
+ * @retval Pointer to descriptor buffer
+ */
+uint8_t * USBD_CDC_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
+{
+ if(speed == 0)
+ {
+ USBD_GetString((uint8_t *)USBD_PRODUCT_STRING, USBD_StrDesc, length);
+ }
+ else
+ {
+ USBD_GetString((uint8_t *)USBD_PRODUCT_STRING, USBD_StrDesc, length);
+ }
+ return USBD_StrDesc;
+}
+
+/**
+ * @brief Return the manufacturer string descriptor
+ * @param speed : Current device speed
+ * @param length : Pointer to data length variable
+ * @retval Pointer to descriptor buffer
+ */
+uint8_t * USBD_CDC_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
+{
+ UNUSED(speed);
+ USBD_GetString((uint8_t *)USBD_MANUFACTURER_STRING, USBD_StrDesc, length);
+ return USBD_StrDesc;
+}
+
+/**
+ * @brief Return the serial number string descriptor
+ * @param speed : Current device speed
+ * @param length : Pointer to data length variable
+ * @retval Pointer to descriptor buffer
+ */
+uint8_t * USBD_CDC_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
+{
+ UNUSED(speed);
+ *length = USB_SIZ_STRING_SERIAL;
+
+ /* Update the serial number string descriptor with the data from the unique
+ * ID */
+ Get_SerialNum();
+
+ /* USER CODE BEGIN USBD_CDC_SerialStrDescriptor */
+
+ /* USER CODE END USBD_CDC_SerialStrDescriptor */
+
+ return (uint8_t *) USBD_StringSerial;
+}
+
+/**
+ * @brief Return the configuration string descriptor
+ * @param speed : Current device speed
+ * @param length : Pointer to data length variable
+ * @retval Pointer to descriptor buffer
+ */
+uint8_t * USBD_CDC_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
+{
+ if(speed == USBD_SPEED_HIGH)
+ {
+ USBD_GetString((uint8_t *)USBD_CONFIGURATION_STRING, USBD_StrDesc, length);
+ }
+ else
+ {
+ USBD_GetString((uint8_t *)USBD_CONFIGURATION_STRING, USBD_StrDesc, length);
+ }
+ return USBD_StrDesc;
+}
+
+/**
+ * @brief Return the interface string descriptor
+ * @param speed : Current device speed
+ * @param length : Pointer to data length variable
+ * @retval Pointer to descriptor buffer
+ */
+uint8_t * USBD_CDC_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
+{
+ if(speed == 0)
+ {
+ USBD_GetString((uint8_t *)USBD_INTERFACE_STRING, USBD_StrDesc, length);
+ }
+ else
+ {
+ USBD_GetString((uint8_t *)USBD_INTERFACE_STRING, USBD_StrDesc, length);
+ }
+ return USBD_StrDesc;
+}
+
+/**
+ * @brief Create the serial number string descriptor
+ * @param None
+ * @retval None
+ */
+static void Get_SerialNum(void)
+{
+ uint32_t deviceserial0, deviceserial1, deviceserial2;
+
+ deviceserial0 = *(uint32_t *) DEVICE_ID1;
+ deviceserial1 = *(uint32_t *) DEVICE_ID2;
+ deviceserial2 = *(uint32_t *) DEVICE_ID3;
+
+ deviceserial0 += deviceserial2;
+
+ if (deviceserial0 != 0)
+ {
+ IntToUnicode(deviceserial0, &USBD_StringSerial[2], 8);
+ IntToUnicode(deviceserial1, &USBD_StringSerial[18], 4);
+ }
+}
+
+/**
+ * @brief Convert Hex 32Bits value into char
+ * @param value: value to convert
+ * @param pbuf: pointer to the buffer
+ * @param len: buffer length
+ * @retval None
+ */
+static void IntToUnicode(uint32_t value, uint8_t * pbuf, uint8_t len)
+{
+ uint8_t idx = 0;
+
+ for (idx = 0; idx < len; idx++)
+ {
+ if (((value >> 28)) < 0xA)
+ {
+ pbuf[2 * idx] = (value >> 28) + '0';
+ }
+ else
+ {
+ pbuf[2 * idx] = (value >> 28) + 'A' - 10;
+ }
+
+ value = value << 4;
+
+ pbuf[2 * idx + 1] = 0;
+ }
+}
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/api-hal/api-hal-delay.c b/firmware/targets/f3/api-hal/api-hal-delay.c
new file mode 100644
index 00000000..bda9cace
--- /dev/null
+++ b/firmware/targets/f3/api-hal/api-hal-delay.c
@@ -0,0 +1,24 @@
+#include "api-hal-delay.h"
+#include "assert.h"
+#include "cmsis_os2.h"
+
+void delay_us_init_DWT(void) {
+ CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
+ DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk;
+ DWT->CYCCNT = 0U;
+}
+
+void delay_us(float microseconds) {
+ uint32_t start = DWT->CYCCNT;
+ uint32_t time_ticks = microseconds * (SystemCoreClock / 1000000.0f);
+ while((DWT->CYCCNT - start) < time_ticks) {
+ };
+}
+
+// cannot be used in ISR
+// TODO add delay_ISR variant
+void delay(float milliseconds) {
+ uint32_t ticks = milliseconds / (1000.0f / osKernelGetTickFreq());
+ osStatus_t result = osDelay(ticks);
+ assert(result == osOK);
+}
\ No newline at end of file
diff --git a/firmware/targets/f3/api-hal/api-hal-delay.h b/firmware/targets/f3/api-hal/api-hal-delay.h
new file mode 100644
index 00000000..9ab51e24
--- /dev/null
+++ b/firmware/targets/f3/api-hal/api-hal-delay.h
@@ -0,0 +1,6 @@
+#pragma once
+#include "main.h"
+
+void delay(float milliseconds);
+void delay_us(float microseconds);
+void delay_us_init_DWT(void);
diff --git a/firmware/targets/f3/api-hal/api-hal-gpio.c b/firmware/targets/f3/api-hal/api-hal-gpio.c
new file mode 100644
index 00000000..cf886353
--- /dev/null
+++ b/firmware/targets/f3/api-hal/api-hal-gpio.c
@@ -0,0 +1,14 @@
+#include "api-hal-gpio.h"
+
+// init GPIO
+void hal_gpio_init(GpioPin* gpio, GpioMode mode, GpioPull pull, GpioSpeed speed) {
+ // TODO: Alternate Functions
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ GPIO_InitStruct.Pin = gpio->pin;
+ GPIO_InitStruct.Mode = mode;
+ GPIO_InitStruct.Pull = pull;
+ GPIO_InitStruct.Speed = speed;
+
+ HAL_GPIO_Init(gpio->port, &GPIO_InitStruct);
+}
diff --git a/firmware/targets/f3/api-hal/api-hal-gpio.h b/firmware/targets/f3/api-hal/api-hal-gpio.h
new file mode 100644
index 00000000..b125a445
--- /dev/null
+++ b/firmware/targets/f3/api-hal/api-hal-gpio.h
@@ -0,0 +1,61 @@
+#pragma once
+#include "main.h"
+#include "stdbool.h"
+
+// this defined in xx_hal_gpio.c, so...
+#define GPIO_NUMBER (16U)
+
+typedef enum {
+ GpioModeInput = GPIO_MODE_INPUT,
+ GpioModeOutputPushPull = GPIO_MODE_OUTPUT_PP,
+ GpioModeOutputOpenDrain = GPIO_MODE_OUTPUT_OD,
+ GpioModeAltFunctionPushPull = GPIO_MODE_AF_PP,
+ GpioModeAltFunctionOpenDrain = GPIO_MODE_AF_OD,
+ GpioModeAnalog = GPIO_MODE_ANALOG,
+ GpioModeInterruptRise = GPIO_MODE_IT_RISING,
+ GpioModeInterruptFall = GPIO_MODE_IT_FALLING,
+ GpioModeInterruptRiseFall = GPIO_MODE_IT_RISING_FALLING,
+ GpioModeEventRise = GPIO_MODE_EVT_RISING,
+ GpioModeEventFall = GPIO_MODE_EVT_FALLING,
+ GpioModeEventRiseFall = GPIO_MODE_EVT_RISING_FALLING,
+} GpioMode;
+
+typedef enum {
+ GpioSpeedLow = GPIO_SPEED_FREQ_LOW,
+ GpioSpeedMedium = GPIO_SPEED_FREQ_MEDIUM,
+ GpioSpeedHigh = GPIO_SPEED_FREQ_HIGH,
+ GpioSpeedVeryHigh = GPIO_SPEED_FREQ_VERY_HIGH,
+} GpioSpeed;
+
+typedef enum {
+ GpioPullNo = GPIO_NOPULL,
+ GpioPullUp = GPIO_PULLUP,
+ GpioPullDown = GPIO_PULLDOWN,
+} GpioPull;
+
+typedef struct {
+ GPIO_TypeDef* port;
+ uint16_t pin;
+} GpioPin;
+
+// init GPIO
+void hal_gpio_init(GpioPin* gpio, GpioMode mode, GpioPull pull, GpioSpeed speed);
+
+// write value to GPIO, false = LOW, true = HIGH
+static inline void hal_gpio_write(GpioPin* gpio, bool state) {
+ // writing to BSSR is an atomic operation
+ if(state == true) {
+ gpio->port->BSRR = gpio->pin;
+ } else {
+ gpio->port->BSRR = (uint32_t)gpio->pin << GPIO_NUMBER;
+ }
+}
+
+// read value from GPIO, false = LOW, true = HIGH
+static inline bool hal_gpio_read(const GpioPin* gpio) {
+ if((gpio->port->IDR & gpio->pin) != 0x00U) {
+ return true;
+ } else {
+ return false;
+ }
+}
\ No newline at end of file
diff --git a/firmware/targets/f3/api-hal/api-hal-pwm.c b/firmware/targets/f3/api-hal/api-hal-pwm.c
new file mode 100644
index 00000000..d198e552
--- /dev/null
+++ b/firmware/targets/f3/api-hal/api-hal-pwm.c
@@ -0,0 +1,57 @@
+#include "api-hal-pwm.h"
+
+void hal_pwm_set(float value, float freq, TIM_HandleTypeDef* tim, uint32_t channel) {
+ tim->Init.CounterMode = TIM_COUNTERMODE_UP;
+ tim->Init.Period = (uint32_t)((SystemCoreClock / (tim->Init.Prescaler + 1)) / freq);
+ tim->Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+ tim->Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
+ HAL_TIM_PWM_Init(tim);
+
+ TIM_OC_InitTypeDef sConfigOC;
+
+ sConfigOC.OCMode = TIM_OCMODE_PWM1;
+ sConfigOC.Pulse = (uint16_t)(tim->Init.Period * value);
+ sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
+ sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
+ sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
+ sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
+ sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
+ HAL_TIM_PWM_ConfigChannel(tim, &sConfigOC, channel);
+ HAL_TIM_PWM_Start(tim, channel);
+}
+
+void hal_pwmn_set(float value, float freq, TIM_HandleTypeDef* tim, uint32_t channel) {
+ tim->Init.CounterMode = TIM_COUNTERMODE_UP;
+ tim->Init.Period = (uint32_t)((SystemCoreClock / (tim->Init.Prescaler + 1)) / freq - 1);
+ tim->Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+ tim->Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
+ HAL_TIM_PWM_Init(tim);
+
+ TIM_OC_InitTypeDef sConfigOC;
+
+ sConfigOC.OCMode = TIM_OCMODE_PWM1;
+ sConfigOC.Pulse = (uint16_t)(tim->Init.Period * value);
+ sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
+ sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
+ sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
+ sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
+ sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
+ HAL_TIM_PWM_ConfigChannel(tim, &sConfigOC, channel);
+ HAL_TIMEx_PWMN_Start(tim, channel);
+}
+
+void hal_pwm_stop(TIM_HandleTypeDef* tim, uint32_t channel) {
+ HAL_TIM_PWM_Stop(tim, channel);
+}
+
+void hal_pwmn_stop(TIM_HandleTypeDef* tim, uint32_t channel) {
+ HAL_TIMEx_PWMN_Stop(tim, channel);
+}
+
+void irda_pwm_set(float value, float freq){
+ hal_pwmn_set(value, freq, &IRDA_TIM, IRDA_CH);
+}
+
+void irda_pwm_stop(){
+ hal_pwmn_stop(&IRDA_TIM, IRDA_CH);
+}
\ No newline at end of file
diff --git a/firmware/targets/f3/api-hal/api-hal-pwm.h b/firmware/targets/f3/api-hal/api-hal-pwm.h
new file mode 100644
index 00000000..e712ca16
--- /dev/null
+++ b/firmware/targets/f3/api-hal/api-hal-pwm.h
@@ -0,0 +1,11 @@
+#pragma once
+#include "main.h"
+#include "stdbool.h"
+
+void hal_pwm_set(float value, float freq, TIM_HandleTypeDef* tim, uint32_t channel);
+void hal_pwmn_set(float value, float freq, TIM_HandleTypeDef* tim, uint32_t channel);
+void hal_pwm_stop(TIM_HandleTypeDef* tim, uint32_t channel);
+void hal_pwmn_stop(TIM_HandleTypeDef* tim, uint32_t channel);
+
+void irda_pwm_set(float value, float freq);
+void irda_pwm_stop();
\ No newline at end of file
diff --git a/firmware/targets/f3/api-hal/api-hal-resources.c b/firmware/targets/f3/api-hal/api-hal-resources.c
new file mode 100644
index 00000000..65e69635
--- /dev/null
+++ b/firmware/targets/f3/api-hal/api-hal-resources.c
@@ -0,0 +1,27 @@
+#include "main.h"
+#include "flipper_v2.h"
+
+const GpioPin input_gpio[GPIO_INPUT_PINS_COUNT] = {
+ {BUTTON_UP_GPIO_Port, BUTTON_UP_Pin},
+ {BUTTON_DOWN_GPIO_Port, BUTTON_DOWN_Pin},
+ {BUTTON_RIGHT_GPIO_Port, BUTTON_RIGHT_Pin},
+ {BUTTON_LEFT_GPIO_Port, BUTTON_LEFT_Pin},
+ {BUTTON_OK_GPIO_Port, BUTTON_OK_Pin},
+ {BUTTON_BACK_GPIO_Port, BUTTON_BACK_Pin},
+};
+
+const bool input_invert[GPIO_INPUT_PINS_COUNT] = {
+ true, // {BUTTON_UP_GPIO_Port, BUTTON_UP_Pin},
+ true, // {BUTTON_DOWN_GPIO_Port, BUTTON_DOWN_Pin},
+ true, // {BUTTON_RIGHT_GPIO_Port, BUTTON_RIGHT_Pin},
+ true, // {BUTTON_LEFT_GPIO_Port, BUTTON_LEFT_Pin},
+ true, // {BUTTON_OK_GPIO_Port, BUTTON_OK_Pin},
+ true, // {BUTTON_BACK_GPIO_Port, BUTTON_BACK_Pin},
+};
+
+const GpioPin led_gpio[3] = {
+ {LED_RED_GPIO_Port, LED_RED_Pin},
+ {LED_GREEN_GPIO_Port, LED_GREEN_Pin},
+ {LED_BLUE_GPIO_Port, LED_BLUE_Pin}};
+
+const GpioPin backlight_gpio = {DISPLAY_BACKLIGHT_GPIO_Port, DISPLAY_BACKLIGHT_Pin};
\ No newline at end of file
diff --git a/firmware/targets/f3/api-hal/api-hal-resources.h b/firmware/targets/f3/api-hal/api-hal-resources.h
new file mode 100644
index 00000000..bed91abc
--- /dev/null
+++ b/firmware/targets/f3/api-hal/api-hal-resources.h
@@ -0,0 +1,12 @@
+#pragma once
+#include "main.h"
+#include "flipper_v2.h"
+
+#define DEBOUNCE_TICKS 10
+#define GPIO_INPUT_PINS_COUNT 6
+
+extern const GpioPin input_gpio[GPIO_INPUT_PINS_COUNT];
+extern const bool input_invert[GPIO_INPUT_PINS_COUNT];
+
+extern const GpioPin led_gpio[3];
+extern const GpioPin backlight_gpio;
\ No newline at end of file
diff --git a/firmware/targets/f3/api-hal/api-hal-task.c b/firmware/targets/f3/api-hal/api-hal-task.c
new file mode 100644
index 00000000..263bc797
--- /dev/null
+++ b/firmware/targets/f3/api-hal/api-hal-task.c
@@ -0,0 +1,59 @@
+#include "cmsis_os.h"
+#include "api-hal-task.h"
+
+//-----------------------------cmsis_os2.c-------------------------------
+// helpers to get isr context
+// get arch
+#ifndef __ARM_ARCH_6M__
+#define __ARM_ARCH_6M__ 0
+#endif
+#ifndef __ARM_ARCH_7M__
+#define __ARM_ARCH_7M__ 0
+#endif
+#ifndef __ARM_ARCH_7EM__
+#define __ARM_ARCH_7EM__ 0
+#endif
+#ifndef __ARM_ARCH_8M_MAIN__
+#define __ARM_ARCH_8M_MAIN__ 0
+#endif
+#ifndef __ARM_ARCH_7A__
+#define __ARM_ARCH_7A__ 0
+#endif
+
+// get masks
+#if((__ARM_ARCH_7M__ == 1U) || (__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M_MAIN__ == 1U))
+#define IS_IRQ_MASKED() ((__get_PRIMASK() != 0U) || (__get_BASEPRI() != 0U))
+#elif(__ARM_ARCH_6M__ == 1U)
+#define IS_IRQ_MASKED() (__get_PRIMASK() != 0U)
+#elif(__ARM_ARCH_7A__ == 1U)
+/* CPSR mask bits */
+#define CPSR_MASKBIT_I 0x80U
+
+#define IS_IRQ_MASKED() ((__get_CPSR() & CPSR_MASKBIT_I) != 0U)
+#else
+#define IS_IRQ_MASKED() (__get_PRIMASK() != 0U)
+#endif
+
+// get is irq mode
+#if(__ARM_ARCH_7A__ == 1U)
+/* CPSR mode bitmasks */
+#define CPSR_MODE_USER 0x10U
+#define CPSR_MODE_SYSTEM 0x1FU
+
+#define IS_IRQ_MODE() ((__get_mode() != CPSR_MODE_USER) && (__get_mode() != CPSR_MODE_SYSTEM))
+#else
+#define IS_IRQ_MODE() (__get_IPSR() != 0U)
+#endif
+
+// added osKernelGetState(), because KernelState is a static var
+#define IS_IRQ() (IS_IRQ_MODE() || (IS_IRQ_MASKED() && (osKernelGetState() == osKernelRunning)))
+//-------------------------end of cmsis_os2.c----------------------------
+
+bool task_is_isr_context(void) {
+ return IS_IRQ();
+}
+
+bool task_equal(TaskHandle_t a, TaskHandle_t b) {
+ if(a == NULL || b == NULL) return false;
+ return a == b;
+}
\ No newline at end of file
diff --git a/firmware/targets/f3/api-hal/api-hal-task.h b/firmware/targets/f3/api-hal/api-hal-task.h
new file mode 100644
index 00000000..f1d015cb
--- /dev/null
+++ b/firmware/targets/f3/api-hal/api-hal-task.h
@@ -0,0 +1,7 @@
+#pragma once
+#include "main.h"
+#include
+#include
+
+bool task_equal(TaskHandle_t a, TaskHandle_t b);
+bool task_is_isr_context(void);
diff --git a/firmware/targets/f3/api-hal/api-hal.h b/firmware/targets/f3/api-hal/api-hal.h
new file mode 100644
index 00000000..68fb0bfb
--- /dev/null
+++ b/firmware/targets/f3/api-hal/api-hal.h
@@ -0,0 +1,6 @@
+#pragma once
+
+#include "api-hal-gpio.h"
+#include "api-hal-delay.h"
+#include "api-hal-pwm.h"
+#include "api-hal-task.h"
diff --git a/firmware/targets/f3/f3.ioc b/firmware/targets/f3/f3.ioc
new file mode 100644
index 00000000..a68bc4de
--- /dev/null
+++ b/firmware/targets/f3/f3.ioc
@@ -0,0 +1,553 @@
+#MicroXplorer Configuration settings - do not modify
+PA11.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
+PB13.GPIOParameters=GPIO_Label
+RCC.USART1Freq_Value=64000000
+RF1.Locked=true
+SPI1.VirtualType=VM_MASTER
+PB10.GPIO_PuPd=GPIO_PULLUP
+RF1.Signal=RF_RF1
+SPI2.VirtualType=VM_MASTER
+VP_ADC1_TempSens_Input.Mode=IN-TempSens
+PC12.Locked=true
+TIM1.IPParameters=Channel-Output Compare1 CH1N,Channel-PWM Generation3 CH3N
+PC12.Signal=GPIO_Output
+PB14.GPIO_Label=iBTN
+PC6.GPIO_Label=DISPLAY_DI
+VP_RTC_VS_RTC_Activate.Mode=RTC_Enabled
+RCC.RTCFreq_Value=32768
+PA3.GPIOParameters=GPIO_Speed,PinState,GPIO_Label,GPIO_ModeDefaultOutputPP
+PA6.GPIO_Label=PA6
+PD0.Locked=true
+PC5.Mode=INP
+USART1.IPParameters=VirtualMode-Asynchronous
+PA3.GPIO_Speed=GPIO_SPEED_FREQ_LOW
+PB13.Signal=TIM1_CH1N
+PA2.GPIOParameters=GPIO_Speed,PinState,GPIO_Label,GPIO_ModeDefaultOutputPP
+PC15-OSC32_OUT.GPIO_Label=QUARTZ_32MHZ_OUT
+PinOutPanel.RotationAngle=0
+RCC.MCO1PinFreq_Value=64000000
+RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
+SH.GPXTI13.0=GPIO_EXTI13
+RCC.LPTIM1Freq_Value=64000000
+NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:false\:false\:false\:false
+FREERTOS.configENABLE_FPU=1
+NVIC.EXTI1_IRQn=true\:5\:0\:true\:false\:true\:false\:true\:true
+SH.S_TIM16_CH1.ConfNb=1
+SPI1.Direction=SPI_DIRECTION_2LINES
+TIM2.IPParameters=Channel-Input_Capture1_from_TI1,ICPolarity_CH1,AutoReloadPreload,Prescaler,Channel-Input_Capture2_from_TI1
+RCC.APB2TimFreq_Value=64000000
+PCC.Ble.PowerLevel=Min
+PB6.Signal=USART1_TX
+PB6.Mode=Asynchronous
+SPI1.CalculateBaudRate=4.0 MBits/s
+PC3.Signal=GPIO_Analog
+PD0.Signal=GPIO_Output
+VP_TIM2_VS_ClockSourceINT.Signal=TIM2_VS_ClockSourceINT
+RCC.PREFETCH_ENABLE=1
+PB13.Locked=true
+NVIC.EXTI15_10_IRQn=true\:5\:0\:true\:false\:true\:false\:true\:true
+ProjectManager.ProjectBuild=false
+NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+PB2.Signal=GPIO_Analog
+PB3.Mode=Full_Duplex_Master
+PH3-BOOT0.Locked=true
+PA8.Locked=true
+PD1.GPIOParameters=GPIO_Label
+RCC.RTCClockSelection=RCC_RTCCLKSOURCE_LSE
+SH.GPXTI12.0=GPIO_EXTI12
+PD1.GPIO_Label=SPI_D_SCK
+PB12.GPIO_Label=BUTTON_RIGHT
+ProjectManager.FirmwarePackage=STM32Cube FW_WB V1.9.0
+VP_ADC1_Vref_Input.Mode=IN-Vrefint
+MxDb.Version=DB.6.0.0
+PB0.GPIOParameters=GPIO_Label
+PA1.GPIOParameters=GPIO_Speed,PinState,GPIO_Label,GPIO_ModeDefaultOutputPP
+ProjectManager.BackupPrevious=false
+VP_SYS_VS_tim17.Signal=SYS_VS_tim17
+PC4.GPIO_Label=CC1101_G0
+FREERTOS.HEAP_NUMBER=4
+PB1.GPIO_Label=BUTTON_DOWN
+NVIC.TIM2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true
+SPI1.DataSize=SPI_DATASIZE_8BIT
+PE4.GPIO_Label=NFC_CS
+SPI2.CalculateBaudRate=4.0 MBits/s
+PA8.Signal=GPXTI8
+RCC.PLLRCLKFreq_Value=64000000
+SH.GPXTI11.ConfNb=1
+PB6.Locked=true
+NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:false\:false\:false\:false
+ProjectManager.HalAssertFull=false
+ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5
+VP_TIM1_VS_ClockSourceINT.Mode=Internal
+TIM16.Pulse=145
+PA0.Signal=S_TIM2_CH1
+PH3-BOOT0.Signal=GPIO_Analog
+NVIC.HSEM_IRQn=true\:5\:0\:true\:false\:true\:true\:false\:true
+PB9.Signal=TIM1_CH3N
+Mcu.Package=VFQFPN68
+TIM2.Prescaler=64-1
+PB1.Signal=GPXTI1
+NVIC.TimeBase=TIM1_TRG_COM_TIM17_IRQn
+SPI2.Mode=SPI_MODE_MASTER
+PA2.GPIO_ModeDefaultOutputPP=GPIO_MODE_OUTPUT_OD
+SH.GPXTI11.0=GPIO_EXTI11
+SH.GPXTI8.0=GPIO_EXTI8
+PA14.Locked=true
+SH.GPXTI8.ConfNb=1
+NVIC.TimeBaseIP=TIM17
+RCC.LSCOPinFreq_Value=32000
+PA10.Signal=I2C1_SDA
+VP_RTC_VS_RTC_Calendar.Mode=RTC_Calendar
+FREERTOS.FootprintOK=true
+PA1.PinState=GPIO_PIN_SET
+PA5.GPIOParameters=GPIO_Label
+NVIC.USB_LP_IRQn=true\:5\:0\:true\:false\:true\:true\:false\:true
+PB14.GPIOParameters=GPIO_Label
+VP_HSEM_VS_HSEM.Mode=HSEM_Activate
+NVIC.EXTI2_IRQn=true\:5\:0\:true\:false\:true\:false\:true\:true
+RCC.PLLPoutputFreq_Value=64000000
+RCC.APB1TimFreq_Value=64000000
+FREERTOS.configGENERATE_RUN_TIME_STATS=1
+NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+RCC.LPUART1Freq_Value=64000000
+PB10.GPIOParameters=GPIO_PuPd,GPIO_Label,GPIO_ModeDefaultEXTI
+PB13.Mode=Output Compare1 CH1N
+TIM16.Prescaler=500 - 1
+PC15-OSC32_OUT.GPIOParameters=GPIO_Label
+I2C1.CustomTiming=Disabled
+PA4.GPIO_Label=PA4
+ProjectManager.CustomerFirmwarePackage=
+PC4.GPIOParameters=GPIO_Label
+RCC.HSI48_VALUE=48000000
+PC2.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_RISING_FALLING
+PA6.GPIOParameters=GPIO_Label
+SH.GPXTI10.0=GPIO_EXTI10
+PCC.Ble.Mode=NOT_SELECTED
+RCC.PLLQoutputFreq_Value=64000000
+ProjectManager.ProjectFileName=f3.ioc
+RCC.SMPSFreq_Value=8000000
+PA3.GPIO_ModeDefaultOutputPP=GPIO_MODE_OUTPUT_OD
+FREERTOS.Tasks01=defaultTask,24,1024,StartDefaultTask,Default,NULL,Dynamic,NULL,NULL;app_main,8,1024,app,As external,NULL,Dynamic,NULL,NULL
+ADC1.Rank-0\#ChannelRegularConversion=1
+PA15.GPIOParameters=GPIO_PuPd,GPIO_Label
+Mcu.PinsNb=64
+PC11.Locked=true
+VP_SYS_VS_tim17.Mode=TIM17
+ADC1.IPParameters=Rank-0\#ChannelRegularConversion,Channel-0\#ChannelRegularConversion,SamplingTime-0\#ChannelRegularConversion,OffsetNumber-0\#ChannelRegularConversion,NbrOfConversionFlag,master
+PC13.Locked=true
+ADC1.OffsetNumber-0\#ChannelRegularConversion=ADC_OFFSET_NONE
+RCC.HCLK3Freq_Value=64000000
+PA9.GPIO_Label=I2C_SCL
+PC13.Signal=GPXTI13
+FREERTOS.configCHECK_FOR_STACK_OVERFLOW=1
+PC2.Signal=GPXTI2
+PC6.Signal=GPIO_Output
+PB11.GPIO_Label=BUTTON_LEFT
+PD1.Signal=SPI2_SCK
+SH.S_TIM16_CH1.0=TIM16_CH1,PWM Generation1 CH1
+VP_TIM16_VS_ClockSourceINT.Mode=Enable_Timer
+SPI1.CLKPhase=SPI_PHASE_2EDGE
+OSC_IN.Locked=true
+RCC.HCLK2Freq_Value=32000000
+PC0.Signal=GPIO_Analog
+PC14-OSC32_IN.Signal=RCC_OSC32_IN
+PC11.GPIOParameters=PinState,GPIO_Label
+Mcu.Pin62=VP_TIM16_VS_ClockSourceINT
+Mcu.Pin63=VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS
+Mcu.Pin60=VP_TIM1_VS_ClockSourceINT
+Mcu.Pin61=VP_TIM2_VS_ClockSourceINT
+PD0.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
+PC3.GPIOParameters=GPIO_Label
+PB8.GPIO_Label=SPEAKER
+PA11.Locked=true
+PA15.Locked=true
+PA8.GPIO_Label=RFID_PULL
+PC15-OSC32_OUT.Locked=true
+Mcu.Pin59=VP_SYS_VS_tim17
+SH.GPXTI2.ConfNb=1
+Mcu.Pin57=VP_RTC_VS_RTC_Activate
+Mcu.Pin58=VP_RTC_VS_RTC_Calendar
+PC12.PinState=GPIO_PIN_SET
+USB_DEVICE.PRODUCT_STRING_CDC_FS=Flipper Control Virtual ComPort
+Mcu.Pin51=PB7
+Mcu.Pin52=VP_ADC1_TempSens_Input
+Mcu.Pin50=PB6
+Mcu.Pin55=VP_FREERTOS_VS_CMSIS_V2
+Mcu.Pin56=VP_HSEM_VS_HSEM
+Mcu.Pin53=VP_ADC1_Vref_Input
+Mcu.Pin54=VP_COMP1_VS_VREFINT12
+PC6.Locked=true
+PA9.Signal=I2C1_SCL
+VP_TIM1_VS_ClockSourceINT.Signal=TIM1_VS_ClockSourceINT
+I2C1.Timing=0x10707DBC
+PB11.GPIOParameters=GPIO_PuPd,GPIO_Label,GPIO_ModeDefaultEXTI
+PB9.Locked=true
+PB5.Locked=true
+OSC_IN.Signal=RCC_OSC_IN
+Mcu.Pin48=PB4
+Mcu.Pin49=PB5
+RCC.PLLSAI1PoutputFreq_Value=48000000
+Mcu.Pin46=PD1
+Mcu.Pin47=PB3
+PB10.Signal=GPXTI10
+PB14.Signal=GPIO_Analog
+PA5.Signal=GPIO_Analog
+Mcu.Pin40=PA14
+Mcu.Pin41=PA15
+Mcu.Pin44=PC12
+Mcu.Pin45=PD0
+Mcu.Pin42=PC10
+Mcu.Pin43=PC11
+RCC.Cortex2Freq_Value=32000000
+ProjectManager.LastFirmware=true
+PD1.Mode=TX_Only_Simplex_Unidirect_Master
+Mcu.Pin37=PA11
+PB4.GPIO_Label=SPI_R_MISO
+PCC.Ble.DataLength=6
+Mcu.Pin38=PA12
+Mcu.Pin35=PC6
+PB15.GPIO_Label=SPI_D_MOSI
+RCC.I2C1Freq_Value=64000000
+Mcu.Pin36=PA10
+SPI1.Mode=SPI_MODE_MASTER
+Mcu.Pin39=PA13
+RCC.LCDFreq_Value=32768
+RCC.RNGFreq_Value=32000
+PC2.GPIOParameters=GPIO_PuPd,GPIO_Label,GPIO_ModeDefaultEXTI
+VP_ADC1_TempSens_Input.Signal=ADC1_TempSens_Input
+Mcu.Pin30=PE4
+PA1.GPIO_Label=LED_RED
+Mcu.Pin33=PB14
+Mcu.Pin34=PB15
+Mcu.Pin31=PB12
+Mcu.Pin32=PB13
+PA9.Locked=true
+VP_TIM16_VS_ClockSourceINT.Signal=TIM16_VS_ClockSourceINT
+NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
+PC10.GPIOParameters=GPIO_Label
+PA13.Mode=Serial_Wire
+ProjectManager.FreePins=false
+PB10.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_RISING_FALLING
+RCC.LPTIM2Freq_Value=64000000
+Mcu.Pin26=OSC_OUT
+Mcu.Pin27=OSC_IN
+Mcu.Pin24=PB11
+ProjectManager.UnderRoot=false
+Mcu.Pin25=RF1
+Mcu.Pin28=PB0
+Mcu.Pin29=PB1
+PB4.Locked=true
+PA4.Signal=GPIO_Analog
+Mcu.Pin22=PB2
+PB5.Signal=SPI1_MOSI
+Mcu.Pin23=PB10
+Mcu.Pin20=PC4
+ADC1.master=1
+PA3.Locked=true
+Mcu.Pin21=PC5
+PA5.GPIO_Label=PA5
+PA10.Locked=true
+NVIC.ForceEnableDMAVector=true
+OSC_IN.Mode=HSE-External-Oscillator
+NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+PC12.GPIO_Label=SD_CS
+ProjectManager.CompilerOptimize=6
+PA11.Signal=USB_DM
+ProjectManager.HeapSize=0x200
+PA0.GPIOParameters=GPIO_Label
+Mcu.Pin15=PA5
+NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+Mcu.Pin16=PA6
+Mcu.Pin13=PA3
+Mcu.Pin14=PA4
+Mcu.Pin19=PA9
+ProjectManager.ComputerToolchain=false
+Mcu.Pin17=PA7
+Mcu.Pin18=PA8
+NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
+Mcu.Pin11=PA1
+Mcu.Pin12=PA2
+PD0.GPIOParameters=GPIO_Speed,PinState,GPIO_Label
+Mcu.Pin10=PA0
+SH.GPXTI10.ConfNb=1
+TIM2.AutoReloadPreload=TIM_AUTORELOAD_PRELOAD_ENABLE
+PC3.GPIO_Label=PC3
+PA3.PinState=GPIO_PIN_SET
+PE4.PinState=GPIO_PIN_SET
+RCC.PWRFreq_Value=64000000
+SPI2.DataSize=SPI_DATASIZE_8BIT
+SH.GPXTI1.ConfNb=1
+PB12.GPIO_PuPd=GPIO_PULLUP
+PD1.Locked=true
+PB0.Signal=GPIO_Output
+PA7.GPIOParameters=GPIO_Label
+PC1.Signal=GPIO_Analog
+PB12.GPIOParameters=GPIO_PuPd,GPIO_Label,GPIO_ModeDefaultEXTI
+Mcu.Family=STM32WB
+SH.GPXTI1.0=GPIO_EXTI1
+ProjectManager.MainLocation=Src
+OSC_OUT.GPIO_Label=QUARTZ_32KHZ_OUT
+USB_DEVICE.CLASS_NAME_FS=CDC
+RCC.SAI1Freq_Value=48000000
+RCC.CortexFreq_Value=64000000
+TIM2.Channel-Input_Capture1_from_TI1=TIM_CHANNEL_1
+ProjectManager.KeepUserCode=true
+Mcu.UserName=STM32WB55RGVx
+RCC.RFWKPFreq_Value=976.5625
+PC10.Signal=GPIO_Analog
+RCC.PLLSAI1RoutputFreq_Value=48000000
+PC5.Locked=true
+PA0.GPIO_Label=IR_RX
+PA12.GPIOParameters=GPIO_Speed
+ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-SystemClock_Config-RCC-false-HAL-false,3-MX_ADC1_Init-ADC1-false-HAL-true,4-MX_I2C1_Init-I2C1-false-HAL-true,5-MX_RTC_Init-RTC-false-HAL-true,6-MX_SPI1_Init-SPI1-false-HAL-true,7-MX_SPI2_Init-SPI2-false-HAL-true,8-MX_USART1_UART_Init-USART1-false-HAL-true,9-MX_USB_Device_Init-USB_DEVICE-false-HAL-false,10-MX_TIM1_Init-TIM1-false-HAL-true,11-MX_TIM2_Init-TIM2-false-HAL-true,12-MX_TIM16_Init-TIM16-false-HAL-true,13-MX_COMP1_Init-COMP1-false-HAL-true,14-MX_RF_Init-RF-false-HAL-true,0-MX_HSEM_Init-HSEM-false-HAL-true
+PC0.GPIOParameters=GPIO_Label
+PA9.GPIOParameters=GPIO_Speed,GPIO_Label
+PA2.GPIO_Speed=GPIO_SPEED_FREQ_LOW
+PH3-BOOT0.GPIO_Label=BOOT0
+PA11.GPIOParameters=GPIO_Speed
+PD0.GPIO_Label=CC1101_CS
+PC0.GPIO_Label=PC0
+PA11.Mode=Device
+PB0.GPIO_Label=DISPLAY_RST
+VP_RTC_VS_RTC_Calendar.Signal=RTC_VS_RTC_Calendar
+PB11.GPIO_PuPd=GPIO_PULLUP
+VP_COMP1_VS_VREFINT12.Signal=COMP1_VS_VREFINT12
+PC13.GPIO_Label=BUTTON_BACK
+PB13.GPIO_Label=RFID_OUT
+PB11.Signal=GPXTI11
+PB15.Signal=SPI2_MOSI
+OSC_OUT.GPIOParameters=GPIO_Label
+ProjectManager.StackSize=0x400
+PB5.GPIOParameters=GPIO_Label
+VP_FREERTOS_VS_CMSIS_V2.Mode=CMSIS_V2
+SH.GPXTI2.0=GPIO_EXTI2
+RCC.I2C3Freq_Value=64000000
+Mcu.IP4=I2C1
+Mcu.IP5=NVIC
+RCC.FCLKCortexFreq_Value=64000000
+USB_DEVICE.MANUFACTURER_STRING=Flipper
+Mcu.IP2=FREERTOS
+I2C1.IPParameters=Timing,CustomTiming
+Mcu.IP3=HSEM
+Mcu.IP0=ADC1
+PB4.GPIOParameters=GPIO_Label
+PA15.GPIO_Label=DISPLAY_BACKLIGHT
+PA12.Locked=true
+Mcu.IP1=COMP1
+PA12.Signal=USB_DP
+PE4.GPIOParameters=GPIO_Speed,PinState,GPIO_Label
+Mcu.UserConstants=
+RCC.VCOSAI1OutputFreq_Value=96000000
+TIM2.ICPolarity_CH1=TIM_INPUTCHANNELPOLARITY_FALLING
+PC1.GPIOParameters=GPIO_Label
+SH.GPXTI13.ConfNb=1
+Mcu.ThirdPartyNb=0
+PB1.GPIO_PuPd=GPIO_PULLUP
+RCC.HCLKFreq_Value=64000000
+Mcu.IPNb=18
+ProjectManager.PreviousToolchain=
+PB1.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_RISING_FALLING
+PA8.GPIOParameters=GPIO_Label
+Mcu.Pin6=PC0
+Mcu.Pin7=PC1
+Mcu.Pin8=PC2
+Mcu.Pin9=PC3
+OSC_OUT.Mode=HSE-External-Oscillator
+FREERTOS.IPParameters=Tasks01,configTOTAL_HEAP_SIZE,HEAP_NUMBER,configUSE_TIMERS,configUSE_IDLE_HOOK,FootprintOK,configCHECK_FOR_STACK_OVERFLOW,configRECORD_STACK_HIGH_ADDRESS,configGENERATE_RUN_TIME_STATS,configENABLE_FPU
+OSC_OUT.Signal=RCC_OSC_OUT
+RCC.AHBFreq_Value=64000000
+SPI2.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_16
+Mcu.Pin0=PC13
+Mcu.Pin1=PC14-OSC32_IN
+GPIO.groupedBy=Show All
+Mcu.Pin2=PC15-OSC32_OUT
+Mcu.Pin3=PH3-BOOT0
+Mcu.Pin4=PB8
+Mcu.Pin5=PB9
+ADC1.Channel-0\#ChannelRegularConversion=ADC_CHANNEL_TEMPSENSOR
+RCC.HSE_VALUE=32000000
+RCC.FCLK2Freq_Value=32000000
+FREERTOS.configUSE_TIMERS=1
+NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+PH3-BOOT0.GPIOParameters=GPIO_Label
+Mcu.IP10=SPI2
+NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:false\:false\:false\:false
+Mcu.IP12=TIM1
+Mcu.IP11=SYS
+Mcu.IP17=USB_DEVICE
+NVIC.TIM1_TRG_COM_TIM17_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
+PA2.PinState=GPIO_PIN_SET
+Mcu.IP14=TIM16
+PB4.Mode=Full_Duplex_Master
+Mcu.IP13=TIM2
+Mcu.IP16=USB
+Mcu.IP15=USART1
+PC14-OSC32_IN.Mode=LSE-External-Oscillator
+RCC.VCOInputFreq_Value=16000000
+PD0.PinState=GPIO_PIN_SET
+PA14.Mode=Serial_Wire
+PE4.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
+PC11.GPIO_Label=DISPLAY_CS
+PB5.Mode=Full_Duplex_Master
+File.Version=6
+PA10.GPIO_Label=I2C_SDA
+PC13.GPIO_PuPd=GPIO_PULLUP
+PB3.GPIOParameters=GPIO_Label
+SH.S_TIM2_CH1.ConfNb=2
+PB7.Signal=USART1_RX
+PB8.Locked=true
+PE4.Signal=GPIO_Output
+PB0.Locked=true
+FREERTOS.configTOTAL_HEAP_SIZE=40960
+PC14-OSC32_IN.GPIOParameters=GPIO_Label
+VP_COMP1_VS_VREFINT12.Mode=VREFINT_12
+ProjectManager.ProjectName=f3
+RCC.APB3Freq_Value=16000000
+PA6.Signal=GPIO_Analog
+TIM2.Channel-Input_Capture2_from_TI1=TIM_CHANNEL_2
+RCC.EnbaleCSS=true
+ProjectManager.ToolChainLocation=
+PA2.GPIO_Label=LED_GREEN
+RCC.LSI_VALUE=32000
+PB11.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_RISING_FALLING
+PA15.Signal=GPIO_Output
+VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS.Signal=USB_DEVICE_VS_USB_DEVICE_CDC_FS
+RCC.MSIOscState=DISABLED
+SPI2.CLKPhase=SPI_PHASE_1EDGE
+PA10.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
+PB5.GPIO_Label=SPI_R_MOSI
+PC4.Locked=true
+PC14-OSC32_IN.GPIO_Label=QUARTZ_32MHZ_IN
+SPI2.Direction=SPI_DIRECTION_2LINES
+PC5.Signal=COMP1_INP
+SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_16
+OSC_IN.GPIO_Label=QUARTZ_32KHZ_IN
+PC2.GPIO_Label=BUTTON_OK
+PC14-OSC32_IN.Locked=true
+PA12.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
+PB15.Locked=true
+PB3.Locked=true
+PB4.Signal=SPI1_MISO
+RCC.PLLSAI1N=6
+PA3.Signal=GPIO_Output
+PA2.Locked=true
+PB3.GPIO_Label=SPI_R_SCK
+VP_RTC_VS_RTC_Activate.Signal=RTC_VS_RTC_Activate
+RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
+PC15-OSC32_OUT.Mode=LSE-External-Oscillator
+SH.S_TIM2_CH1.1=TIM2_CH1,Input_Capture2_from_TI1
+SH.S_TIM2_CH1.0=TIM2_CH1,Input_Capture1_from_TI1
+PB8.GPIOParameters=GPIO_Label
+PB9.GPIO_Label=IR_TX
+PC10.GPIO_Label=PC10
+PA10.Mode=I2C
+ProjectManager.NoMain=false
+SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,BaudRatePrescaler,DataSize,CLKPhase
+USB_DEVICE.VirtualModeFS=Cdc_FS
+NVIC.SavedSvcallIrqHandlerGenerated=false
+PC11.Signal=GPIO_Output
+PC4.Signal=GPIO_Input
+ProjectManager.DefaultFWLocation=true
+VP_HSEM_VS_HSEM.Signal=HSEM_VS_HSEM
+OSC_IN.GPIOParameters=GPIO_Label
+PB12.Locked=true
+ProjectManager.DeletePrevious=true
+PB10.Locked=true
+USB_DEVICE.IPParameters=VirtualMode,VirtualModeFS,CLASS_NAME_FS,MANUFACTURER_STRING,PRODUCT_STRING_CDC_FS
+TIM16.Channel=TIM_CHANNEL_1
+RCC.AHB2CLKDivider=RCC_SYSCLK_DIV2
+RCC.FamilyName=M
+PB9.GPIOParameters=GPIO_Label
+PC12.GPIOParameters=GPIO_Speed,PinState,GPIO_Label
+USART1.VirtualMode-Asynchronous=VM_ASYNC
+PA13.Signal=SYS_JTMS-SWDIO
+FREERTOS.configUSE_IDLE_HOOK=1
+PA9.Mode=I2C
+TIM1.Channel-Output\ Compare1\ CH1N=TIM_CHANNEL_1
+FREERTOS.configRECORD_STACK_HIGH_ADDRESS=1
+ProjectManager.TargetToolchain=Makefile
+PB10.GPIO_Label=BUTTON_UP
+VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS.Mode=CDC_FS
+RCC.HCLKRFFreq_Value=16000000
+PC5.GPIOParameters=GPIO_Label
+PB9.Mode=PWM Generation3 CH3N
+PB2.GPIOParameters=GPIO_Label
+SH.GPXTI12.ConfNb=1
+PE4.Locked=true
+SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,BaudRatePrescaler,CLKPhase
+PC2.Locked=true
+ProjectManager.RegisterCallBack=
+RCC.USBFreq_Value=48000000
+TIM1.Channel-PWM\ Generation3\ CH3N=TIM_CHANNEL_3
+PC15-OSC32_OUT.Signal=RCC_OSC32_OUT
+PA1.Signal=GPIO_Output
+PB1.Locked=true
+RCC.SMPSCLockSelectionVirtual=RCC_SMPSCLKSOURCE_HSE
+board=custom
+RCC.VCOOutputFreq_Value=128000000
+RCC.SMPS1Freq_Value=16000000
+PB15.Mode=TX_Only_Simplex_Unidirect_Master
+TIM16.Period=291
+NVIC.SavedSystickIrqHandlerGenerated=true
+RCC.APB2Freq_Value=64000000
+PC11.PinState=GPIO_PIN_SET
+MxCube.Version=6.0.1
+VP_TIM2_VS_ClockSourceINT.Mode=Internal
+PC13.GPIOParameters=GPIO_PuPd,GPIO_Label,GPIO_ModeDefaultEXTI
+PA1.GPIO_Speed=GPIO_SPEED_FREQ_LOW
+RCC.PLLSAI1QoutputFreq_Value=48000000
+RCC.ADCFreq_Value=48000000
+PC1.GPIO_Label=PC1
+PA10.GPIOParameters=GPIO_Speed,GPIO_Label
+VP_ADC1_Vref_Input.Signal=ADC1_Vref_Input
+OSC_OUT.Locked=true
+PA4.GPIOParameters=GPIO_Label
+PC2.GPIO_PuPd=GPIO_PULLUP
+PB15.GPIOParameters=GPIO_Label
+RCC.IPParameters=ADCFreq_Value,AHB2CLKDivider,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,APB3Freq_Value,Cortex2Freq_Value,CortexFreq_Value,EnbaleCSS,FCLK2Freq_Value,FCLKCortexFreq_Value,FamilyName,HCLK2Freq_Value,HCLK3Freq_Value,HCLKFreq_Value,HCLKRFFreq_Value,HSE_VALUE,HSI48_VALUE,HSI_VALUE,I2C1Freq_Value,I2C3Freq_Value,LCDFreq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPUART1Freq_Value,LSCOPinFreq_Value,LSI_VALUE,MCO1PinFreq_Value,MSIOscState,PLLM,PLLPoutputFreq_Value,PLLQoutputFreq_Value,PLLRCLKFreq_Value,PLLSAI1N,PLLSAI1PoutputFreq_Value,PLLSAI1QoutputFreq_Value,PLLSAI1RoutputFreq_Value,PLLSourceVirtual,PREFETCH_ENABLE,PWRFreq_Value,RFWKPFreq_Value,RNGFreq_Value,RTCClockSelection,RTCFreq_Value,SAI1Freq_Value,SMPS1Freq_Value,SMPSCLockSelectionVirtual,SMPSFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,USART1Freq_Value,USBFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VCOSAI1OutputFreq_Value
+ProjectManager.AskForMigrate=true
+Mcu.Name=STM32WB55RGVx
+NVIC.SavedPendsvIrqHandlerGenerated=false
+PA2.Signal=GPIO_Output
+Mcu.IP8=RTC
+VP_FREERTOS_VS_CMSIS_V2.Signal=FREERTOS_VS_CMSIS_V2
+Mcu.IP9=SPI1
+Mcu.IP6=RCC
+Mcu.IP7=RF
+ProjectManager.CoupleFile=true
+PB3.Signal=SPI1_SCK
+RCC.SYSCLKFreq_VALUE=64000000
+PA7.GPIO_Label=PA7
+PA1.Locked=true
+PA12.Mode=Device
+PCC.Ble.ConnectionInterval=1000.0
+KeepUserPlacement=false
+PC13.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_RISING_FALLING
+PC5.GPIO_Label=RFID_RF_IN
+PA13.Locked=true
+RF1.Mode=RF1_Activate
+PB7.Mode=Asynchronous
+NVIC.EXTI9_5_IRQn=true\:5\:0\:true\:false\:true\:false\:true\:true
+PA14.Signal=SYS_JTCK-SWCLK
+PB2.GPIO_Label=PB2
+PC6.GPIOParameters=GPIO_Label
+PB12.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_RISING_FALLING
+RCC.HSI_VALUE=16000000
+ADC1.NbrOfConversionFlag=1
+RCC.PLLM=RCC_PLLM_DIV2
+PA15.GPIO_PuPd=GPIO_PULLDOWN
+PB7.Locked=true
+PB8.Signal=S_TIM16_CH1
+PA9.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
+TIM16.IPParameters=Channel,Pulse,Prescaler,Period
+RCC.APB1Freq_Value=64000000
+PC12.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
+USB_DEVICE.VirtualMode=Cdc
+PB11.Locked=true
+ProjectManager.DeviceId=STM32WB55RGVx
+PB12.Signal=GPXTI12
+ProjectManager.LibraryCopy=2
+PA3.GPIO_Label=LED_BLUE
+PB1.GPIOParameters=GPIO_PuPd,GPIO_Label,GPIO_ModeDefaultEXTI
+PA7.Signal=GPIO_Analog
+PA1.GPIO_ModeDefaultOutputPP=GPIO_MODE_OUTPUT_OD
diff --git a/firmware/targets/f3/startup_stm32wb55xx_cm4.s b/firmware/targets/f3/startup_stm32wb55xx_cm4.s
new file mode 100644
index 00000000..295f58d9
--- /dev/null
+++ b/firmware/targets/f3/startup_stm32wb55xx_cm4.s
@@ -0,0 +1,445 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32wb55xx_cm4.s
+ * @author MCD Application Team
+ * @brief STM32WB55xx devices vector table GCC toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M4 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m4
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+/* start address for the .MB_MEM2 section. defined in linker script */
+.word _sMB_MEM2
+/* end address for the .MB_MEM2 section. defined in linker script */
+.word _eMB_MEM2
+
+/* INIT_BSS macro is used to fill the specified region [start : end] with zeros */
+.macro INIT_BSS start, end
+ ldr r0, =\start
+ ldr r1, =\end
+ movs r3, #0
+ bl LoopFillZerobss
+.endm
+
+/* INIT_DATA macro is used to copy data in the region [start : end] starting from 'src' */
+.macro INIT_DATA start, end, src
+ ldr r0, =\start
+ ldr r1, =\end
+ ldr r2, =\src
+ movs r3, #0
+ bl LoopCopyDataInit
+.endm
+
+.section .text.data_initializers
+CopyDataInit:
+ ldr r4, [r2, r3]
+ str r4, [r0, r3]
+ adds r3, r3, #4
+
+LoopCopyDataInit:
+ adds r4, r0, r3
+ cmp r4, r1
+ bcc CopyDataInit
+ bx lr
+
+FillZerobss:
+ str r3, [r0]
+ adds r0, r0, #4
+
+LoopFillZerobss:
+ cmp r0, r1
+ bcc FillZerobss
+ bx lr
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr r0, =_estack
+ mov sp, r0 /* set stack pointer */
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+
+/* Copy the data segment initializers from flash to SRAM */
+ INIT_DATA _sdata, _edata, _sidata
+
+/* Zero fill the bss segments. */
+ INIT_BSS _sbss, _ebss
+ INIT_BSS _sMB_MEM2, _eMB_MEM2
+
+/* Call static constructors */
+ bl __libc_init_array
+/* Call the application s entry point.*/
+ bl main
+
+LoopForever:
+ b LoopForever
+
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ *
+ * @param None
+ * @retval None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex-M4. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler
+ .word PVD_PVM_IRQHandler
+ .word TAMP_STAMP_LSECSS_IRQHandler
+ .word RTC_WKUP_IRQHandler
+ .word FLASH_IRQHandler
+ .word RCC_IRQHandler
+ .word EXTI0_IRQHandler
+ .word EXTI1_IRQHandler
+ .word EXTI2_IRQHandler
+ .word EXTI3_IRQHandler
+ .word EXTI4_IRQHandler
+ .word DMA1_Channel1_IRQHandler
+ .word DMA1_Channel2_IRQHandler
+ .word DMA1_Channel3_IRQHandler
+ .word DMA1_Channel4_IRQHandler
+ .word DMA1_Channel5_IRQHandler
+ .word DMA1_Channel6_IRQHandler
+ .word DMA1_Channel7_IRQHandler
+ .word ADC1_IRQHandler
+ .word USB_HP_IRQHandler
+ .word USB_LP_IRQHandler
+ .word C2SEV_PWR_C2H_IRQHandler
+ .word COMP_IRQHandler
+ .word EXTI9_5_IRQHandler
+ .word TIM1_BRK_IRQHandler
+ .word TIM1_UP_TIM16_IRQHandler
+ .word TIM1_TRG_COM_TIM17_IRQHandler
+ .word TIM1_CC_IRQHandler
+ .word TIM2_IRQHandler
+ .word PKA_IRQHandler
+ .word I2C1_EV_IRQHandler
+ .word I2C1_ER_IRQHandler
+ .word I2C3_EV_IRQHandler
+ .word I2C3_ER_IRQHandler
+ .word SPI1_IRQHandler
+ .word SPI2_IRQHandler
+ .word USART1_IRQHandler
+ .word LPUART1_IRQHandler
+ .word SAI1_IRQHandler
+ .word TSC_IRQHandler
+ .word EXTI15_10_IRQHandler
+ .word RTC_Alarm_IRQHandler
+ .word CRS_IRQHandler
+ .word PWR_SOTF_BLEACT_802ACT_RFPHASE_IRQHandler
+ .word IPCC_C1_RX_IRQHandler
+ .word IPCC_C1_TX_IRQHandler
+ .word HSEM_IRQHandler
+ .word LPTIM1_IRQHandler
+ .word LPTIM2_IRQHandler
+ .word LCD_IRQHandler
+ .word QUADSPI_IRQHandler
+ .word AES1_IRQHandler
+ .word AES2_IRQHandler
+ .word RNG_IRQHandler
+ .word FPU_IRQHandler
+ .word DMA2_Channel1_IRQHandler
+ .word DMA2_Channel2_IRQHandler
+ .word DMA2_Channel3_IRQHandler
+ .word DMA2_Channel4_IRQHandler
+ .word DMA2_Channel5_IRQHandler
+ .word DMA2_Channel6_IRQHandler
+ .word DMA2_Channel7_IRQHandler
+ .word DMAMUX1_OVR_IRQHandler
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_PVM_IRQHandler
+ .thumb_set PVD_PVM_IRQHandler,Default_Handler
+
+ .weak TAMP_STAMP_LSECSS_IRQHandler
+ .thumb_set TAMP_STAMP_LSECSS_IRQHandler,Default_Handler
+
+ .weak RTC_WKUP_IRQHandler
+ .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_IRQHandler
+ .thumb_set EXTI2_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_IRQHandler
+ .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel3_IRQHandler
+ .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_IRQHandler
+ .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel5_IRQHandler
+ .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel6_IRQHandler
+ .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel7_IRQHandler
+ .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+ .weak ADC1_IRQHandler
+ .thumb_set ADC1_IRQHandler,Default_Handler
+
+ .weak USB_HP_IRQHandler
+ .thumb_set USB_HP_IRQHandler,Default_Handler
+
+ .weak USB_LP_IRQHandler
+ .thumb_set USB_LP_IRQHandler,Default_Handler
+
+ .weak C2SEV_PWR_C2H_IRQHandler
+ .thumb_set C2SEV_PWR_C2H_IRQHandler,Default_Handler
+
+ .weak COMP_IRQHandler
+ .thumb_set COMP_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_IRQHandler
+ .thumb_set TIM1_BRK_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_TIM16_IRQHandler
+ .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_TIM17_IRQHandler
+ .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak PKA_IRQHandler
+ .thumb_set PKA_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C3_EV_IRQHandler
+ .thumb_set I2C3_EV_IRQHandler,Default_Handler
+
+ .weak I2C3_ER_IRQHandler
+ .thumb_set I2C3_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak LPUART1_IRQHandler
+ .thumb_set LPUART1_IRQHandler,Default_Handler
+
+ .weak SAI1_IRQHandler
+ .thumb_set SAI1_IRQHandler,Default_Handler
+
+ .weak TSC_IRQHandler
+ .thumb_set TSC_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak CRS_IRQHandler
+ .thumb_set CRS_IRQHandler,Default_Handler
+
+ .weak PWR_SOTF_BLEACT_802ACT_RFPHASE_IRQHandler
+ .thumb_set PWR_SOTF_BLEACT_802ACT_RFPHASE_IRQHandler,Default_Handler
+
+ .weak IPCC_C1_RX_IRQHandler
+ .thumb_set IPCC_C1_RX_IRQHandler,Default_Handler
+
+ .weak IPCC_C1_TX_IRQHandler
+ .thumb_set IPCC_C1_TX_IRQHandler,Default_Handler
+
+ .weak HSEM_IRQHandler
+ .thumb_set HSEM_IRQHandler,Default_Handler
+
+ .weak LPTIM1_IRQHandler
+ .thumb_set LPTIM1_IRQHandler,Default_Handler
+
+ .weak LPTIM2_IRQHandler
+ .thumb_set LPTIM2_IRQHandler,Default_Handler
+
+ .weak LCD_IRQHandler
+ .thumb_set LCD_IRQHandler,Default_Handler
+
+ .weak QUADSPI_IRQHandler
+ .thumb_set QUADSPI_IRQHandler,Default_Handler
+
+ .weak AES1_IRQHandler
+ .thumb_set AES1_IRQHandler,Default_Handler
+
+ .weak AES2_IRQHandler
+ .thumb_set AES2_IRQHandler,Default_Handler
+
+ .weak RNG_IRQHandler
+ .thumb_set RNG_IRQHandler,Default_Handler
+
+ .weak FPU_IRQHandler
+ .thumb_set FPU_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel1_IRQHandler
+ .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel2_IRQHandler
+ .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel3_IRQHandler
+ .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel4_IRQHandler
+ .thumb_set DMA2_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel5_IRQHandler
+ .thumb_set DMA2_Channel5_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel6_IRQHandler
+ .thumb_set DMA2_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel7_IRQHandler
+ .thumb_set DMA2_Channel7_IRQHandler,Default_Handler
+
+ .weak DMAMUX1_OVR_IRQHandler
+ .thumb_set DMAMUX1_OVR_IRQHandler,Default_Handler
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/firmware/targets/f3/stm32wb55xx_flash_cm4.ld b/firmware/targets/f3/stm32wb55xx_flash_cm4.ld
new file mode 100644
index 00000000..c8946a8e
--- /dev/null
+++ b/firmware/targets/f3/stm32wb55xx_flash_cm4.ld
@@ -0,0 +1,187 @@
+/**
+*****************************************************************************
+**
+** File : stm32wb55xx_flash_cm4.ld
+**
+** Abstract : System Workbench Minimal System calls file
+**
+** For more information about which c-functions
+** need which of these lowlevel functions
+** please consult the Newlib libc-manual
+**
+** Environment : System Workbench for MCU
+**
+** Distribution: The file is distributed “as is,” without any warranty
+** of any kind.
+**
+*****************************************************************************
+**
+** © COPYRIGHT(c) 2019 Ac6
+**
+** 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 Ac6 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 = 0x20030000; /* 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
+{
+FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 480K
+RAM1 (xrw) : ORIGIN = 0x20000004, LENGTH = 0x2FFFC
+RAM_SHARED (xrw) : ORIGIN = 0x20030000, LENGTH = 10K
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(4);
+ *(.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(4);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+ .ARM : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >FLASH
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >FLASH
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >FLASH
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM1 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;
+ } >RAM1
+
+ /* 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);
+ } >RAM1
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+ MAPPING_TABLE (NOLOAD) : { *(MAPPING_TABLE) } >RAM_SHARED
+ MB_MEM1 (NOLOAD) : { *(MB_MEM1) } >RAM_SHARED
+ MB_MEM2 (NOLOAD) : { _sMB_MEM2 = . ; *(MB_MEM2) ; _eMB_MEM2 = . ; } >RAM_SHARED
+}
+
+
diff --git a/firmware/targets/f3/stm32wb55xx_flash_cm4_no_boot.ld b/firmware/targets/f3/stm32wb55xx_flash_cm4_no_boot.ld
new file mode 100644
index 00000000..ce970b16
--- /dev/null
+++ b/firmware/targets/f3/stm32wb55xx_flash_cm4_no_boot.ld
@@ -0,0 +1,187 @@
+/**
+*****************************************************************************
+**
+** File : stm32wb55xx_flash_cm4.ld
+**
+** Abstract : System Workbench Minimal System calls file
+**
+** For more information about which c-functions
+** need which of these lowlevel functions
+** please consult the Newlib libc-manual
+**
+** Environment : System Workbench for MCU
+**
+** Distribution: The file is distributed “as is,” without any warranty
+** of any kind.
+**
+*****************************************************************************
+**
+** © COPYRIGHT(c) 2019 Ac6
+**
+** 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 Ac6 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 = 0x20030000; /* 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
+{
+FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K
+RAM1 (xrw) : ORIGIN = 0x20000004, LENGTH = 0x2FFFC
+RAM_SHARED (xrw) : ORIGIN = 0x20030000, LENGTH = 10K
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(4);
+ *(.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(4);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+ .ARM : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >FLASH
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >FLASH
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >FLASH
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM1 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;
+ } >RAM1
+
+ /* 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);
+ } >RAM1
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+ MAPPING_TABLE (NOLOAD) : { *(MAPPING_TABLE) } >RAM_SHARED
+ MB_MEM1 (NOLOAD) : { *(MB_MEM1) } >RAM_SHARED
+ MB_MEM2 (NOLOAD) : { _sMB_MEM2 = . ; *(MB_MEM2) ; _eMB_MEM2 = . ; } >RAM_SHARED
+}
+
+
diff --git a/firmware/targets/f3/target.mk b/firmware/targets/f3/target.mk
new file mode 100644
index 00000000..c4dff7ee
--- /dev/null
+++ b/firmware/targets/f3/target.mk
@@ -0,0 +1,103 @@
+TOOLCHAIN = arm
+
+DEBUG_AGENT = openocd -f interface/stlink-v2.cfg -c "transport select hla_swd" -f ../debug/stm32wbx.cfg -c "init" -c "reset halt"
+
+BOOT_ADDRESS = 0x08000000
+FW_ADDRESS = 0x08008000
+OS_OFFSET = 0x00008000
+FLASH_ADDRESS = 0x08008000
+
+NO_BOOTLOADER ?= 0
+ifeq ($(NO_BOOTLOADER), 1)
+BOOT_ADDRESS = 0x08000000
+FW_ADDRESS = 0x08000000
+OS_OFFSET = 0x00000000
+FLASH_ADDRESS = 0x08000000
+CFLAGS += -DNO_BOOTLOADER
+endif
+
+BOOT_CFLAGS = -DBOOT_ADDRESS=$(BOOT_ADDRESS) -DFW_ADDRESS=$(FW_ADDRESS) -DOS_OFFSET=$(OS_OFFSET)
+MCU_FLAGS = -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=hard
+
+CFLAGS += $(MCU_FLAGS) $(BOOT_CFLAGS) -DSTM32WB55xx -Wall -fdata-sections -ffunction-sections
+LDFLAGS += $(MCU_FLAGS) -specs=nosys.specs -specs=nano.specs
+
+CUBE_DIR = ../lib/STM32CubeWB
+C_SOURCES += \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_gpio.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd_ex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_usb.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rcc.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rcc_ex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash_ex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_hsem.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_dma.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_dma_ex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr_ex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_cortex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_exti.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc_ex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_adc.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_i2c.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_i2c_ex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc_ex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi_ex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim_ex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_uart.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_uart_ex.c \
+ $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_comp.c \
+ $(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/croutine.c \
+ $(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/event_groups.c \
+ $(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/list.c \
+ $(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/queue.c \
+ $(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/stream_buffer.c \
+ $(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/tasks.c \
+ $(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/timers.c \
+ $(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c \
+ $(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/portable/MemMang/heap_4.c \
+ $(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c \
+ $(CUBE_DIR)/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c \
+ $(CUBE_DIR)/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c \
+ $(CUBE_DIR)/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c \
+ $(CUBE_DIR)/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c \
+ $(wildcard $(TARGET_DIR)/Src/*.c) \
+ $(wildcard $(TARGET_DIR)/Src/fatfs/*.c) \
+ $(wildcard $(TARGET_DIR)/api-hal/*.c)
+
+ASM_SOURCES += $(TARGET_DIR)/startup_stm32wb55xx_cm4.s
+
+# Common
+CFLAGS += \
+ -DUSE_HAL_DRIVER \
+ -DHAVE_FREERTOS \
+ -DBUTON_INVERT=true \
+ -DDEBUG_UART=huart1
+
+ifeq ($(NO_BOOTLOADER), 1)
+LDFLAGS += -T$(TARGET_DIR)/stm32wb55xx_flash_cm4_no_boot.ld
+else
+LDFLAGS += -T$(TARGET_DIR)/stm32wb55xx_flash_cm4.ld
+endif
+
+CFLAGS += \
+ -I$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Inc \
+ -I$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Inc/Legacy \
+ -I$(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/include \
+ -I$(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2 \
+ -I$(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F \
+ -I$(CUBE_DIR)/Middlewares/ST/STM32_USB_Device_Library/Core/Inc \
+ -I$(CUBE_DIR)/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc \
+ -I$(CUBE_DIR)/Drivers/CMSIS/Device/ST/STM32WBxx/Include \
+ -I$(CUBE_DIR)/Drivers/CMSIS/Include \
+ -I$(TARGET_DIR)/Inc \
+ -I$(TARGET_DIR)/Src/fatfs \
+ -I$(TARGET_DIR)/api-hal
+
diff --git a/lib/STM32CubeWB b/lib/STM32CubeWB
new file mode 160000
index 00000000..e3d0473c
--- /dev/null
+++ b/lib/STM32CubeWB
@@ -0,0 +1 @@
+Subproject commit e3d0473c1588f1379ff0e4d7d1c78d081c352518