diff --git a/MDK-ARM/FreeJoy.bin b/MDK-ARM/FreeJoy.bin index b749d22..09ec0a3 100644 Binary files a/MDK-ARM/FreeJoy.bin and b/MDK-ARM/FreeJoy.bin differ diff --git a/MDK-ARM/FreeJoy.uvprojx b/MDK-ARM/FreeJoy.uvprojx index 713a1b8..0ab2da2 100644 --- a/MDK-ARM/FreeJoy.uvprojx +++ b/MDK-ARM/FreeJoy.uvprojx @@ -760,6 +760,75 @@ SEGGER + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + SEGGER_SYSVIEW.c diff --git a/application/Src/analog.c b/application/Src/analog.c index 9b137e4..0daef8c 100644 --- a/application/Src/analog.c +++ b/application/Src/analog.c @@ -24,8 +24,6 @@ #include "analog.h" -#include "SEGGER_SYSVIEW.h" - #include #include #include "tle5011.h" @@ -647,7 +645,6 @@ void AxesInit (dev_config_t * p_dev_config) */ void ADC_Conversion (void) { - SEGGER_SYSVIEW_RecordVoid(45); if (adc_cnt > 0) { @@ -683,7 +680,6 @@ void ADC_Conversion (void) adc_data[j] /= ADC_CONV_NUM; } } - SEGGER_SYSVIEW_RecordEndCall(45); } /** @@ -693,7 +689,6 @@ void ADC_Conversion (void) */ void AxesProcess (dev_config_t * p_dev_config) { - SEGGER_SYSVIEW_RecordVoid(46); int32_t tmp[MAX_AXIS_NUM]; float tmpf; @@ -1173,7 +1168,6 @@ void AxesProcess (dev_config_t * p_dev_config) NVIC_EnableIRQ(TIM2_IRQn); } - SEGGER_SYSVIEW_RecordEndCall(46); } /** diff --git a/application/Src/buttons.c b/application/Src/buttons.c index 56f21f5..6b784c8 100644 --- a/application/Src/buttons.c +++ b/application/Src/buttons.c @@ -25,8 +25,6 @@ #include "buttons.h" #include "string.h" -#include "SEGGER_SYSVIEW.h" - uint8_t raw_buttons_data[MAX_BUTTONS_NUM]; physical_buttons_state_t physical_buttons_state[MAX_BUTTONS_NUM]; logical_buttons_state_t logical_buttons_state[MAX_BUTTONS_NUM]; @@ -167,7 +165,6 @@ static void LogicalButtonProcessTimer (logical_buttons_state_t * p_button_state, */ void LogicalButtonProcessState (logical_buttons_state_t * p_button_state, uint8_t * pov_buf, dev_config_t * p_dev_config, uint8_t num) { - SEGGER_SYSVIEW_RecordVoid(49); uint32_t millis; uint8_t pov_group = 0; @@ -566,7 +563,6 @@ void LogicalButtonProcessState (logical_buttons_state_t * p_button_state, uint8_ default: break; } - SEGGER_SYSVIEW_RecordEndCall(49); } /** @@ -721,8 +717,6 @@ void SingleButtonsGet (uint8_t * raw_button_data_buf, dev_config_t * p_dev_confi uint8_t ButtonsReadPhysical(dev_config_t * p_dev_config, uint8_t * p_buf) { - SEGGER_SYSVIEW_RecordVoid(47); - uint8_t pos = 0; // Getting physical buttons states @@ -733,8 +727,6 @@ uint8_t ButtonsReadPhysical(dev_config_t * p_dev_config, uint8_t * p_buf) a2b_last = pos; SingleButtonsGet(p_buf, p_dev_config, &pos); - SEGGER_SYSVIEW_RecordEndCall(47); - return pos; } @@ -745,8 +737,6 @@ uint8_t ButtonsReadPhysical(dev_config_t * p_dev_config, uint8_t * p_buf) */ void ButtonsReadLogical (dev_config_t * p_dev_config) { - SEGGER_SYSVIEW_RecordVoid(48); - // Process regular buttons for (uint8_t i=0; iCR1 |= I2C_CR1_SWRST; I2C1->CR1 &= ~I2C_CR1_SWRST; I2C_Start(); - - SEGGER_SYSVIEW_RecordEndCall(36); } @@ -504,12 +478,8 @@ void I2C1_ER_IRQHandler(void) * @brief This function handles USB low priority or CAN RX0 interrupts. */ void USB_LP_CAN1_RX0_IRQHandler(void) -{ - SEGGER_SYSVIEW_RecordVoid(37); - +{ USB_Istr(); - - SEGGER_SYSVIEW_RecordEndCall(37); } /** diff --git a/armgcc/Makefile b/armgcc/Makefile index ff1bb99..41639bb 100644 --- a/armgcc/Makefile +++ b/armgcc/Makefile @@ -1,200 +1,13 @@ - -###################################### -# target -###################################### -TARGET = FreeJoy - - -###################################### -# building variables -###################################### -# debug build? -DEBUG = 1 -# optimization -OPT = -O3 - - -####################################### -# paths -####################################### -# Build path -BUILD_DIR = build - -###################################### -# source -###################################### -# C sources -C_SOURCES = \ -../Src/analog.c \ -../Src/axis_to_buttons.c \ -../Src/buttons.c \ -../Src/crc16.c \ -../Src/encoders.c \ -../Src/config.c \ -../Src/leds.c \ -../Src/main.c \ -../Src/periphery.c \ -../Src/tle5011.c \ -../Src/as5600.c \ -../Src/ads1115.c \ -../Src/mlx90393.c \ -../Src/mcp320x.c \ -../Src/shift_registers.c \ -../Src/spi.c \ -../Src/i2c.c \ -../Src/stm32f10x_it.c \ -../Src/usb_desc.c \ -../Src/usb_endp.c \ -../Src/usb_hw.c \ -../Src/usb_istr.c \ -../Src/usb_prop.c \ -../Src/usb_pwr.c \ -../Drivers/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.c \ -../Drivers/STM32F10x_StdPeriph_Driver/src/misc.c \ -../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c \ -../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c \ -../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c \ -../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c \ -../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c \ -../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c \ -../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c \ -../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c \ -../Drivers/STM32_USB-FS-Device_Driver/src/usb_core.c \ -../Drivers/STM32_USB-FS-Device_Driver/src/usb_init.c \ -../Drivers/STM32_USB-FS-Device_Driver/src/usb_int.c \ -../Drivers/STM32_USB-FS-Device_Driver/src/usb_mem.c \ -../Drivers/STM32_USB-FS-Device_Driver/src/usb_regs.c \ -../Drivers/STM32_USB-FS-Device_Driver/src/usb_sil.c \ - -# ASM sources -ASM_SOURCES = \ -startup_stm32f103xb.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-m3 - -# fpu -# NONE for Cortex-M0/M0+/M3 - -# float-abi - - -# mcu -MCU = $(CPU) -mthumb $(FPU) $(FLOAT-ABI) - -# macros for gcc -# AS defines -AS_DEFS = - -# C defines -C_DEFS = \ --DUSE_STDPERIPH_DRIVER \ --DSTM32F10X_MD - - -# AS includes -AS_INCLUDES = - -# C includes -C_INCLUDES = \ --I../Inc \ --I../Drivers/CMSIS/CM3/CoreSupport \ --I../Drivers/CMSIS/CM3/DeviceSupport/ST/STM32F10x \ --I../Drivers/STM32F10x_StdPeriph_Driver/inc \ --I../Drivers/STM32_USB-FS-Device_Driver/inc - - -# 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 = STM32F103C8Tx_FLASH.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 -all: $(BUILD_DIR)/$(TARGET).elf $(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 *** \ No newline at end of file +all: + make -f makefile.app + make -f makefile.boot + +app: + make -f makefile.app + +boot: + make -f makefile.boot + +clean: + make -f makefile.app clean + make -f makefile.boot clean \ No newline at end of file diff --git a/armgcc/STM32F103C8Tx_FLASH.ld b/armgcc/linker_app.ld similarity index 99% rename from armgcc/STM32F103C8Tx_FLASH.ld rename to armgcc/linker_app.ld index 12b259f..d3bd4aa 100644 --- a/armgcc/STM32F103C8Tx_FLASH.ld +++ b/armgcc/linker_app.ld @@ -62,7 +62,7 @@ _Min_Stack_Size = 0x400; /* required amount of stack */ MEMORY { RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K -FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 64K +FLASH (rx) : ORIGIN = 0x8002000, LENGTH = 50K } /* Define output sections */ diff --git a/armgcc/linker_boot.ld b/armgcc/linker_boot.ld new file mode 100644 index 0000000..bf81cc2 --- /dev/null +++ b/armgcc/linker_boot.ld @@ -0,0 +1,189 @@ +/* +****************************************************************************** +** + +** File : LinkerScript.ld +** +** Author : Auto-generated by Ac6 System Workbench +** +** Abstract : Linker script for STM32F103C8Tx series +** 64Kbytes FLASH and 20Kbytes RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Distribution: The file is distributed “as is,” without any warranty +** of any kind. +** +***************************************************************************** +** @attention +** +**

