From 91dc120678c665e140f5e22276b74b358c7b34a1 Mon Sep 17 00:00:00 2001 From: Floris Romeijn Date: Tue, 31 Oct 2023 20:12:43 +0100 Subject: [PATCH 01/11] able to build with gcc --- .gitignore | 1 + .../Source/GCC/startup_hk32f030mf4p6.s | 245 ++++++++++++++++++ LCM/Library/LDScripts/hk32f030mf4p6.ld | 163 ++++++++++++ LCM/Makefile | 75 ++++++ LCM/Readme/Readme.txt | 6 - LCM/rules.mk | 124 +++++++++ README.md | 71 +++++ 7 files changed, 679 insertions(+), 6 deletions(-) create mode 100644 LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/CMSIS/HK32F030M/Source/GCC/startup_hk32f030mf4p6.s create mode 100644 LCM/Library/LDScripts/hk32f030mf4p6.ld create mode 100644 LCM/Makefile delete mode 100644 LCM/Readme/Readme.txt create mode 100644 LCM/rules.mk create mode 100644 README.md diff --git a/.gitignore b/.gitignore index e4961bac..2629c4ea 100644 --- a/.gitignore +++ b/.gitignore @@ -4,3 +4,4 @@ LCM/Project/MDK5/Objects/ LCM/Project/MDK5/LCM_Light_Control_IO_WS2812_New.uvguix.* LCM/Project/MDK5/Listings/ +LCM/Build/ diff --git a/LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/CMSIS/HK32F030M/Source/GCC/startup_hk32f030mf4p6.s b/LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/CMSIS/HK32F030M/Source/GCC/startup_hk32f030mf4p6.s new file mode 100644 index 00000000..822b0749 --- /dev/null +++ b/LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/CMSIS/HK32F030M/Source/GCC/startup_hk32f030mf4p6.s @@ -0,0 +1,245 @@ +/** + ****************************************************************************** + * @file startup_hk32f030mf4p6.s + * @brief HK32F030MF4P6 devices vector table for 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-M0 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + */ + + .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 */ + ldr r0, =_sdata + ldr r1, =_edata + ldr r2, =_sidata + movs r3, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r4, [r2, r3] + str r4, [r0, r3] + adds r3, r3, #4 + +LoopCopyDataInit: + adds r4, r0, r3 + cmp r4, r1 + bcc CopyDataInit + +/* Zero fill the bss segment. */ + ldr r2, =_sbss + ldr r4, =_ebss + movs r3, #0 + b LoopFillZerobss + +FillZerobss: + str r3, [r2] + adds r2, r2, #4 + +LoopFillZerobss: + cmp r2, r4 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors. Remove this line if compile with `-nostartfiles` reports error */ + 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 0 /* Reserved */ + .word EXTI11_IRQHandler /* EXTI Line 11 interrupt(AWU_WKP) */ + .word FLASH_IRQHandler /* FLASH */ + .word RCC_IRQHandler /* RCC */ + .word EXTI0_IRQHandler /* EXTI Line 0 */ + .word EXTI1_IRQHandler /* EXTI Line 1 */ + .word EXTI2_IRQHandler /* EXTI Line 2 */ + .word EXTI3_IRQHandler /* EXTI Line 3 */ + .word EXTI4_IRQHandler /* EXTI Line 4 */ + .word EXTI5_IRQHandler /* EXTI Line 5 */ + .word TIM1_BRK_IRQHandler /* TIM1 break interrupt */ + .word ADC1_IRQHandler /* ADC1 interrupt, combined with EXTI line 8 */ + .word TIM1_UP_TRG_COM_IRQHandler /* TIM1 Update, Trigger and Commutation */ + .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ + .word TIM2_IRQHandler /* TIM2 */ + .word 0 /* Reserved */ + .word TIM6_IRQHandler /* TIM6 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word EXTI6_IRQHandler /* EXTI Line 6 */ + .word EXTI7_IRQHandler /* EXTI Line 7 */ + .word I2C1_IRQHandler /* I2C1 global interrupt, combined with EXTI Line 10 */ + .word 0 /* Reserved */ + .word SPI1_IRQHandler /* SPI1 */ + .word 0 /* Reserved */ + .word USART1_IRQHandler /* USART1 global interrupt, combined with EXTI Line 9 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + +/******************************************************************************* +* +* 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 EXTI11_IRQHandler + .thumb_set EXTI11_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 EXTI5_IRQHandler + .thumb_set EXTI5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak TIM1_UP_TRG_COM_IRQHandler + .thumb_set TIM1_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 TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak EXTI6_IRQHandler + .thumb_set EXTI6_IRQHandler,Default_Handler + + .weak EXTI7_IRQHandler + .thumb_set EXTI7_IRQHandler,Default_Handler + + .weak I2C1_IRQHandler + .thumb_set I2C1_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler diff --git a/LCM/Library/LDScripts/hk32f030mf4p6.ld b/LCM/Library/LDScripts/hk32f030mf4p6.ld new file mode 100644 index 00000000..f619651d --- /dev/null +++ b/LCM/Library/LDScripts/hk32f030mf4p6.ld @@ -0,0 +1,163 @@ +/* +****************************************************************************** +** +** File : LinkerScript.ld +** +** Abstract : Linker script for HK32F030Mx series +** Set heap size, stack size and stack location according +** to application requirements. +** Set memory bank area and size if external memory is used. +** +** Distribution: The file is distributed “as is,” without any warranty +** of any kind. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of RAM */ +/* + Generate a link error if heap and stack don't fit into RAM. + These numbers affect the USED size of RAM +*/ +_Min_Heap_Size = 0x200; /* required amount of heap: 512 bytes */ +_Min_Stack_Size = 0x400; /* required amount of stack: 1024 bytes */ + +/* Specify the memory areas */ +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 4K + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K + EEPROM (rx) : ORIGIN = 0x0C000000, LENGTH = 448 +} + +/* Define output sections */ +SECTIONS +{ + .eeprom : + { + . = ALIGN(4); + KEEP(*(.eeprom)) /* .eeprom section */ + . = ALIGN(4); + } >EEPROM + + /* 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/LCM/Makefile b/LCM/Makefile new file mode 100644 index 00000000..6e1b33e1 --- /dev/null +++ b/LCM/Makefile @@ -0,0 +1,75 @@ +# Based on https://github.com/IOsetting/hk32f030m-template/blob/master/Makefile +##### Project ##### + +PROJECT ?= app +# The path for generated files +BUILD_DIR = Build + + +##### Options ##### + +# Enable printf float %f support, y:yes, n:no +ENABLE_PRINTF_FLOAT ?= n +# Build with FreeRTOS, y:yes, n:no +USE_FREERTOS ?= n +# Programmer, jlink or pyocd +FLASH_PROGRM ?= jlink + + +##### Toolchains ####### + +# path to gcc arm +# ARM_TOOCHAIN ?= /opt/gcc-arm/arm-gnu-toolchain-12.2.mpacbti-rel1-x86_64-arm-none-eabi/bin +# path to JLinkExe +JLINKEXE ?= /opt/SEGGER/JLink/JLinkExe +# JLink device type: HK32F030MD4P6, HK32F030MF4U6, HK32F030MF4P6 or HK32F030MJ4M6 +JLINK_DEVICE ?= HK32F030MF4P6 +# path to PyOCD +PYOCD_EXE ?= pyocd +# PyOCD device type: hk32f030md4p6, hk32f030mf4p6, hk32f030mf4u6, hk32f030mj4m6 +PYOCD_DEVICE ?= hk32f030mf4p6 + + +##### Paths ############ + +# Link descript file +LDSCRIPT = Library/LDScripts/hk32f030mf4p6.ld +# Library build flags +LIB_FLAGS = HK32F030MF4P6 + +# C source folders +CDIRS := Code/App \ + Code/Drive \ + Code/User \ + Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/CMSIS/HK32F030M/Source/GCC \ + Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/CMSIS/HK32F030M/Source \ + Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/HK32F030M_Lib/src/ + +# C source files (if there are any single ones) +CFILES := + +# ASM source folders +ADIRS := Code/User +# ASM single files +AFILES := Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/CMSIS/HK32F030M/Source/GCC/startup_hk32f030mf4p6.s + +# Include paths +INCLUDES := Code/App \ + Code/Drive \ + Code/User \ + Libraries/CMSIS/HK32F030M/Source/ \ + Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/CMSIS/HK32F030M/Include \ + Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/CMSIS/CM0/Core/ \ + Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/HK32F030M_Lib/inc + +ifeq ($(USE_FREERTOS),y) +CDIRS += Libraries/FreeRTOS \ + Libraries/FreeRTOS/portable/GCC/ARM_CM0 + +CFILES += Libraries/FreeRTOS/portable/MemMang/heap_4.c + +INCLUDES += Libraries/FreeRTOS/include \ + Libraries/FreeRTOS/portable/GCC/ARM_CM0 +endif + +include ./rules.mk diff --git a/LCM/Readme/Readme.txt b/LCM/Readme/Readme.txt deleted file mode 100644 index e4a77164..00000000 --- a/LCM/Readme/Readme.txt +++ /dev/null @@ -1,6 +0,0 @@ -This code is a continuation of the stock Floatwheel LCM (Light Control Module). This version offers added features. On the side off the LCM an expended messaging structure was added (to work in combination with the Comm bridge that was created in a custom Float Package). -EEPROM writes and reads, store settings on the LCM without having to flash again. This brings some features such as changing the preset lighting profiles, remembering which profile was last used, changing boot animation and cell type and more. - -TODO: -Include Float package buzzer support (let the vesc controll the buzzer). - diff --git a/LCM/rules.mk b/LCM/rules.mk new file mode 100644 index 00000000..047b80dd --- /dev/null +++ b/LCM/rules.mk @@ -0,0 +1,124 @@ +# 'make V=1' will show all compiler calls. +V ?= 0 +ifeq ($(V),0) +Q := @ +NULL := 2>/dev/null +endif + +ifdef ARM_TOOCHAIN +PREFIX ?= $(ARM_TOOCHAIN)/arm-none-eabi- +else +PREFIX = arm-none-eabi- +endif +CC = $(PREFIX)gcc +AS = $(PREFIX)as +LD = $(PREFIX)ld +OBJCOPY = $(PREFIX)objcopy +# `$(shell pwd)` or `.`, both works +TOP = . +BDIR = $(TOP)/$(BUILD_DIR) + +# For each direcotry, add it to csources +CSOURCES := $(foreach dir, $(CDIRS), $(shell find $(TOP)/$(dir) -maxdepth 1 -name '*.c')) +# Add single c source files to csources +CSOURCES += $(addprefix $(TOP)/, $(CFILES)) +# Then assembly source folders and files +ASOURCES := $(foreach dir, $(ADIRS), $(shell find $(TOP)/$(dir) -maxdepth 1 -name '*.s')) +ASOURCES += $(addprefix $(TOP)/, $(AFILES)) + +# Fill object files with c and asm files (keep source directory structure) +OBJS = $(CSOURCES:$(TOP)/%.c=$(BDIR)/%.o) +OBJS += $(ASOURCES:$(TOP)/%.s=$(BDIR)/%.o) +# d files for detecting h file changes +DEPS=$(CSOURCES:$(TOP)/%.c=$(BDIR)/%.d) + +# Arch and target specified flags +ARCH_FLAGS := -mthumb -mcpu=cortex-m0 -fno-common +# Debug options, -gdwarf-2 for debug, -g0 for release +# https://gcc.gnu.org/onlinedocs/gcc-12.2.0/gcc/Debugging-Options.html +# -g: system’s native format, -g0:off, -g/g1,-g2,-g3 -> more verbosely +# -ggdb: for gdb, -ggdb0:off, -ggdb/ggdb1,-ggdb2,-ggdb3 -> more verbosely +# -gdwarf: in DWARF format, -gdwarf-2,-gdwarf-3,-gdwarf-4,-gdwarf-5 +DEBUG_FLAGS ?= -gdwarf-3 + +# c flags +OPT ?= -Os +CSTD ?= -std=c99 +TGT_CFLAGS += $(ARCH_FLAGS) $(DEBUG_FLAGS) $(OPT) $(CSTD) $(addprefix -D, $(LIB_FLAGS)) \ + -Wall -ffunction-sections -fdata-sections -ffreestanding -flto \ + -fsingle-precision-constant + +# asm flags +TGT_ASFLAGS += $(ARCH_FLAGS) $(DEBUG_FLAGS) $(OPT) -Wa,--warn + +# ld flags +TGT_LDFLAGS += $(ARCH_FLAGS) -specs=nano.specs -specs=nosys.specs -static -lc -lm \ + -Wl,-Map=$(BDIR)/$(PROJECT).map \ + -Wl,--gc-sections \ + -Wl,--print-memory-usage \ + -Wl,--cref +# Exclude standard initialization actions, when __libc_init_array exists, this should be omit, \ + otherwise it will generate "undefined reference to `_init'" error. \ + **Remove** `bl __libc_init_array` from startup.s if you want to enable this. +# TGT_LDFLAGS += -nostartfiles + +ifeq ($(ENABLE_PRINTF_FLOAT),y) +TGT_LDFLAGS += -u _printf_float +endif + +### included paths ### +TGT_INCFLAGS := $(addprefix -I $(TOP)/, $(INCLUDES)) + + +.PHONY: all clean flash echo + +all: $(BDIR)/$(PROJECT).elf $(BDIR)/$(PROJECT).bin $(BDIR)/$(PROJECT).hex + +# for debug +echo: + $(info 1. $(AFILES)) + $(info 2. $(ASOURCES)) + $(info 3. $(CSOURCES)) + $(info 4. $(OBJS)) + $(info 5. $(TGT_INCFLAGS)) + +# include d files without non-exist warning +-include $(DEPS) + +# Compile c to obj -- should be `$(BDIR)/%.o: $(TOP)/%.c`, but since $(TOP) is base folder so non-path also works +$(BDIR)/%.o: %.c + @printf " CC\t$<\n" + @mkdir -p $(dir $@) + $(Q)$(CC) $(TGT_CFLAGS) $(TGT_INCFLAGS) -o $@ -c $< -MD -MF $(BDIR)/$*.d -MP + +# Compile asm to obj +$(BDIR)/%.o: %.s + @printf " AS\t$<\n" + @mkdir -p $(dir $@) + $(Q)$(CC) $(TGT_ASFLAGS) -o $@ -c $< + +# Link object files to elf +$(BDIR)/$(PROJECT).elf: $(OBJS) $(TOP)/$(LDSCRIPT) + @printf " LD\t$@\n" + $(Q)$(CC) $(TGT_LDFLAGS) -T$(TOP)/$(LDSCRIPT) $(OBJS) -o $@ + +# Convert elf to bin +%.bin: %.elf + @printf " OBJCP BIN\t$@\n" + $(Q)$(OBJCOPY) -I elf32-littlearm -O binary $< $@ + +# Convert elf to hex +%.hex: %.elf + @printf " OBJCP HEX\t$@\n" + $(Q)$(OBJCOPY) -I elf32-littlearm -O ihex $< $@ + +clean: + rm -rf $(BDIR)/* + +flash: +ifeq ($(FLASH_PROGRM),jlink) + $(JLINKEXE) -device $(JLINK_DEVICE) -if swd -speed 4000 -JLinkScriptFile $(TOP)/Misc/jlink-script -CommanderScript $(TOP)/Misc/jlink-command +else ifeq ($(FLASH_PROGRM),pyocd) + $(PYOCD_EXE) erase -c -t $(PYOCD_DEVICE) --config $(TOP)/Misc/pyocd.yaml + $(PYOCD_EXE) load $(BDIR)/$(PROJECT).hex -t $(PYOCD_DEVICE) --config $(TOP)/Misc/pyocd.yaml +endif diff --git a/README.md b/README.md new file mode 100644 index 00000000..4f2d2d85 --- /dev/null +++ b/README.md @@ -0,0 +1,71 @@ +# Floatwheel Light Control Module + +This code is a continuation of the stock Floatwheel LCM (Light Control Module). This version offers added features. On the side off the LCM an expended messaging structure was added (to work in combination with the Comm bridge that was created in a custom Float Package). +EEPROM writes and reads, store settings on the LCM without having to flash again. This brings some features such as changing the preset lighting profiles, remembering which profile was last used, changing boot animation and cell type and more. + +TODO: +Include Float package buzzer support (let the vesc control the buzzer). + +## Building with GCC / Makefile (Linux) + +### Requirements + +* Programmer + * PyOCD: DAPLink, J-Link or ST-LINK +* PyOCD [https://pyocd.io/](https://pyocd.io/) +* GNU Arm Embedded Toolchain + +### Building + +#### 1. Install GNU Arm Embedded Toolchain + +On debian based systems simply use + +```bash +sudo apt install gcc-arm-none-eabi +``` + +or + +Download the toolchain from [Arm GNU Toolchain Downloads](https://developer.arm.com/downloads/-/arm-gnu-toolchain-downloads) according to your pc architecture, extract the files + +```bash +cd ~/Downloads +curl https://developer.arm.com/-/media/Files/downloads/gnu/12.2.mpacbti-rel1/binrel/arm-gnu-toolchain-12.2.mpacbti-rel1-x86_64-arm-none-eabi.tar.xz -L -o arm-gnu-toolchain-12.2.mpacbti-rel1-x86_64-arm-none-eabi.tar.xz +tar xvf arm-gnu-toolchain-12.2.mpacbti-rel1-x86_64-arm-none-eabi.tar.xz +sudo mkdir -p /opt/gcc-arm +cd /opt/gcc-arm/ +sudo mv ~/Downloads/arm-gnu-toolchain-12.2.mpacbti-rel1-x86_64-arm-none-eabi/ . +sudo chown -R root:root arm-gnu-toolchain-12.2.mpacbti-rel1-x86_64-arm-none-eabi/ +``` + +add /opt/gcc-arm/arm-gnu-toolchain-12.2.rel1-x86_64-arm-none-eabi/bin to you `PATH` or define `ARM_TOOCHAIN` in `Makefile` + +#### 2. Install PyOCD + +Install from pip instead of apt repository because the version is 0.13.1+dfsg-1, which is too low to recognize J-Link probe + +```bash +pip install pyocd +``` + +#### 3. Clone This Repository + +Clone this repository to local workspace + +#### 4. Compiling And Flashing + +```bash +# clean source code +make clean +# build +make +# or make with verbose output +V=1 make +# flash +make flash +``` + +#### 5. Troubleshooting + +* Image is too big, make sure you are not using double functions From e302253256954f6d549dcfb051a57631d583dec5 Mon Sep 17 00:00:00 2001 From: Floris Romeijn Date: Tue, 31 Oct 2023 21:50:59 +0100 Subject: [PATCH 02/11] make flash --- LCM/Makefile | 2 +- LCM/rules.mk | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/LCM/Makefile b/LCM/Makefile index 6e1b33e1..9c1bae89 100644 --- a/LCM/Makefile +++ b/LCM/Makefile @@ -13,7 +13,7 @@ ENABLE_PRINTF_FLOAT ?= n # Build with FreeRTOS, y:yes, n:no USE_FREERTOS ?= n # Programmer, jlink or pyocd -FLASH_PROGRM ?= jlink +FLASH_PROGRM ?= pyocd ##### Toolchains ####### diff --git a/LCM/rules.mk b/LCM/rules.mk index 047b80dd..802a9dbc 100644 --- a/LCM/rules.mk +++ b/LCM/rules.mk @@ -119,6 +119,6 @@ flash: ifeq ($(FLASH_PROGRM),jlink) $(JLINKEXE) -device $(JLINK_DEVICE) -if swd -speed 4000 -JLinkScriptFile $(TOP)/Misc/jlink-script -CommanderScript $(TOP)/Misc/jlink-command else ifeq ($(FLASH_PROGRM),pyocd) - $(PYOCD_EXE) erase -c -t $(PYOCD_DEVICE) --config $(TOP)/Misc/pyocd.yaml - $(PYOCD_EXE) load $(BDIR)/$(PROJECT).hex -t $(PYOCD_DEVICE) --config $(TOP)/Misc/pyocd.yaml + $(PYOCD_EXE) erase -c -t $(PYOCD_DEVICE) --config $(TOP)/pyocd.yaml + $(PYOCD_EXE) load $(BDIR)/$(PROJECT).hex -t $(PYOCD_DEVICE) --config $(TOP)/pyocd.yaml endif From a5b4305f46ade20f88399b176c793b42be967ba6 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 24 Mar 2024 14:05:44 +0100 Subject: [PATCH 03/11] Remove usage of floor Based on 46c875c2089d04f19d692c104828f197cec75676, except it removes completely the usage of floor() we don't need. --- LCM/Code/App/task.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/LCM/Code/App/task.c b/LCM/Code/App/task.c index f07e7ec8..85a5962a 100644 --- a/LCM/Code/App/task.c +++ b/LCM/Code/App/task.c @@ -222,7 +222,7 @@ static void WS2812_VESC(void) void WS2812_Boot(void) { uint8_t i; - uint8_t num = floor(Power_Time / 500) + 1; + uint8_t num = (Power_Time / 500) + 1; uint8_t bootAnims[10][3] = { // Default (blue...green) //{{10,0,30}, {9,3,27}, {8,6,24}, {7,9,21}, {6,12,18}, {5,15,15}, {4,18,12}, {3,21,9}, {2,24,6}, {1,27,3}}, @@ -255,7 +255,7 @@ void WS2812_Boot(void) void WS2812_Shutdown(void) { uint8_t brightness = 100; - int num = 10 - floor(Power_Time / 100); + int num = 10 - (Power_Time / 100); if (num < 1) { num = 1; } From 49217b8bbf5215900e336490c653281c50d82f3b Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 24 Mar 2024 14:14:51 +0100 Subject: [PATCH 04/11] Remove unused variables --- LCM/Code/App/task.c | 4 ---- 1 file changed, 4 deletions(-) diff --git a/LCM/Code/App/task.c b/LCM/Code/App/task.c index 85a5962a..e544e58b 100644 --- a/LCM/Code/App/task.c +++ b/LCM/Code/App/task.c @@ -143,7 +143,6 @@ static void WS2812_Power_Display(uint8_t brightness) **************************************************/ static void WS2812_VESC(void) { - uint8_t i; uint8_t pos, red; uint8_t green = 0; uint8_t blue = WS2812_Measure; @@ -412,8 +411,6 @@ static void WS2812_Handtest(void) **************************************************/ void WS2812_Task(void) { - uint8_t i; - if(Charge_Flag == 3) // Battery fully charged { WS2812_Set_AllColours(1,10,50,150,50); // white with a strong green tint @@ -729,7 +726,6 @@ static void Set_Headlights_Brightness(int brightness) void Headlights_Task(void) { static uint8_t gear_position_last = 0; - static bool isForward = false; if (Flashlight_Time < 10) { return; From 97394d2d02e52b6c7d577918cfe3afc14e8e0b63 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 24 Mar 2024 14:32:31 +0100 Subject: [PATCH 05/11] Remove duplicate/incorrect public declarations TI*_Config are static to hk32f030m_tim.c --- .../HK32F030M/HK32F030M_Lib/inc/hk32f030m_tim.h | 9 --------- 1 file changed, 9 deletions(-) diff --git a/LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/HK32F030M_Lib/inc/hk32f030m_tim.h b/LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/HK32F030M_Lib/inc/hk32f030m_tim.h index 7f9bdaea..b55f4934 100644 --- a/LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/HK32F030M_Lib/inc/hk32f030m_tim.h +++ b/LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/HK32F030M_Lib/inc/hk32f030m_tim.h @@ -951,15 +951,6 @@ void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity); void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState); -static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter); -static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter); -static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter); -static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter); - #ifdef __cplusplus } From 3131fd8a1936e46f2335b0c3488b05194a2c85e8 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 24 Mar 2024 14:57:58 +0100 Subject: [PATCH 06/11] Fix gcc linker flags - Remove unnecessary linker flags - Pass -flto also as a linker flag - Remove warning on RWX segments with gcc 13 --- LCM/rules.mk | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/LCM/rules.mk b/LCM/rules.mk index 802a9dbc..fe269ef5 100644 --- a/LCM/rules.mk +++ b/LCM/rules.mk @@ -52,9 +52,10 @@ TGT_CFLAGS += $(ARCH_FLAGS) $(DEBUG_FLAGS) $(OPT) $(CSTD) $(addprefix -D, $(LIB TGT_ASFLAGS += $(ARCH_FLAGS) $(DEBUG_FLAGS) $(OPT) -Wa,--warn # ld flags -TGT_LDFLAGS += $(ARCH_FLAGS) -specs=nano.specs -specs=nosys.specs -static -lc -lm \ +TGT_LDFLAGS += $(ARCH_FLAGS) -specs=nano.specs -specs=nosys.specs -flto \ -Wl,-Map=$(BDIR)/$(PROJECT).map \ -Wl,--gc-sections \ + -Wl,--no-warn-rwx-segments \ -Wl,--print-memory-usage \ -Wl,--cref # Exclude standard initialization actions, when __libc_init_array exists, this should be omit, \ From 907d217e084507646f9366ae9d4343e73319d20c Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 24 Mar 2024 15:09:52 +0100 Subject: [PATCH 07/11] Mark implicit fall-thru --- LCM/Code/App/test.c | 1 + 1 file changed, 1 insertion(+) diff --git a/LCM/Code/App/test.c b/LCM/Code/App/test.c index 05a35372..22fe0cc0 100644 --- a/LCM/Code/App/test.c +++ b/LCM/Code/App/test.c @@ -109,6 +109,7 @@ void Test_LED(void) case 1: led_pwm += 1; pwm_st = 2; + /* FALLTHRU */ case 2: led_pwm -= 500; if(led_pwm == 0) From b4f784b7fc7a9021a020a2ec4951da997826c5b5 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 24 Mar 2024 16:52:29 +0100 Subject: [PATCH 08/11] No not use any stdlib on GCC We're not using any libc function, so drop nano/nosys specs and use nostdlib directly. Stub _init() to get the default implementation of __libc_init_array. --- LCM/Code/User/main.c | 7 ++++--- LCM/rules.mk | 2 +- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/LCM/Code/User/main.c b/LCM/Code/User/main.c index 3e9d7ba7..06ba0926 100644 --- a/LCM/Code/User/main.c +++ b/LCM/Code/User/main.c @@ -37,9 +37,10 @@ //RCC_ClocksTypeDef RCC_Clock; -/* - -*/ +#ifdef __GNUC__ +// stub init (main is called explicitly during startup) +void _init(void) {} +#endif /************************************************** * @brie :main() diff --git a/LCM/rules.mk b/LCM/rules.mk index fe269ef5..12bcf02d 100644 --- a/LCM/rules.mk +++ b/LCM/rules.mk @@ -52,7 +52,7 @@ TGT_CFLAGS += $(ARCH_FLAGS) $(DEBUG_FLAGS) $(OPT) $(CSTD) $(addprefix -D, $(LIB TGT_ASFLAGS += $(ARCH_FLAGS) $(DEBUG_FLAGS) $(OPT) -Wa,--warn # ld flags -TGT_LDFLAGS += $(ARCH_FLAGS) -specs=nano.specs -specs=nosys.specs -flto \ +TGT_LDFLAGS += $(ARCH_FLAGS) -nostdlib -flto \ -Wl,-Map=$(BDIR)/$(PROJECT).map \ -Wl,--gc-sections \ -Wl,--no-warn-rwx-segments \ From af5763ebd9b088e581faeb469b7bf450669339aa Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 24 Mar 2024 16:56:35 +0100 Subject: [PATCH 09/11] Do not include stdio globally --- .../HK32F030M/HK32F030M_Lib/inc/hk32f030m_def.h | 1 - 1 file changed, 1 deletion(-) diff --git a/LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/HK32F030M_Lib/inc/hk32f030m_def.h b/LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/HK32F030M_Lib/inc/hk32f030m_def.h index 639f43c1..da53a7d1 100644 --- a/LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/HK32F030M_Lib/inc/hk32f030m_def.h +++ b/LCM/Library/HK32F030Mxx_Library_V1.1.6/HK32F030M/HK32F030M_Lib/inc/hk32f030m_def.h @@ -17,7 +17,6 @@ extern "C" { /* Includes ------------------------------------------------------------------*/ #include "hk32f030m.h" -#include #define UNUSED(X) (void)X /* To avoid gcc/g++ warnings */ From ecbbbda35fc1a5b40f1ea5fd6280fcb87aed10ff Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 24 Mar 2024 16:56:48 +0100 Subject: [PATCH 10/11] Reduce include pollution --- LCM/Code/App/vesc_uasrt.c | 1 + LCM/Code/App/vesc_uasrt.h | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/LCM/Code/App/vesc_uasrt.c b/LCM/Code/App/vesc_uasrt.c index 14090d7c..c1442b7b 100644 --- a/LCM/Code/App/vesc_uasrt.c +++ b/LCM/Code/App/vesc_uasrt.c @@ -1,6 +1,7 @@ #include "vesc_uasrt.h" #include "flag_bit.h" #include "eeprom.h" +#include uint8_t VESC_RX_Buff[32]; uint8_t VESC_RX_Flag = 0; diff --git a/LCM/Code/App/vesc_uasrt.h b/LCM/Code/App/vesc_uasrt.h index ffe5e44a..c30acee1 100644 --- a/LCM/Code/App/vesc_uasrt.h +++ b/LCM/Code/App/vesc_uasrt.h @@ -1,7 +1,6 @@ #ifndef __VESC_USART_H #define __VESC_USART_H -#include #include "hk32f030m.h" #include "crc.h" #include "usart.h" From 3869510120db4f7866ce3bc984157d542ca45829 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 24 Mar 2024 18:47:47 +0100 Subject: [PATCH 11/11] Fix statusbar with gcc Prevent a few delay loops from being elided --- LCM/Code/App/ws2812.c | 4 +++- LCM/Code/Drive/io_ws2812.c | 35 +++++++++++++---------------------- 2 files changed, 16 insertions(+), 23 deletions(-) diff --git a/LCM/Code/App/ws2812.c b/LCM/Code/App/ws2812.c index c6ada65b..f583ec12 100644 --- a/LCM/Code/App/ws2812.c +++ b/LCM/Code/App/ws2812.c @@ -121,7 +121,9 @@ void WS2812_Set_Colour(uint8_t num,uint8_t red,uint8_t green,uint8_t blue) void delay(uint16_t i) { - while(i--); + while(i--) { + __ASM volatile("nop"); + } } void WS2812_Refresh(void) diff --git a/LCM/Code/Drive/io_ws2812.c b/LCM/Code/Drive/io_ws2812.c index abc3d6d4..309c378b 100644 --- a/LCM/Code/Drive/io_ws2812.c +++ b/LCM/Code/Drive/io_ws2812.c @@ -39,34 +39,25 @@ void IO_WS2812_Init(void) } i=250 120us */ + void WS2812_0_Code(void) { - GPIOD->BSRR = GPIO_Pin_4; - GPIOD->BSRR = GPIO_Pin_4; - GPIOD->BSRR = GPIO_Pin_4; //250ns - + //250ns + for(int i = 0; i != 3; ++i) { + GPIOD->BSRR = GPIO_Pin_4; + __ASM volatile("" ::: "memory"); + } + GPIOD->BRR = GPIO_Pin_4; -// GPIOD->BRR = GPIO_Pin_4; -// GPIOD->BRR = GPIO_Pin_4; -// GPIOD->BRR = GPIO_Pin_4; -// GPIOD->BRR = GPIO_Pin_4; -// GPIOD->BRR = GPIO_Pin_4; -// GPIOD->BRR = GPIO_Pin_4; -// GPIOD->BRR = GPIO_Pin_4; //750ns } void WS2812_1_Code(void) { - GPIOD->BSRR = GPIO_Pin_4; - GPIOD->BSRR = GPIO_Pin_4; - GPIOD->BSRR = GPIO_Pin_4; - GPIOD->BSRR = GPIO_Pin_4; - GPIOD->BSRR = GPIO_Pin_4; - GPIOD->BSRR = GPIO_Pin_4; - GPIOD->BSRR = GPIO_Pin_4; - GPIOD->BSRR = GPIO_Pin_4; //750ns - + //750ns + for(int i = 0; i != 8; ++i) { + GPIOD->BSRR = GPIO_Pin_4; + __ASM volatile("" ::: "memory"); + } + GPIOD->BRR = GPIO_Pin_4; -// GPIOD->BRR = GPIO_Pin_4; -// GPIOD->BRR = GPIO_Pin_4; //250ns }