diff --git a/Inc/led.h b/Inc/led.h
index 38d0e0a..257d844 100644
--- a/Inc/led.h
+++ b/Inc/led.h
@@ -1,9 +1,30 @@
#ifndef _LED_H
#define _LED_H
-
#define LED_DURATION 50
+#ifdef LINKLAYER
+// LINKLAYER CANTACT-HW
+#define LED_GREEN_GPIO GPIOB
+#define LED_RED_GPIO GPIOB
+#define LED_GREEN_GPIO_CLK __GPIOB_CLK_ENABLE
+#define LED_RED_GPIO_CLK __GPIOB_CLK_ENABLE
+#define LED_GREEN (GPIO_PIN_0)
+#define LED_RED (GPIO_PIN_1)
+
+#else
+
+// STM32F072B-DISCOVERY
+
+#define LED_GREEN_GPIO GPIOC
+#define LED_RED_GPIO GPIOC
+#define LED_GREEN_GPIO_CLK __GPIOC_CLK_ENABLE
+#define LED_RED_GPIO_CLK __GPIOC_CLK_ENABLE
+#define LED_GREEN (GPIO_PIN_9)
+#define LED_RED (GPIO_PIN_8)
+
+#endif
+
void led_on(void);
void led_process(void);
diff --git a/Makefile b/Makefile
index 3e766b0..67572a0 100644
--- a/Makefile
+++ b/Makefile
@@ -9,6 +9,24 @@
#######################################
BUILD_NUMBER ?= 0
+# build hw can be either 'cantact' or 'disco'
+BUILD_HW ?= cantact
+
+# BUILD_DIR: directory to place output files in
+BUILD_DIR = build
+
+ifeq ($(BUILD_HW),cantact)
+EXTRA_DEFS = -D LINKLAYER
+STARTUP_S = $(BUILD_DIR)/startup_stm32f042x6.o
+TARGET_DEVICE = STM32F042x6
+LD_SCRIPT = STM32F042C6_FLASH.ld
+endif
+ifeq ($(BUILD_HW),disco)
+EXTRA_DEFS =
+STARTUP_S = $(BUILD_DIR)/startup_stm32f072xb.o
+TARGET_DEVICE = STM32F072xB
+LD_SCRIPT = STM32F072RB_FLASH.ld
+endif
# SOURCES: list of sources in the user application
SOURCES = main.c usbd_conf.c usbd_cdc_if.c usb_device.c usbd_desc.c stm32f0xx_hal_msp.c stm32f0xx_it.c system_stm32f0xx.c can.c slcan.c led.c
@@ -16,14 +34,8 @@ SOURCES = main.c usbd_conf.c usbd_cdc_if.c usb_device.c usbd_desc.c stm32f0xx_ha
# TARGET: name of the user application
TARGET = CANtact-b$(BUILD_NUMBER)
-# BUILD_DIR: directory to place output files in
-BUILD_DIR = build
-
-# LD_SCRIPT: location of the linker script
-LD_SCRIPT = STM32F042C6_FLASH.ld
-
# USER_DEFS user defined macros
-USER_DEFS = -D HSI48_VALUE=48000000 -D HSE_VALUE=16000000
+USER_DEFS = -D HSI48_VALUE=48000000 -D HSE_VALUE=16000000 $(EXTRA_DEFS)
USER_DEFS += -D CANTACT_BUILD_NUMBER=$(BUILD_NUMBER)
# USER_INCLUDES: user defined includes
USER_INCLUDES =
@@ -37,9 +49,6 @@ USER_CFLAGS = -Wall -g -ffunction-sections -fdata-sections -Os
# USER_LDFLAGS: user LD flags
USER_LDFLAGS = -fno-exceptions -ffunction-sections -fdata-sections -Wl,--gc-sections
-# TARGET_DEVICE: device to compile for
-TARGET_DEVICE = STM32F042x6
-
#######################################
# end of user configuration
#######################################
@@ -143,7 +152,7 @@ $(USB_BUILD_DIR):
# list of user program objects
OBJECTS = $(addprefix $(BUILD_DIR)/,$(notdir $(SOURCES:.c=.o)))
# add an object for the startup code
-OBJECTS += $(BUILD_DIR)/startup_stm32f042x6.o
+OBJECTS += $(STARTUP_S)
# use the periphlib core library, plus generic ones (libc, libm, libnosys)
LIBS = -lstm32cube -lc -lm -lnosys
@@ -172,10 +181,10 @@ $(BUILD_DIR):
# delete all user application files, keep the libraries
clean:
- -rm $(BUILD_DIR)/*.o
- -rm $(BUILD_DIR)/*.elf
- -rm $(BUILD_DIR)/*.hex
- -rm $(BUILD_DIR)/*.map
- -rm $(BUILD_DIR)/*.bin
+ -rm -f $(BUILD_DIR)/*.o
+ -rm -f $(BUILD_DIR)/*.elf
+ -rm -f $(BUILD_DIR)/*.hex
+ -rm -f $(BUILD_DIR)/*.map
+ -rm -f $(BUILD_DIR)/*.bin
.PHONY: clean all cubelib
diff --git a/README.md b/README.md
index 29f6188..a20be91 100644
--- a/README.md
+++ b/README.md
@@ -6,6 +6,23 @@ This repository contains sources for CANtact firmware.
Documentation can be found on the [Linklayer Wiki](https://wiki.linklayer.com/index.php/CANtact).
+## STM32F072B-DISCO Notes
+
+LD4: "RED" led (can frame rx/tx)
+LD5: "Green" led (status)
+
+CanBUS connection:
+PB9: `CAN_TX`
+PB8: `CAN_RX`
+
+Firmware runs from internal HSI48 oscillator.
+The connectors are nicely aligned together in top right of the board, on P2 connector.
+GND, PB9, PB8, VCC is available in a single row.
+
+Tested with: Waveshare CAN breakout board
+
+USB connection via `USB USER` connector on the board
+
## Building
Firmware builds with GCC. Specifically, you will need gcc-arm-none-eabi, which
diff --git a/STM32F072RB_FLASH.ld b/STM32F072RB_FLASH.ld
new file mode 100644
index 0000000..79c33bd
--- /dev/null
+++ b/STM32F072RB_FLASH.ld
@@ -0,0 +1,168 @@
+/*
+*****************************************************************************
+**
+
+** File : stm32_flash.ld
+**
+** Abstract : Linker script for STM32F072RB Device with
+** 128KByte FLASH, 16KByte RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+** Environment : Atollic TrueSTUDIO(R)
+**
+** Distribution: The file is distributed as is, without any warranty
+** of any kind.
+**
+** (c)Copyright Atollic AB.
+** You may use this file as-is or modify it according to the needs of your
+** project. This file may only be built (assembled or compiled and linked)
+** using the Atollic TrueSTUDIO(R) product. The use of this file together
+** with other tools than Atollic TrueSTUDIO(R) is not permitted.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20004000; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 16K
+FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 128K
+}
+
+/* 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 */
+ } >RAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(4);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(4);
+ } >RAM
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+
diff --git a/Src/can.c b/Src/can.c
index 769d6e1..645fa9e 100644
--- a/Src/can.c
+++ b/Src/can.c
@@ -68,7 +68,7 @@ void can_disable(void) {
hcan.Instance->MCR |= CAN_MCR_RESET;
bus_state = OFF_BUS;
}
- HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, GPIO_PIN_RESET);
+ HAL_GPIO_WritePin(LED_RED_GPIO, LED_RED, GPIO_PIN_RESET);
}
void can_set_bitrate(enum can_bitrate bitrate) {
diff --git a/Src/led.c b/Src/led.c
index 762539f..f3c5e86 100644
--- a/Src/led.c
+++ b/Src/led.c
@@ -15,7 +15,7 @@ void led_on(void)
// This prevents a solid status LED on a busy canbus
if(led_laston == 0 && HAL_GetTick() - led_lastoff > LED_DURATION)
{
- HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, 1);
+ HAL_GPIO_WritePin(LED_RED_GPIO, LED_RED, GPIO_PIN_SET);
led_laston = HAL_GetTick();
}
}
@@ -27,7 +27,7 @@ void led_process(void)
// If LED has been on for long enough, turn it off
if(led_laston > 0 && HAL_GetTick() - led_laston > LED_DURATION)
{
- HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, 0);
+ HAL_GPIO_WritePin(LED_RED_GPIO, LED_RED, GPIO_PIN_RESET);
led_laston = 0;
led_lastoff = HAL_GetTick();
}
diff --git a/Src/main.c b/Src/main.c
index c4d1534..2e1a4af 100644
--- a/Src/main.c
+++ b/Src/main.c
@@ -42,8 +42,33 @@
#include "slcan.h"
#include "led.h"
-//#define INTERNAL_OSCILLATOR
+// Define below to run on original CANTACT-HW, leave it undefined to use STM32F072B-DISCO
+// #define LINKLAYER
+
+/*
+ STM32F072B-DISCO Notes
+
+ LD4: "RED" led (can frame rx/tx)
+ LD5: "Green" led (status)
+
+ CanBUS connection:
+ PB9: CAN_TX
+ PB8: CAN_RX
+
+ Firmware runs from internal HSI48 oscillator.
+ The connectors are nicely aligned together in top right of the board, on P2 connector.
+ GND, PB9, PB8, VCC is available in a single row.
+
+ Tested with: Waveshare CAN breakout board
+*/
+
+#ifdef LINKLAYER
+// CANTACT-HW (16MHz XTAL)
#define EXTERNAL_OSCILLATOR
+#else
+// STM32F072B-DISCO
+#define INTERNAL_OSCILLATOR
+#endif
/* USER CODE END Includes */
@@ -95,16 +120,16 @@ int main(void)
// turn on green LED
- HAL_GPIO_WritePin(GPIOB, GPIO_PIN_0, GPIO_PIN_SET);
+ HAL_GPIO_WritePin(LED_GREEN_GPIO, LED_GREEN, GPIO_PIN_SET);
// blink red LED for test
- HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, GPIO_PIN_SET);
+ HAL_GPIO_WritePin(LED_RED_GPIO, LED_RED, GPIO_PIN_SET);
HAL_Delay(100);
- HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, GPIO_PIN_RESET);
+ HAL_GPIO_WritePin(LED_RED_GPIO, LED_RED, GPIO_PIN_RESET);
HAL_Delay(100);
- HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, GPIO_PIN_SET);
+ HAL_GPIO_WritePin(LED_RED_GPIO, LED_RED, GPIO_PIN_SET);
HAL_Delay(100);
- HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, GPIO_PIN_RESET);
+ HAL_GPIO_WritePin(LED_RED_GPIO, LED_RED, GPIO_PIN_RESET);
// loop forever
CanRxMsgTypeDef rx_msg;
@@ -131,29 +156,34 @@ int main(void)
void SystemClock_Config(void)
{
-
- RCC_OscInitTypeDef RCC_OscInitStruct;
- RCC_ClkInitTypeDef RCC_ClkInitStruct;
- RCC_PeriphCLKInitTypeDef PeriphClkInit;
+ RCC_OscInitTypeDef RCC_OscInitStruct = {0};
+ RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
+ RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
#ifdef INTERNAL_OSCILLATOR
- // set up the oscillators
- // use internal HSI48 (48 MHz), no PLL
- RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI48;
+ /** Initializes the RCC Oscillators according to the specified parameters
+ * in the RCC_OscInitTypeDef structure.
+ */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_HSI48;
+ RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.HSI48State = RCC_HSI48_ON;
- RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
-
- // set sysclk, hclk, and pclk1 source to HSI48 (48 MHz)
- RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK |
- RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1);
- RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI48;
+ RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
+ RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL6;
+ RCC_OscInitStruct.PLL.PREDIV = RCC_PREDIV_DIV1;
+ HAL_RCC_OscConfig(&RCC_OscInitStruct);
+ /** Initializes the CPU, AHB and APB buses clocks */
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_PCLK1;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
- // set USB clock source to HSI48 (48 MHz)
+ HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1);
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB;
PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_HSI48;
+ HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
#elif defined EXTERNAL_OSCILLATOR
// set up the oscillators
@@ -176,19 +206,18 @@ void SystemClock_Config(void)
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB;
PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_PLLCLK;
-#else
- #error "Please define whether to use an internal or external oscillator"
-#endif
-
HAL_RCC_OscConfig(&RCC_OscInitStruct);
HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0);
HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
__SYSCFG_CLK_ENABLE();
- HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000);
- HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
- HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
+#else
+ #error "Please define whether to use an internal or external oscillator"
+#endif
+ HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000);
+ HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
+ HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
}
/** Configure pins as
@@ -205,17 +234,22 @@ void MX_GPIO_Init(void)
__GPIOF_CLK_ENABLE();
__GPIOA_CLK_ENABLE();
__GPIOB_CLK_ENABLE();
+ LED_GREEN_GPIO_CLK();
+ LED_RED_GPIO_CLK();
}
/* USER CODE BEGIN 4 */
-static void led_init() {
- GPIO_InitTypeDef GPIO_InitStruct;
- GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1;
+static void led_init(void)
+{
+ GPIO_InitTypeDef GPIO_InitStruct = { 0, };
+ GPIO_InitStruct.Pin = LED_GREEN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_MEDIUM;
GPIO_InitStruct.Alternate = 0;
- HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+ HAL_GPIO_Init(LED_GREEN_GPIO, &GPIO_InitStruct);
+ GPIO_InitStruct.Pin = LED_RED;
+ HAL_GPIO_Init(LED_RED_GPIO, &GPIO_InitStruct);
}
/* USER CODE END 4 */
diff --git a/Src/slcan.c b/Src/slcan.c
index 243cfa7..cc5bd93 100644
--- a/Src/slcan.c
+++ b/Src/slcan.c
@@ -203,7 +203,7 @@ int8_t slcan_parse_str(uint8_t *buf, uint8_t len) {
frame.DLC = buf[i++];
- if (frame.DLC < 0 || frame.DLC > 8) {
+ if (frame.DLC > 8) {
return -1;
}
diff --git a/Src/startup_stm32f072xb.s b/Src/startup_stm32f072xb.s
new file mode 100644
index 0000000..6ee8242
--- /dev/null
+++ b/Src/startup_stm32f072xb.s
@@ -0,0 +1,308 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32f072xb.s
+ * @author MCD Application Team
+ * @version V2.1.0
+ * @date 03-Oct-2014
+ * @brief STM32F072x8/STM32F072xB devices vector table for Atollic TrueSTUDIO 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-M0 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ *
+ * 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.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m0
+ .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
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr r0, =_estack
+ mov sp, r0 /* set stack pointer */
+
+/* Copy the data segment initializers from flash to SRAM */
+ movs r1, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r3, =_sidata
+ ldr r3, [r3, r1]
+ str r3, [r0, r1]
+ adds r1, r1, #4
+
+LoopCopyDataInit:
+ ldr r0, =_sdata
+ ldr r3, =_edata
+ adds r2, r0, r1
+ cmp r2, r3
+ bcc CopyDataInit
+ ldr r2, =_sbss
+ b LoopFillZerobss
+/* Zero fill the bss segment. */
+FillZerobss:
+ movs r3, #0
+ str r3, [r2]
+ adds r2, r2, #4
+
+
+LoopFillZerobss:
+ ldr r3, = _ebss
+ cmp r2, r3
+ bcc FillZerobss
+
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+/* 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 M0. 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 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word 0
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler /* Window WatchDog */
+ .word PVD_VDDIO2_IRQHandler /* PVD and VDDIO2 through EXTI Line detect */
+ .word RTC_IRQHandler /* RTC through the EXTI line */
+ .word FLASH_IRQHandler /* FLASH */
+ .word RCC_CRS_IRQHandler /* RCC and CRS */
+ .word EXTI0_1_IRQHandler /* EXTI Line 0 and 1 */
+ .word EXTI2_3_IRQHandler /* EXTI Line 2 and 3 */
+ .word EXTI4_15_IRQHandler /* EXTI Line 4 to 15 */
+ .word TSC_IRQHandler /* TSC */
+ .word DMA1_Channel1_IRQHandler /* DMA1 Channel 1 */
+ .word DMA1_Channel2_3_IRQHandler /* DMA1 Channel 2 and Channel 3 */
+ .word DMA1_Channel4_5_6_7_IRQHandler /* DMA1 Channel 4, Channel 5, Channel 6 and Channel 7*/
+ .word ADC1_COMP_IRQHandler /* ADC1, COMP1 and COMP2 */
+ .word TIM1_BRK_UP_TRG_COM_IRQHandler /* TIM1 Break, Update, Trigger and Commutation */
+ .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */
+ .word TIM2_IRQHandler /* TIM2 */
+ .word TIM3_IRQHandler /* TIM3 */
+ .word TIM6_DAC_IRQHandler /* TIM6 and DAC */
+ .word TIM7_IRQHandler /* TIM7 */
+ .word TIM14_IRQHandler /* TIM14 */
+ .word TIM15_IRQHandler /* TIM15 */
+ .word TIM16_IRQHandler /* TIM16 */
+ .word TIM17_IRQHandler /* TIM17 */
+ .word I2C1_IRQHandler /* I2C1 */
+ .word I2C2_IRQHandler /* I2C2 */
+ .word SPI1_IRQHandler /* SPI1 */
+ .word SPI2_IRQHandler /* SPI2 */
+ .word USART1_IRQHandler /* USART1 */
+ .word USART2_IRQHandler /* USART2 */
+ .word USART3_4_IRQHandler /* USART3 and USART4 */
+ .word CEC_CAN_IRQHandler /* CEC and CAN */
+ .word USB_IRQHandler /* USB */
+
+/*******************************************************************************
+*
+* 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 SVC_Handler
+ .thumb_set SVC_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_VDDIO2_IRQHandler
+ .thumb_set PVD_VDDIO2_IRQHandler,Default_Handler
+
+ .weak RTC_IRQHandler
+ .thumb_set RTC_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_CRS_IRQHandler
+ .thumb_set RCC_CRS_IRQHandler,Default_Handler
+
+ .weak EXTI0_1_IRQHandler
+ .thumb_set EXTI0_1_IRQHandler,Default_Handler
+
+ .weak EXTI2_3_IRQHandler
+ .thumb_set EXTI2_3_IRQHandler,Default_Handler
+
+ .weak EXTI4_15_IRQHandler
+ .thumb_set EXTI4_15_IRQHandler,Default_Handler
+
+ .weak TSC_IRQHandler
+ .thumb_set TSC_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_3_IRQHandler
+ .thumb_set DMA1_Channel2_3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_5_6_7_IRQHandler
+ .thumb_set DMA1_Channel4_5_6_7_IRQHandler,Default_Handler
+
+ .weak ADC1_COMP_IRQHandler
+ .thumb_set ADC1_COMP_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_UP_TRG_COM_IRQHandler
+ .thumb_set TIM1_BRK_UP_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak TIM3_IRQHandler
+ .thumb_set TIM3_IRQHandler,Default_Handler
+
+ .weak TIM6_DAC_IRQHandler
+ .thumb_set TIM6_DAC_IRQHandler,Default_Handler
+
+ .weak TIM7_IRQHandler
+ .thumb_set TIM7_IRQHandler,Default_Handler
+
+ .weak TIM14_IRQHandler
+ .thumb_set TIM14_IRQHandler,Default_Handler
+
+ .weak TIM15_IRQHandler
+ .thumb_set TIM15_IRQHandler,Default_Handler
+
+ .weak TIM16_IRQHandler
+ .thumb_set TIM16_IRQHandler,Default_Handler
+
+ .weak TIM17_IRQHandler
+ .thumb_set TIM17_IRQHandler,Default_Handler
+
+ .weak I2C1_IRQHandler
+ .thumb_set I2C1_IRQHandler,Default_Handler
+
+ .weak I2C2_IRQHandler
+ .thumb_set I2C2_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 USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak USART3_4_IRQHandler
+ .thumb_set USART3_4_IRQHandler,Default_Handler
+
+ .weak CEC_CAN_IRQHandler
+ .thumb_set CEC_CAN_IRQHandler,Default_Handler
+
+ .weak USB_IRQHandler
+ .thumb_set USB_IRQHandler,Default_Handler
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/cantact-fw.uvopt b/cantact-fw.uvopt
new file mode 100644
index 0000000..2045f79
--- /dev/null
+++ b/cantact-fw.uvopt
@@ -0,0 +1,620 @@
+
+
+
+ 1.0
+
+ ### uVision Project, (C) Keil Software
+
+
+ *.c
+ *.s*; *.src; *.a*
+ *.obj; *.o
+ *.lib
+ *.txt; *.h; *.inc
+ *.plm
+ *.cpp
+ 0
+
+
+
+ 0
+ 0
+
+
+
+ STM32
+ 0x4
+ ARM-ADS
+
+ 8000000
+
+ 1
+ 1
+ 1
+ 0
+ 0
+
+
+ 1
+ 65535
+ 0
+ 0
+ 0
+
+
+ 79
+ 66
+ 8
+ .\build\
+
+
+ 1
+ 1
+ 1
+ 0
+ 1
+ 1
+ 0
+ 1
+ 0
+ 0
+ 0
+ 0
+
+
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 0
+
+
+ 1
+ 0
+ 1
+
+ 18
+
+
+ 0
+ Data Sheet
+ datashts\ST\STM32F0xx\NotYetAvailable.pdf
+
+
+ 1
+ Reference Manual
+ datashts\ST\STM32F0xx\NotYetAvailable.pdf
+
+
+ 2
+ Technical Reference Manual
+ datashts\arm\cortex_m0\r0p0\DDI0432C_CORTEX_M0_R0P0_TRM.PDF
+
+
+ 3
+ Generic User Guide
+ datashts\arm\cortex_m0\r0p0\DUI0497A_CORTEX_M0_R0P0_GENERIC_UG.PDF
+
+
+
+ 0
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 1
+ 1
+ 1
+ 1
+ 0
+ 0
+ 1
+ 0
+ 0
+ 6
+
+
+
+
+
+
+
+
+
+
+ STLink\ST-LINKIII-KEIL_SWO.dll
+
+
+
+ 0
+ ST-LINKIII-KEIL_SWO
+ -U51FF6E065067485746201887 -O207 -SF4000 -C0 -A0 -I0 -HNlocalhost -HP7184 -P1 -N00("ARM CoreSight SW-DP") -D00(0BB11477) -L00(0) -TO131090 -TC10000000 -TT10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO11 -FD20000000 -FC800 -FN1 -FF0STM32F0xx_128 -FS08000000 -FL020000
+
+
+ 0
+ JL2CM3
+ -U504401610 -O207 -S2 -ZTIFSpeedSel5000 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO7 -FD20000000 -FC800 -FN1 -FF0STM32F0xx_128 -FS08000000 -FL020000
+
+
+ 0
+ UL2CM3
+ UL2CM3(-O207 -S0 -C0 -FO7 -FD20000000 -FC800 -FN1 -FF0STM32F0xx_128 -FS08000000 -FL020000)
+
+
+
+
+ 0
+
+
+ 0
+ 1
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ App
+ 1
+ 0
+ 0
+ 0
+
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+ .\Src\can.c
+ can.c
+ 0
+ 0
+
+
+ 1
+ 2
+ 1
+ 0
+ 0
+ 0
+ .\Src\led.c
+ led.c
+ 0
+ 0
+
+
+ 1
+ 3
+ 1
+ 0
+ 0
+ 0
+ .\Src\main.c
+ main.c
+ 0
+ 0
+
+
+ 1
+ 4
+ 1
+ 0
+ 0
+ 0
+ .\Src\slcan.c
+ slcan.c
+ 0
+ 0
+
+
+ 1
+ 5
+ 1
+ 0
+ 0
+ 0
+ .\Src\stm32f0xx_hal_msp.c
+ stm32f0xx_hal_msp.c
+ 0
+ 0
+
+
+ 1
+ 6
+ 1
+ 0
+ 0
+ 0
+ .\Src\stm32f0xx_it.c
+ stm32f0xx_it.c
+ 0
+ 0
+
+
+ 1
+ 7
+ 1
+ 0
+ 0
+ 0
+ .\Src\usb_device.c
+ usb_device.c
+ 0
+ 0
+
+
+ 1
+ 8
+ 1
+ 0
+ 0
+ 0
+ .\Src\usbd_cdc_if.c
+ usbd_cdc_if.c
+ 0
+ 0
+
+
+ 1
+ 9
+ 1
+ 0
+ 0
+ 0
+ .\Src\usbd_conf.c
+ usbd_conf.c
+ 0
+ 0
+
+
+ 1
+ 10
+ 1
+ 0
+ 0
+ 0
+ .\Src\usbd_desc.c
+ usbd_desc.c
+ 0
+ 0
+
+
+
+
+ HAL
+ 1
+ 0
+ 0
+ 0
+
+ 2
+ 11
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal.c
+ stm32f0xx_hal.c
+ 0
+ 0
+
+
+ 2
+ 12
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_can.c
+ stm32f0xx_hal_can.c
+ 0
+ 0
+
+
+ 2
+ 13
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_cortex.c
+ stm32f0xx_hal_cortex.c
+ 0
+ 0
+
+
+ 2
+ 14
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_dma.c
+ stm32f0xx_hal_dma.c
+ 0
+ 0
+
+
+ 2
+ 15
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_flash.c
+ stm32f0xx_hal_flash.c
+ 0
+ 0
+
+
+ 2
+ 16
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_flash_ex.c
+ stm32f0xx_hal_flash_ex.c
+ 0
+ 0
+
+
+ 2
+ 17
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_gpio.c
+ stm32f0xx_hal_gpio.c
+ 0
+ 0
+
+
+ 2
+ 18
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_pcd.c
+ stm32f0xx_hal_pcd.c
+ 0
+ 0
+
+
+ 2
+ 19
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_pcd_ex.c
+ stm32f0xx_hal_pcd_ex.c
+ 0
+ 0
+
+
+ 2
+ 20
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_pwr.c
+ stm32f0xx_hal_pwr.c
+ 0
+ 0
+
+
+ 2
+ 21
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_pwr_ex.c
+ stm32f0xx_hal_pwr_ex.c
+ 0
+ 0
+
+
+ 2
+ 22
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_rcc.c
+ stm32f0xx_hal_rcc.c
+ 0
+ 0
+
+
+ 2
+ 23
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_rcc_ex.c
+ stm32f0xx_hal_rcc_ex.c
+ 0
+ 0
+
+
+ 2
+ 24
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_spi.c
+ stm32f0xx_hal_spi.c
+ 0
+ 0
+
+
+ 2
+ 25
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_tim.c
+ stm32f0xx_hal_tim.c
+ 0
+ 0
+
+
+ 2
+ 26
+ 1
+ 0
+ 0
+ 0
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_tim_ex.c
+ stm32f0xx_hal_tim_ex.c
+ 0
+ 0
+
+
+
+
+ CMSIS
+ 0
+ 0
+ 0
+ 0
+
+ 3
+ 27
+ 1
+ 0
+ 0
+ 0
+ .\Src\system_stm32f0xx.c
+ system_stm32f0xx.c
+ 0
+ 0
+
+
+ 3
+ 28
+ 2
+ 0
+ 0
+ 0
+ .\Drivers\CMSIS\Device\ST\STM32F0xx\Source\Templates\arm\startup_stm32f072xb.s
+ startup_stm32f072xb.s
+ 0
+ 0
+
+
+
+
+ USB
+ 1
+ 0
+ 0
+ 0
+
+ 4
+ 29
+ 1
+ 0
+ 0
+ 0
+ .\Middlewares\ST\STM32_USB_Device_Library\Core\Src\usbd_core.c
+ usbd_core.c
+ 0
+ 0
+
+
+ 4
+ 30
+ 1
+ 0
+ 0
+ 0
+ .\Middlewares\ST\STM32_USB_Device_Library\Core\Src\usbd_ctlreq.c
+ usbd_ctlreq.c
+ 0
+ 0
+
+
+ 4
+ 31
+ 1
+ 0
+ 0
+ 0
+ .\Middlewares\ST\STM32_USB_Device_Library\Core\Src\usbd_ioreq.c
+ usbd_ioreq.c
+ 0
+ 0
+
+
+ 4
+ 32
+ 1
+ 0
+ 0
+ 0
+ .\Middlewares\ST\STM32_USB_Device_Library\Class\CDC\Src\usbd_cdc.c
+ usbd_cdc.c
+ 0
+ 0
+
+
+
+
diff --git a/cantact-fw.uvproj b/cantact-fw.uvproj
new file mode 100644
index 0000000..64a50c0
--- /dev/null
+++ b/cantact-fw.uvproj
@@ -0,0 +1,606 @@
+
+
+
+ 1.1
+
+ ### uVision Project, (C) Keil Software
+
+
+
+ STM32
+ 0x4
+ ARM-ADS
+ 5060750::V5.06 update 6 (build 750)::ARMCC
+ 0
+
+
+ STM32F072RB
+ STMicroelectronics
+ IRAM(0x20000000-0x20003FFF) IROM(0x08000000-0x0801FFFF) CLOCK(8000000) CPUTYPE("Cortex-M0")
+
+ "Startup\ST\STM32F0xx\startup_stm32f072.s" ("STM32F072 Startup Code")
+ UL2CM3(-O207 -S0 -C0 -FO7 -FD20000000 -FC800 -FN1 -FF0STM32F0xx_128 -FS08000000 -FL020000)
+ 7471
+ stm32f0xx.h
+
+
+
+
+
+
+ -DSTM32F072
+
+
+ SFD\ST\STM32F0xx\STM32F072x.SFR
+ 0
+ 0
+
+
+
+ ST\STM32F0xx\
+ ST\STM32F0xx\
+
+ 0
+ 0
+ 0
+ 0
+ 1
+
+ .\build\
+ cantact-fw
+ 1
+ 0
+ 1
+ 1
+ 1
+ .\build\
+ 1
+ 0
+ 0
+
+ 0
+ 0
+
+
+ 0
+ 0
+ 0
+ 0
+
+
+ 0
+ 0
+
+
+ 0
+ 0
+ 0
+ 0
+
+
+ 0
+ 0
+
+
+ 0
+ 0
+ 0
+ 0
+
+ 0
+
+
+
+ 0
+ 0
+ 0
+ 0
+ 0
+ 1
+ 0
+ 0
+ 0
+ 0
+ 3
+
+
+ 1
+
+
+ SARMCM3.DLL
+ -REMAP
+ DARMCM1.DLL
+ -pCM0
+ SARMCM3.DLL
+
+ TARMCM1.DLL
+ -pCM0
+
+
+
+ 1
+ 0
+ 0
+ 0
+ 16
+
+
+ 0
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 1
+
+
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 1
+ 1
+ 1
+
+ 0
+ 6
+
+
+
+
+
+
+
+
+
+
+
+
+
+ STLink\ST-LINKIII-KEIL_SWO.dll
+
+
+
+
+ 1
+ 0
+ 0
+ 1
+ 1
+ 4096
+
+ 1
+ BIN\UL2CM3.DLL
+ "" ()
+
+
+
+
+ 0
+
+
+
+ 0
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 1
+ 1
+ 0
+ 1
+ 1
+ 0
+ 0
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 0
+ "Cortex-M0"
+
+ 0
+ 0
+ 0
+ 1
+ 1
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 8
+ 0
+ 0
+ 0
+ 0
+ 3
+ 3
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 1
+ 0
+ 0
+ 0
+ 0
+ 1
+ 0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x20000000
+ 0x4000
+
+
+ 1
+ 0x8000000
+ 0x20000
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 1
+ 0x0
+ 0x0
+
+
+ 1
+ 0x0
+ 0x0
+
+
+ 1
+ 0x0
+ 0x0
+
+
+ 1
+ 0x8000000
+ 0x20000
+
+
+ 1
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x20000000
+ 0x4000
+
+
+ 0
+ 0x0
+ 0x0
+
+
+
+
+
+ 1
+ 4
+ 0
+ 0
+ 1
+ 0
+ 0
+ 0
+ 0
+ 0
+ 2
+ 0
+ 1
+ 1
+ 1
+ 0
+ 3
+ 3
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+ STM32F072xB,HSI48_VALUE=48000000
+
+ Drivers\CMSIS\Include;Drivers\CMSIS\Device\ST\STM32F0xx\Include;Drivers\STM32F0xx_HAL_Driver\Inc;Middlewares\ST\STM32_USB_Device_Library\Core\Inc;Middlewares\ST\STM32_USB_Device_Library\Class\CDC\Inc;Inc
+
+
+
+ 1
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 1
+
+
+
+
+
+
+
+
+ 1
+ 0
+ 0
+ 0
+ 1
+ 0
+ 0x08000000
+ 0x20000000
+
+
+
+
+
+
+
+
+
+
+
+
+ App
+
+
+ can.c
+ 1
+ .\Src\can.c
+
+
+ led.c
+ 1
+ .\Src\led.c
+
+
+ main.c
+ 1
+ .\Src\main.c
+
+
+ slcan.c
+ 1
+ .\Src\slcan.c
+
+
+ stm32f0xx_hal_msp.c
+ 1
+ .\Src\stm32f0xx_hal_msp.c
+
+
+ stm32f0xx_it.c
+ 1
+ .\Src\stm32f0xx_it.c
+
+
+ usb_device.c
+ 1
+ .\Src\usb_device.c
+
+
+ usbd_cdc_if.c
+ 1
+ .\Src\usbd_cdc_if.c
+
+
+ usbd_conf.c
+ 1
+ .\Src\usbd_conf.c
+
+
+ usbd_desc.c
+ 1
+ .\Src\usbd_desc.c
+
+
+
+
+ HAL
+
+
+ stm32f0xx_hal.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal.c
+
+
+ stm32f0xx_hal_can.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_can.c
+
+
+ stm32f0xx_hal_cortex.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_cortex.c
+
+
+ stm32f0xx_hal_dma.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_dma.c
+
+
+ stm32f0xx_hal_flash.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_flash.c
+
+
+ stm32f0xx_hal_flash_ex.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_flash_ex.c
+
+
+ stm32f0xx_hal_gpio.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_gpio.c
+
+
+ stm32f0xx_hal_pcd.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_pcd.c
+
+
+ stm32f0xx_hal_pcd_ex.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_pcd_ex.c
+
+
+ stm32f0xx_hal_pwr.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_pwr.c
+
+
+ stm32f0xx_hal_pwr_ex.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_pwr_ex.c
+
+
+ stm32f0xx_hal_rcc.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_rcc.c
+
+
+ stm32f0xx_hal_rcc_ex.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_rcc_ex.c
+
+
+ stm32f0xx_hal_spi.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_spi.c
+
+
+ stm32f0xx_hal_tim.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_tim.c
+
+
+ stm32f0xx_hal_tim_ex.c
+ 1
+ .\Drivers\STM32F0xx_HAL_Driver\Src\stm32f0xx_hal_tim_ex.c
+
+
+
+
+ CMSIS
+
+
+ system_stm32f0xx.c
+ 1
+ .\Src\system_stm32f0xx.c
+
+
+ startup_stm32f072xb.s
+ 2
+ .\Drivers\CMSIS\Device\ST\STM32F0xx\Source\Templates\arm\startup_stm32f072xb.s
+
+
+
+
+ USB
+
+
+ usbd_core.c
+ 1
+ .\Middlewares\ST\STM32_USB_Device_Library\Core\Src\usbd_core.c
+
+
+ usbd_ctlreq.c
+ 1
+ .\Middlewares\ST\STM32_USB_Device_Library\Core\Src\usbd_ctlreq.c
+
+
+ usbd_ioreq.c
+ 1
+ .\Middlewares\ST\STM32_USB_Device_Library\Core\Src\usbd_ioreq.c
+
+
+ usbd_cdc.c
+ 1
+ .\Middlewares\ST\STM32_USB_Device_Library\Class\CDC\Src\usbd_cdc.c
+
+
+
+
+
+
+
+