© COPYRIGHT(c) 2014 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 = 0x20005000; /* 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 = 20K +FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 8K +} + +/* 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(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + + diff --git a/armgcc/makefile.app b/armgcc/makefile.app new file mode 100644 index 0000000..bb9e568 --- /dev/null +++ b/armgcc/makefile.app @@ -0,0 +1,206 @@ + +###################################### +# target +###################################### +TARGET = FreeJoy + + +###################################### +# building variables +###################################### +# debug build? +DEBUG = 1 +# optimization +OPT = -O3 + + +####################################### +# paths +####################################### +# Build path +BUILD_DIR = build/app + +###################################### +# source +###################################### +# C sources +C_SOURCES = \ +../application/Src/analog.c \ +../application/Src/axis_to_buttons.c \ +../application/Src/buttons.c \ +../utils/crc16.c \ +../application/Src/encoders.c \ +../application/Src/config.c \ +../application/Src/leds.c \ +../application/Src/main.c \ +../application/Src/periphery.c \ +../application/Src/tle5011.c \ +../application/Src/as5600.c \ +../application/Src/ads1115.c \ +../application/Src/mlx90393.c \ +../application/Src/mcp320x.c \ +../application/Src/shift_registers.c \ +../application/Src/spi.c \ +../application/Src/i2c.c \ +../application/Src/stm32f10x_it.c \ +../application/Src/usb_desc.c \ +../application/Src/usb_endp.c \ +../application/Src/usb_hw.c \ +../application/Src/usb_istr.c \ +../application/Src/usb_prop.c \ +../application/Src/usb_pwr.c \ +../Drivers/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.c \ +../Drivers/STM32F10x_StdPeriph_Driver/src/misc.c \ +../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c \ +../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c \ +../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c \ +../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c \ +../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c \ +../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c \ +../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c \ +../Drivers/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_core.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_init.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_int.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_mem.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_regs.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_sil.c \ +#../SEGGER/SEGGER/SEGGER_SYSVIEW.c \ +#../SEGGER/SEGGER/SEGGER_RTT.c \ +#../SEGGER/SEGGER/SEGGER_RTT_printf.c \ +#../SEGGER/Sample/NoOS/Config/Cortex-M/SEGGER_SYSVIEW_Config_NoOS.c + +# ASM sources +ASM_SOURCES = \ +startup_stm32f103xb.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-m3 + +# fpu +# NONE for Cortex-M0/M0+/M3 + +# float-abi + + +# mcu +MCU = $(CPU) -mthumb $(FPU) $(FLOAT-ABI) + +# macros for gcc +# AS defines +AS_DEFS = + +# C defines +C_DEFS = \ +-DUSE_STDPERIPH_DRIVER \ +-DSTM32F10X_MD + + +# AS includes +AS_INCLUDES = + +# C includes +C_INCLUDES = \ +-I../Drivers/CMSIS/CM3/CoreSupport \ +-I../Drivers/CMSIS/CM3/DeviceSupport/ST/STM32F10x \ +-I../Drivers/STM32F10x_StdPeriph_Driver/inc \ +-I../Drivers/STM32_USB-FS-Device_Driver/inc \ +-I../application/Inc \ +-I../utils \ +#-I../SEGGER/SEGGER \ +#-I../SEGGER/Config + +# 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 = linker_app.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).bin $(BUILD_DIR)/$(TARGET).hex +#all: $(BUILD_DIR)/$(TARGET).elf $(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 -p $@ + +####################################### +# clean up +####################################### +clean: + -rm -fR $(BUILD_DIR) + +####################################### +# dependencies +####################################### +-include $(wildcard $(BUILD_DIR)/*.d) + +# *** EOF *** \ No newline at end of file diff --git a/armgcc/makefile.boot b/armgcc/makefile.boot new file mode 100644 index 0000000..7209b34 --- /dev/null +++ b/armgcc/makefile.boot @@ -0,0 +1,179 @@ + +###################################### +# target +###################################### +TARGET = Bootloader + + +###################################### +# building variables +###################################### +# debug build? +DEBUG = 1 +# optimization +OPT = -O3 + + +####################################### +# paths +####################################### +# Build path +BUILD_DIR = build/boot + +###################################### +# source +###################################### +# C sources +C_SOURCES = \ +../utils/crc16.c \ +../bootloader/Src/main.c \ +../bootloader/Src/periphery.c \ +../bootloader/Src/stm32f10x_it.c \ +../bootloader/Src/usb_desc.c \ +../bootloader/Src/usb_endp.c \ +../bootloader/Src/usb_hw.c \ +../bootloader/Src/usb_istr.c \ +../bootloader/Src/usb_prop.c \ +../bootloader/Src/usb_pwr.c \ +../Drivers/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.c \ +../Drivers/STM32F10x_StdPeriph_Driver/src/misc.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_core.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_init.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_int.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_mem.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_regs.c \ +../Drivers/STM32_USB-FS-Device_Driver/src/usb_sil.c \ + +# ASM sources +ASM_SOURCES = \ +startup_stm32f103xb.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-m3 + +# fpu +# NONE for Cortex-M0/M0+/M3 + +# float-abi + + +# mcu +MCU = $(CPU) -mthumb $(FPU) $(FLOAT-ABI) + +# macros for gcc +# AS defines +AS_DEFS = + +# C defines +C_DEFS = \ +-DUSE_STDPERIPH_DRIVER \ +-DSTM32F10X_MD + + +# AS includes +AS_INCLUDES = + +# C includes +C_INCLUDES = \ +-I../Drivers/CMSIS/CM3/CoreSupport \ +-I../Drivers/CMSIS/CM3/DeviceSupport/ST/STM32F10x \ +-I../Drivers/STM32F10x_StdPeriph_Driver/inc \ +-I../Drivers/STM32_USB-FS-Device_Driver/inc \ +-I../bootloader/Inc \ +-I../utils \ + + +# 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 = linker_boot.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 +all: $(BUILD_DIR)/$(TARGET).elf $(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 -p $@ + +####################################### +# clean up +####################################### +clean: + -rm -fR $(BUILD_DIR) + +####################################### +# dependencies +####################################### +-include $(wildcard $(BUILD_DIR)/*.d) + +# *** EOF *** \ No newline at end of file diff --git a/armgcc/readme.txt b/armgcc/readme.txt new file mode 100644 index 0000000..712cff2 --- /dev/null +++ b/armgcc/readme.txt @@ -0,0 +1,51 @@ +I. Building binaries from source with ARM GCC compiler + +The firmware consist of 2 parts: +- bootloader +- application + +Both parts can be build separately or together. For building use following commands: + +1) Building bootloader: + +> make boot + +2) Building application: + +> make app + +3) Building both bootloader and application: + +> make + +or + +> make all + +4) Cleaning build directories: + +> make clean + + +After building binaries and hex files are place in build sub-directories: + +/build/app/Bootlooader.bin +/build/app/FreeJoy.bin +/build/app/FreeJoy.hex + + +II. Flashing binaries to MCU + +Bootlooader and aplication have different base addresses in flash memory: + +bootloader base address: 0x8000000 +bootloader flash size: 0x2000 + +aplication base address: 0x8002000 +aplication flash size: 0xC800 + +So as you can see FreeJoy application have 0x2000 ofsset from the start of the flash memory (0x8000000). If you flashing .bin files the offset must be applied to the start address. + + + + diff --git a/armgcc/startup_stm32f103xb.s b/armgcc/startup_stm32f103xb.s index 3a0a3b9..1bdd524 100644 --- a/armgcc/startup_stm32f103xb.s +++ b/armgcc/startup_stm32f103xb.s @@ -1,379 +1,379 @@ -/** - *************** (C) COPYRIGHT 2017 STMicroelectronics ************************ - * @file startup_stm32f103xb.s - * @author MCD Application Team - * @version V4.2.0 - * @date 31-March-2017 - * @brief STM32F103xB Devices vector table for Atollic toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * - *

© COPYRIGHT(c) 2017 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. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m3 - .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 - -.equ BootRAM, 0xF108F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - -/* 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], #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 - bx lr -.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 M3. 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_IRQHandler - .word TAMPER_IRQHandler - .word RTC_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_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTC_Alarm_IRQHandler - .word USBWakeUp_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x108. This is for boot in RAM mode for - STM32F10x Medium Density devices. */ - -/******************************************************************************* -* -* 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_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_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_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_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_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_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 TIM4_IRQHandler - .thumb_set TIM4_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 I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_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 USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_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 USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - +/** + *************** (C) COPYRIGHT 2017 STMicroelectronics ************************ + * @file startup_stm32f103xb.s + * @author MCD Application Team + * @version V4.2.0 + * @date 31-March-2017 + * @brief STM32F103xB Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * + *

© COPYRIGHT(c) 2017 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. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .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 + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* 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], #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 + bx lr +.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 M3. 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_IRQHandler + .word TAMPER_IRQHandler + .word RTC_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_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTC_Alarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* 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_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_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_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_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_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_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 TIM4_IRQHandler + .thumb_set TIM4_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 I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_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 USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_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 USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ +