diff --git a/.editorconfig b/.editorconfig new file mode 100644 index 00000000..e32f6185 --- /dev/null +++ b/.editorconfig @@ -0,0 +1,33 @@ +# see https://editorconfig.org + +# top-most EditorConfig file +root = true + +# Unix-style newlines with a newline ending every file +[*] +end_of_line = lf +insert_final_newline = true + +# Matches multiple files with brace expansion notation +# Set default charset +[*.{js,py}] +charset = utf-8 + +# 2 space indentation for C +[*.{c,h}] +indent_style = space +indent_size = 2 + +# 4 space indentation +[*.py] +indent_style = space +indent_size = 4 + +# Tab indentation for Makefile +[Makefile] +indent_style = tab +indent_size = 8 + +[*.mk] +indent_style = tab +indent_size = 8 diff --git a/.git-blame-ignore-revs b/.git-blame-ignore-revs new file mode 100644 index 00000000..1061ed1b --- /dev/null +++ b/.git-blame-ignore-revs @@ -0,0 +1,7 @@ +# This file allows ignoring commits in git blame view on Github. +# For more info, see here: +# https://docs.github.com/en/repositories/working-with-files/using-files/viewing-a-file#ignore-commits-in-the-blame-view + +# global reformat +29cc6a9ca13c828c17396f01d0fa6b30571b3a1f + diff --git a/.github/workflows/CI_build.yml b/.github/workflows/CI_build.yml index cb855e05..323df40b 100644 --- a/.github/workflows/CI_build.yml +++ b/.github/workflows/CI_build.yml @@ -13,9 +13,10 @@ jobs: run: | make arm_sdk_install make -j8 + tools/linux/xpack-arm-none-eabi-gcc-10.3.1-2.3/bin/arm-none-eabi-size obj/*.elf - name: Archive build - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: AM32-bootloaders path: | diff --git a/.github/workflows/CI_build_macos.yml b/.github/workflows/CI_build_macos.yml index 7c61c09b..284a471b 100644 --- a/.github/workflows/CI_build_macos.yml +++ b/.github/workflows/CI_build_macos.yml @@ -15,7 +15,7 @@ jobs: make -j8 - name: Archive build - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: AM32-bootloaders path: | diff --git a/.github/workflows/CI_build_updaters.yml b/.github/workflows/CI_build_updaters.yml index 71aa699a..f3f1f726 100644 --- a/.github/workflows/CI_build_updaters.yml +++ b/.github/workflows/CI_build_updaters.yml @@ -15,17 +15,17 @@ jobs: make updaters -j8 - name: Archive build hex - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: AM32-bootloader-updaters-hex path: | obj/*_BL_UPDATER_*.hex - retention-days: 7 + retention-days: 60 - name: Archive build amj - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: AM32-bootloader-updaters-amj path: | obj/*_BL_UPDATER_*.amj - retention-days: 7 + retention-days: 60 diff --git a/.github/workflows/CI_build_windows.yml b/.github/workflows/CI_build_windows.yml index 38fe4e9a..688eeb75 100644 --- a/.github/workflows/CI_build_windows.yml +++ b/.github/workflows/CI_build_windows.yml @@ -15,7 +15,7 @@ jobs: tools/windows/make/bin/make - name: Archive build - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: AM32-bootloader path: | diff --git a/Inc/version.h b/Inc/version.h index 38b69b0b..e05be348 100644 --- a/Inc/version.h +++ b/Inc/version.h @@ -2,4 +2,7 @@ update this file for new releases */ -#define BOOTLOADER_VERSION 12 +#define BOOTLOADER_VERSION 15 + + + diff --git a/Makefile b/Makefile index 316a1273..038f6c10 100644 --- a/Makefile +++ b/Makefile @@ -20,7 +20,7 @@ ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST)))) include $(ROOT)/make/tools.mk # MCU builds, if with _xxK then adds build with given flash size -MCU_BUILDS := E230 F031 F051 F415 F415_128K F421 G071 G071_64K L431 L431_128K G431 V203 +MCU_BUILDS := E230 F031 F051 F415 F415_128K F421 G071 G071_64K L431 L431_128K G431 V203 L431_CAN F415_CAN # we support bootloader comms on a list of possible pins BOOTLOADER_PINS = PB4 PA2 PA6 PA15 PA0 @@ -86,11 +86,20 @@ SRC_BL := $(foreach dir,bootloader,$(wildcard $(dir)/*.[cs])) SRC_BLU := $(foreach dir,bl_update,$(wildcard $(dir)/*.[cs])) LDSCRIPT_BL := bootloader/ldscript_bl.ld +LDSCRIPT_BL_CAN := bootloader/ldscript_bl_CAN.ld LDSCRIPT_BLU := bl_update/ldscript_bl.ld +LDSCRIPT_BLU_CAN := bl_update/ldscript_bl_CAN.ld -# get a define in form -DBOARD_FLASH_SIZE=N if the target has a _NK suffix -define flash_size_flag -$(if $(findstring _,$1),-DBOARD_FLASH_SIZE=$(subst K,,$(word 2,$(subst _, ,$1)))) +# Function to extract CFLAGS based on target name +get_flash_size = $(if $(filter %K,$(word 2,$(subst _, ,$1))),-DBOARD_FLASH_SIZE=$(subst K,,$(word 2,$(subst _, ,$1)))) + +# Function to check for _CAN suffix +has_can_suffix = $(findstring _CAN,$1) + +# Function to return CFLAGS +define get_cflags + $(call get_flash_size,$1) \ + $(if $(call has_can_suffix,$1),-DDRONECAN_SUPPORT=1 -DBOARD_FLASH_SIZE=128,-DDRONECAN_SUPPORT=0) endef # get a tag in the form _nK if the build has a _nK suffix @@ -126,7 +135,7 @@ define CREATE_BOOTLOADER_TARGET $(eval BUILD := $(1)) $(eval PIN := $(2)) $(eval MCU := $$(call base_mcu,$$(1))) -$(eval EXTRA_CFLAGS := $(call flash_size_flag,$(1))) +$(eval EXTRA_CFLAGS := $(call get_cflags,$(1))) $(eval ELF_FILE := $(BIN_DIR)/$(call BOOTLOADER_BASENAME_VER,$(BUILD),$(PIN)).elf) $(eval HEX_FILE := $(ELF_FILE:.elf=.hex)) $(eval DEP_FILE := $(ELF_FILE:.elf=.d)) @@ -143,19 +152,21 @@ $(eval BLU_TARGET := $(call BOOTLOADER_UPDATE_BASENAME,$(BUILD),$(PIN))) # get MCU specific compiler, objcopy and link script or use the ARM SDK one $(eval xCC := $(if $($(MCU)_CC), $($(MCU)_CC), $(CC))) $(eval xOBJCOPY := $(if $($(MCU)_OBJCOPY), $($(MCU)_OBJCOPY), $(OBJCOPY))) -$(eval xLDSCRIPT := $(if $($(MCU)_LDSCRIPT), $($(MCU)_LDSCRIPT), $(LDSCRIPT_BL))) -$(eval xBLU_LDSCRIPT := $(if $($(MCU)_LDSCRIPT_BLU), $($(MCU)_LDSCRIPT_BLU), $(LDSCRIPT_BLU))) +$(eval xLDSCRIPT := $(if $($(MCU)_LDSCRIPT), $($(MCU)_LDSCRIPT), $$(if $$(call has_can_suffix,$$(BUILD)),$(LDSCRIPT_BL_CAN),$(LDSCRIPT_BL)))) +$(eval xBLU_LDSCRIPT := $(if $($(MCU)_LDSCRIPT_BLU), $($(MCU)_LDSCRIPT_BLU), $$(if $$(call has_can_suffix,$$(BUILD)),$(LDSCRIPT_BLU_CAN),$(LDSCRIPT_BLU)))) +$(eval CFLAGS_DRONECAN := $$(if $$(call has_can_suffix,$$(1)),$$(CFLAGS_DRONECAN_L431))) +$(eval SRC_DRONECAN := $(if $(call has_can_suffix,$(1)),$(SRC_DRONECAN_$(MCU)))) -include $(DEP_FILE) -include $(BLU_DEP_FILE) -$(ELF_FILE): CFLAGS_BL := $$(MCU_$(MCU)) $$(CFLAGS_$(MCU)) $$(CFLAGS_BASE) -DBOOTLOADER -DUSE_$(PIN) $(EXTRA_CFLAGS) +$(ELF_FILE): CFLAGS_BL := $$(MCU_$(MCU)) $$(CFLAGS_$(MCU)) $$(CFLAGS_BASE) -DBOOTLOADER -DUSE_$(PIN) $(EXTRA_CFLAGS) -DAM32_MCU=\"$(MCU)\" $$(CFLAGS_DRONECAN) $(ELF_FILE): LDFLAGS_BL := $$(LDFLAGS_COMMON) $$(LDFLAGS_$(MCU)) -T$(xLDSCRIPT) -$(ELF_FILE): $$(SRC_$(MCU)_BL) $$(SRC_BL) +$(ELF_FILE): $$(SRC_$(MCU)_BL) $$(SRC_BL) $$(SRC_DRONECAN) $$(QUIET)echo building bootloader for $(BUILD) with pin $(PIN) $$(QUIET)$$(MKDIR) -p $(OBJ) $$(QUIET)echo Compiling $(notdir $$@) - $$(QUIET)$(xCC) $$(CFLAGS_BL) $$(LDFLAGS_BL) -MMD -MP -MF $(DEP_FILE) -o $$(@) $$(SRC_$(MCU)_BL) $$(SRC_BL) + $$(QUIET)$(xCC) $$(CFLAGS_BL) $(CFLAGS_DRONECAN) $$(LDFLAGS_BL) -MMD -MP -MF $(DEP_FILE) -o $$(@) $$(SRC_$(MCU)_BL) $$(SRC_BL) $(SRC_DRONECAN) $$(QUIET)$$(CP) -f $$@ $$(OBJ)$$(DSEP)debug.elf $$(QUIET)$$(CP) -f $$(SVD_$(MCU)) $$(OBJ)/debug.svd $$(QUIET)$$(CP) -f Mcu$(DSEP)$(call lc,$(MCU))$(DSEP)openocd.cfg $$(OBJ)$$(DSEP)openocd.cfg > $$(NUL) @@ -163,7 +174,7 @@ $(ELF_FILE): $$(SRC_$(MCU)_BL) $$(SRC_BL) $(H_FILE): $(BIN_FILE) $$(QUIET)python3 bl_update/make_binheader.py $(BIN_FILE) $(H_FILE) -$(BLU_ELF_FILE): CFLAGS_BLU := $$(MCU_$(MCU)) $$(CFLAGS_$(MCU)) $$(CFLAGS_BASE) -DBOOTLOADER -DUSE_$(PIN) $(EXTRA_CFLAGS) -Wno-unused-variable -Wno-unused-function +$(BLU_ELF_FILE): CFLAGS_BLU := -DAM32_MCU=\"$(MCU)\" $$(MCU_$(MCU)) $$(CFLAGS_$(MCU)) $$(CFLAGS_BASE) -DBOOTLOADER -DUSE_$(PIN) $(EXTRA_CFLAGS) -Wno-unused-variable -Wno-unused-function $(BLU_ELF_FILE): LDFLAGS_BLU := $$(LDFLAGS_COMMON) $$(LDFLAGS_$(MCU)) -T$(xBLU_LDSCRIPT) $(BLU_ELF_FILE): $$(SRC_$(MCU)_BL) $$(SRC_BLU) $(H_FILE) $$(QUIET)echo building bootloader updater for $(BUILD) with pin $(PIN) @@ -180,12 +191,13 @@ $(HEX_FILE): $$(ELF_FILE) $(BIN_FILE): $$(HEX_FILE) # Generate bin and hex files for bl updater -$(BLU_HEX_FILE): $$(BLU_ELF_FILE) +$(BLU_BIN_FILE): $$(BLU_ELF_FILE) $$(QUIET)echo Generating $(notdir $$@) $$(QUIET)$(xOBJCOPY) -O binary $$(<) $$(@:.hex=.bin) + $$(QUIET)python3 bl_update/set_app_signature.py $$@ $$(<) $$(QUIET)$(xOBJCOPY) $$(<) -O ihex $$(@:.bin=.hex) -$(BLU_AMJ_FILE): $$(BLU_HEX_FILE) +$(BLU_AMJ_FILE): $$(BLU_BIN_FILE) $$(QUIET)echo Generating $(notdir $$@) $$(QUIET)python3 bl_update/make_amj.py --type bl_update --githash $(shell git rev-parse HEAD) $(BLU_HEX_FILE) $(BLU_AMJ_FILE) diff --git a/Mcu/e230/Inc/blutil.h b/Mcu/e230/Inc/blutil.h index 783469b7..70c35a38 100644 --- a/Mcu/e230/Inc/blutil.h +++ b/Mcu/e230/Inc/blutil.h @@ -25,27 +25,27 @@ static inline void gpio_mode_set_input(uint32_t pin, uint32_t pull_up_down) { - gpio_mode_set(input_port, GPIO_MODE_INPUT, pull_up_down, pin); + gpio_mode_set(input_port, GPIO_MODE_INPUT, pull_up_down, pin); } static inline void gpio_mode_set_output(uint32_t pin, uint32_t output_mode) { - gpio_mode_set(input_port, GPIO_MODE_OUTPUT, output_mode, pin); + gpio_mode_set(input_port, GPIO_MODE_OUTPUT, output_mode, pin); } static inline void gpio_set(uint32_t pin) { - gpio_bit_set(input_port, pin); + gpio_bit_set(input_port, pin); } static inline void gpio_clear(uint32_t pin) { - gpio_bit_reset(input_port, pin); + gpio_bit_reset(input_port, pin); } static inline bool gpio_read(uint32_t pin) { - return (gpio_input_port_get(input_port) & pin) != 0; + return (gpio_input_port_get(input_port) & pin) != 0; } #define BL_TIMER TIMER16 @@ -55,11 +55,11 @@ static inline bool gpio_read(uint32_t pin) */ static inline void bl_timer_init(void) { - rcu_periph_clock_enable(RCU_TIMER16); - TIMER_CAR(BL_TIMER) = 0xFFFF; - TIMER_PSC(BL_TIMER) = 71; - timer_auto_reload_shadow_enable(BL_TIMER); - timer_enable(BL_TIMER); + rcu_periph_clock_enable(RCU_TIMER16); + TIMER_CAR(BL_TIMER) = 0xFFFF; + TIMER_PSC(BL_TIMER) = 71; + timer_auto_reload_shadow_enable(BL_TIMER); + timer_enable(BL_TIMER); } /* @@ -67,17 +67,12 @@ static inline void bl_timer_init(void) */ static inline void bl_timer_disable(void) { - timer_disable(BL_TIMER); + timer_disable(BL_TIMER); } -static inline uint32_t bl_timer_us(void) +static inline uint16_t bl_timer_us(void) { - return timer_counter_read(BL_TIMER); -} - -static inline void bl_timer_reset(void) -{ - timer_counter_value_config(BL_TIMER, 0); + return timer_counter_read(BL_TIMER); } /* @@ -85,8 +80,8 @@ static inline void bl_timer_reset(void) */ static inline void bl_clock_config(void) { - rcu_periph_clock_enable(RCU_GPIOA); - rcu_periph_clock_enable(RCU_GPIOB); + rcu_periph_clock_enable(RCU_GPIOA); + rcu_periph_clock_enable(RCU_GPIOB); } static inline void bl_gpio_init(void) @@ -98,7 +93,7 @@ static inline void bl_gpio_init(void) */ static inline bool bl_was_software_reset(void) { - return (RCU_RSTSCK & RCU_RSTSCK_SWRSTF) != 0; + return (RCU_RSTSCK & RCU_RSTSCK_SWRSTF) != 0; } /* @@ -106,22 +101,22 @@ static inline bool bl_was_software_reset(void) */ static inline void jump_to_application(void) { - __disable_irq(); - bl_timer_disable(); - const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; - const uint32_t *app_data = (const uint32_t *)app_address; - const uint32_t stack_top = app_data[0]; - const uint32_t JumpAddress = app_data[1]; + __disable_irq(); + bl_timer_disable(); + const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; + const uint32_t *app_data = (const uint32_t *)app_address; + const uint32_t stack_top = app_data[0]; + const uint32_t JumpAddress = app_data[1]; - // setup vector table - SCB->VTOR = app_address; + // setup vector table + SCB->VTOR = app_address; - // setup sp, msp and jump - asm volatile( - "mov sp, %0 \n" - "msr msp, %0 \n" - "bx %1 \n" - : : "r"(stack_top), "r"(JumpAddress) :); + // setup sp, msp and jump + asm volatile( + "mov sp, %0 \n" + "msr msp, %0 \n" + "bx %1 \n" + : : "r"(stack_top), "r"(JumpAddress) :); } void SysTick_Handler(void) @@ -143,51 +138,51 @@ void SysTick_Handler(void) static void system_clock_72m_irc8m(void) { - uint32_t timeout = 0U; - uint32_t stab_flag = 0U; + uint32_t timeout = 0U; + uint32_t stab_flag = 0U; - /* enable IRC8M */ - RCU_CTL0 |= RCU_CTL0_IRC8MEN; + /* enable IRC8M */ + RCU_CTL0 |= RCU_CTL0_IRC8MEN; - /* wait until IRC8M is stable or the startup time is longer than - * IRC8M_STARTUP_TIMEOUT */ - do { - timeout++; - stab_flag = (RCU_CTL0 & RCU_CTL0_IRC8MSTB); - } while ((0U == stab_flag) && (IRC8M_STARTUP_TIMEOUT != timeout)); + /* wait until IRC8M is stable or the startup time is longer than + * IRC8M_STARTUP_TIMEOUT */ + do { + timeout++; + stab_flag = (RCU_CTL0 & RCU_CTL0_IRC8MSTB); + } while ((0U == stab_flag) && (IRC8M_STARTUP_TIMEOUT != timeout)); - /* if fail */ - if (0U == (RCU_CTL0 & RCU_CTL0_IRC8MSTB)) { - while (1) { - } + /* if fail */ + if (0U == (RCU_CTL0 & RCU_CTL0_IRC8MSTB)) { + while (1) { } + } - FMC_WS = (FMC_WS & (~FMC_WS_WSCNT)) | WS_WSCNT_2; + FMC_WS = (FMC_WS & (~FMC_WS_WSCNT)) | WS_WSCNT_2; - /* AHB = SYSCLK */ - RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; - /* APB2 = AHB */ - RCU_CFG0 |= RCU_APB2_CKAHB_DIV1; - /* APB1 = AHB */ - RCU_CFG0 |= RCU_APB1_CKAHB_DIV1; - /* PLL = (IRC8M/2) * 18 = 72 MHz */ - RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF); - RCU_CFG0 |= (RCU_PLLSRC_IRC8M_DIV2 | RCU_PLL_MUL18); + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV1; + /* APB1 = AHB */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV1; + /* PLL = (IRC8M/2) * 18 = 72 MHz */ + RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF); + RCU_CFG0 |= (RCU_PLLSRC_IRC8M_DIV2 | RCU_PLL_MUL18); - /* enable PLL */ - RCU_CTL0 |= RCU_CTL0_PLLEN; + /* enable PLL */ + RCU_CTL0 |= RCU_CTL0_PLLEN; - /* wait until PLL is stable */ - while (0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) { - } + /* wait until PLL is stable */ + while (0U == (RCU_CTL0 & RCU_CTL0_PLLSTB)) { + } - /* select PLL as system clock */ - RCU_CFG0 &= ~RCU_CFG0_SCS; - RCU_CFG0 |= RCU_CKSYSSRC_PLL; + /* select PLL as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_PLL; - /* wait until PLL is selected as system clock */ - while (0U == (RCU_CFG0 & RCU_SCSS_PLL)) { - } + /* wait until PLL is selected as system clock */ + while (0U == (RCU_CFG0 & RCU_SCSS_PLL)) { + } } /*! @@ -198,7 +193,7 @@ static void system_clock_72m_irc8m(void) */ static void system_clock_config(void) { - system_clock_72m_irc8m(); + system_clock_72m_irc8m(); } /*! @@ -209,24 +204,24 @@ static void system_clock_config(void) */ void SystemInit(void) { - /* enable IRC8M */ - RCU_CTL0 |= RCU_CTL0_IRC8MEN; - while (0U == (RCU_CTL0 & RCU_CTL0_IRC8MSTB)) { - } - - RCU_MODIFY(0x80); - RCU_CFG0 &= ~RCU_CFG0_SCS; - RCU_CTL0 &= ~(RCU_CTL0_HXTALEN | RCU_CTL0_CKMEN | RCU_CTL0_PLLEN | RCU_CTL0_HXTALBPS); - /* reset RCU */ - RCU_CFG0 &= ~(RCU_CFG0_SCS | RCU_CFG0_AHBPSC | RCU_CFG0_APB1PSC | RCU_CFG0_APB2PSC | RCU_CFG0_ADCPSC | RCU_CFG0_CKOUTSEL | RCU_CFG0_CKOUTDIV | RCU_CFG0_PLLDV); - RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLDV); - RCU_CFG1 &= ~(RCU_CFG1_PREDV); - RCU_CFG2 &= ~(RCU_CFG2_USART0SEL | RCU_CFG2_ADCSEL); - RCU_CFG2 &= ~RCU_CFG2_IRC28MDIV; - RCU_CFG2 &= ~RCU_CFG2_ADCPSC2; - RCU_CTL1 &= ~RCU_CTL1_IRC28MEN; - RCU_INT = 0x00000000U; - - /* configure system clock */ - system_clock_config(); + /* enable IRC8M */ + RCU_CTL0 |= RCU_CTL0_IRC8MEN; + while (0U == (RCU_CTL0 & RCU_CTL0_IRC8MSTB)) { + } + + RCU_MODIFY(0x80); + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CTL0 &= ~(RCU_CTL0_HXTALEN | RCU_CTL0_CKMEN | RCU_CTL0_PLLEN | RCU_CTL0_HXTALBPS); + /* reset RCU */ + RCU_CFG0 &= ~(RCU_CFG0_SCS | RCU_CFG0_AHBPSC | RCU_CFG0_APB1PSC | RCU_CFG0_APB2PSC | RCU_CFG0_ADCPSC | RCU_CFG0_CKOUTSEL | RCU_CFG0_CKOUTDIV | RCU_CFG0_PLLDV); + RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PLLMF | RCU_CFG0_PLLMF4 | RCU_CFG0_PLLDV); + RCU_CFG1 &= ~(RCU_CFG1_PREDV); + RCU_CFG2 &= ~(RCU_CFG2_USART0SEL | RCU_CFG2_ADCSEL); + RCU_CFG2 &= ~RCU_CFG2_IRC28MDIV; + RCU_CFG2 &= ~RCU_CFG2_ADCPSC2; + RCU_CTL1 &= ~RCU_CTL1_IRC28MEN; + RCU_INT = 0x00000000U; + + /* configure system clock */ + system_clock_config(); } diff --git a/Mcu/e230/Src/eeprom.c b/Mcu/e230/Src/eeprom.c index e6aeb4ba..1aad5e43 100644 --- a/Mcu/e230/Src/eeprom.c +++ b/Mcu/e230/Src/eeprom.c @@ -8,35 +8,35 @@ bool save_flash_nolib(const uint8_t* data, uint32_t length, uint32_t add) { - if ((add & 0x3) != 0 || (length & 0x3) != 0) { - return false; - } - const uint32_t data_length = length / 4; - - // unlock flash - - fmc_unlock(); - - // erase page if address even divisable by 1024 - if ((add % page_size) == 0) { - fmc_page_erase(add); - } - - volatile uint32_t index = 0; - while (index < data_length) { - uint32_t word; - memcpy(&word, (void*)(data+(index*4)), sizeof(word)); - fmc_word_program(add + (index * 4), word); - fmc_flag_clear(FMC_FLAG_END | FMC_FLAG_WPERR | FMC_FLAG_PGERR); - index++; - } - fmc_lock(); - - // ensure data is correct - return memcmp(data, (const void *)add, length) == 0; + if ((add & 0x3) != 0 || (length & 0x3) != 0) { + return false; + } + const uint32_t data_length = length / 4; + + // unlock flash + + fmc_unlock(); + + // erase page if address even divisable by 1024 + if ((add % page_size) == 0) { + fmc_page_erase(add); + } + + volatile uint32_t index = 0; + while (index < data_length) { + uint32_t word; + memcpy(&word, (void*)(data+(index*4)), sizeof(word)); + fmc_word_program(add + (index * 4), word); + fmc_flag_clear(FMC_FLAG_END | FMC_FLAG_WPERR | FMC_FLAG_PGERR); + index++; + } + fmc_lock(); + + // ensure data is correct + return memcmp(data, (const void *)add, length) == 0; } void read_flash_bin(uint8_t* data, uint32_t add, int out_buff_len) { - memcpy(data, (void*)add, out_buff_len); + memcpy(data, (void*)add, out_buff_len); } diff --git a/Mcu/f031/Inc/blutil.h b/Mcu/f031/Inc/blutil.h index ef4e6ad2..21bb8210 100644 --- a/Mcu/f031/Inc/blutil.h +++ b/Mcu/f031/Inc/blutil.h @@ -30,29 +30,29 @@ uint32_t SystemCoreClock = 8000000U; static inline void gpio_mode_set_input(uint32_t pin, uint32_t pull_up_down) { - LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_INPUT); - LL_GPIO_SetPinPull(input_port, pin, pull_up_down); + LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_INPUT); + LL_GPIO_SetPinPull(input_port, pin, pull_up_down); } static inline void gpio_mode_set_output(uint32_t pin, uint32_t output_mode) { - LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_OUTPUT); - LL_GPIO_SetPinOutputType(input_port, pin, output_mode); + LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_OUTPUT); + LL_GPIO_SetPinOutputType(input_port, pin, output_mode); } static inline void gpio_set(uint32_t pin) { - LL_GPIO_SetOutputPin(input_port, pin); + LL_GPIO_SetOutputPin(input_port, pin); } static inline void gpio_clear(uint32_t pin) { - LL_GPIO_ResetOutputPin(input_port, pin); + LL_GPIO_ResetOutputPin(input_port, pin); } static inline bool gpio_read(uint32_t pin) { - return LL_GPIO_IsInputPinSet(input_port, pin); + return LL_GPIO_IsInputPinSet(input_port, pin); } #define BL_TIMER TIM2 @@ -62,23 +62,23 @@ static inline bool gpio_read(uint32_t pin) */ static inline void bl_timer_init(void) { - LL_TIM_InitTypeDef TIM_InitStruct = {0}; - - /* Peripheral clock enable */ - LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2); - - TIM_InitStruct.Prescaler = 47; - TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP; - TIM_InitStruct.Autoreload = 0xFFFFFFFF; - TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; - LL_TIM_Init(BL_TIMER, &TIM_InitStruct); - LL_TIM_DisableARRPreload(BL_TIMER); - LL_TIM_SetClockSource(BL_TIMER, LL_TIM_CLOCKSOURCE_INTERNAL); - LL_TIM_SetTriggerOutput(BL_TIMER, LL_TIM_TRGO_RESET); - LL_TIM_DisableMasterSlaveMode(BL_TIMER); - - LL_TIM_SetCounterMode(BL_TIMER, LL_TIM_COUNTERMODE_UP); - LL_TIM_EnableCounter(BL_TIMER); + LL_TIM_InitTypeDef TIM_InitStruct = {0}; + + /* Peripheral clock enable */ + LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2); + + TIM_InitStruct.Prescaler = 47; + TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP; + TIM_InitStruct.Autoreload = 0xFFFFFFFF; + TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; + LL_TIM_Init(BL_TIMER, &TIM_InitStruct); + LL_TIM_DisableARRPreload(BL_TIMER); + LL_TIM_SetClockSource(BL_TIMER, LL_TIM_CLOCKSOURCE_INTERNAL); + LL_TIM_SetTriggerOutput(BL_TIMER, LL_TIM_TRGO_RESET); + LL_TIM_DisableMasterSlaveMode(BL_TIMER); + + LL_TIM_SetCounterMode(BL_TIMER, LL_TIM_COUNTERMODE_UP); + LL_TIM_EnableCounter(BL_TIMER); } /* @@ -86,17 +86,12 @@ static inline void bl_timer_init(void) */ static inline void bl_timer_disable(void) { - LL_TIM_DeInit(BL_TIMER); + LL_TIM_DeInit(BL_TIMER); } -static inline uint32_t bl_timer_us(void) +static inline uint16_t bl_timer_us(void) { - return LL_TIM_GetCounter(BL_TIMER); -} - -static inline void bl_timer_reset(void) -{ - LL_TIM_SetCounter(BL_TIMER, 0); + return LL_TIM_GetCounter(BL_TIMER); } /* @@ -104,50 +99,50 @@ static inline void bl_timer_reset(void) */ static inline void bl_clock_config(void) { - FLASH->ACR |= FLASH_ACR_PRFTBE; // prefetch buffer enable + FLASH->ACR |= FLASH_ACR_PRFTBE; // prefetch buffer enable - LL_FLASH_SetLatency(LL_FLASH_LATENCY_1); + LL_FLASH_SetLatency(LL_FLASH_LATENCY_1); - LL_RCC_HSI_Enable(); + LL_RCC_HSI_Enable(); - /* Wait till HSI is ready */ - while (LL_RCC_HSI_IsReady() != 1) ; - LL_RCC_HSI_SetCalibTrimming(16); - LL_RCC_HSI14_Enable(); + /* Wait till HSI is ready */ + while (LL_RCC_HSI_IsReady() != 1) ; + LL_RCC_HSI_SetCalibTrimming(16); + LL_RCC_HSI14_Enable(); - /* Wait till HSI14 is ready */ - while (LL_RCC_HSI14_IsReady() != 1) ; - LL_RCC_HSI14_SetCalibTrimming(16); - LL_RCC_LSI_Enable(); + /* Wait till HSI14 is ready */ + while (LL_RCC_HSI14_IsReady() != 1) ; + LL_RCC_HSI14_SetCalibTrimming(16); + LL_RCC_LSI_Enable(); - /* Wait till LSI is ready */ - while (LL_RCC_LSI_IsReady() != 1) ; - LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI_DIV_2, LL_RCC_PLL_MUL_12); - LL_RCC_PLL_Enable(); + /* Wait till LSI is ready */ + while (LL_RCC_LSI_IsReady() != 1) ; + LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI_DIV_2, LL_RCC_PLL_MUL_12); + LL_RCC_PLL_Enable(); - /* Wait till PLL is ready */ - while (LL_RCC_PLL_IsReady() != 1) ; - LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1); - LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1); - LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); + /* Wait till PLL is ready */ + while (LL_RCC_PLL_IsReady() != 1) ; + LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1); + LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1); + LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); - /* Wait till System clock is ready */ - while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) ; - LL_Init1msTick(48000000); - LL_SetSystemCoreClock(48000000); + /* Wait till System clock is ready */ + while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) ; + LL_Init1msTick(48000000); + LL_SetSystemCoreClock(48000000); } static inline void bl_gpio_init(void) { - LL_GPIO_InitTypeDef GPIO_InitStruct = {0}; - LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOB); - LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOA); - - /**/ - GPIO_InitStruct.Pin = input_pin; - GPIO_InitStruct.Mode = LL_GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = LL_GPIO_PULL_UP; - LL_GPIO_Init(input_port, &GPIO_InitStruct); + LL_GPIO_InitTypeDef GPIO_InitStruct = {0}; + LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOB); + LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOA); + + /**/ + GPIO_InitStruct.Pin = input_pin; + GPIO_InitStruct.Mode = LL_GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = LL_GPIO_PULL_UP; + LL_GPIO_Init(input_port, &GPIO_InitStruct); } /* @@ -155,7 +150,7 @@ static inline void bl_gpio_init(void) */ static inline bool bl_was_software_reset(void) { - return (RCC->CSR & RCC_CSR_SFTRSTF) != 0; + return (RCC->CSR & RCC_CSR_SFTRSTF) != 0; } /* @@ -170,17 +165,17 @@ void SystemInit() */ static inline void jump_to_application(void) { - __disable_irq(); - bl_timer_disable(); - const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; - const uint32_t *app_data = (const uint32_t *)app_address; - const uint32_t stack_top = app_data[0]; - const uint32_t JumpAddress = app_data[1]; - - // setup sp, msp and jump - asm volatile( - "mov sp, %0 \n" - "msr msp, %0 \n" - "bx %1 \n" - : : "r"(stack_top), "r"(JumpAddress) :); + __disable_irq(); + bl_timer_disable(); + const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; + const uint32_t *app_data = (const uint32_t *)app_address; + const uint32_t stack_top = app_data[0]; + const uint32_t JumpAddress = app_data[1]; + + // setup sp, msp and jump + asm volatile( + "mov sp, %0 \n" + "msr msp, %0 \n" + "bx %1 \n" + : : "r"(stack_top), "r"(JumpAddress) :); } diff --git a/Mcu/f031/Src/eeprom.c b/Mcu/f031/Src/eeprom.c index 8c4859c5..7789da27 100644 --- a/Mcu/f031/Src/eeprom.c +++ b/Mcu/f031/Src/eeprom.c @@ -17,52 +17,52 @@ static const uint32_t FLASH_FKEY2 = 0xCDEF89AB; bool save_flash_nolib(const uint8_t* data, uint32_t length, uint32_t add) { - if ((add & 0x1) != 0 || (length & 0x1) != 0) { - return false; - } - const uint32_t data_length = length / 2; + if ((add & 0x1) != 0 || (length & 0x1) != 0) { + return false; + } + const uint32_t data_length = length / 2; - // unlock flash - while ((FLASH->SR & FLASH_SR_BSY) != 0) { - /* add time-out*/ - } - if ((FLASH->CR & FLASH_CR_LOCK) != 0) { - FLASH->KEYR = FLASH_FKEY1; - FLASH->KEYR = FLASH_FKEY2; - } + // unlock flash + while ((FLASH->SR & FLASH_SR_BSY) != 0) { + /* add time-out*/ + } + if ((FLASH->CR & FLASH_CR_LOCK) != 0) { + FLASH->KEYR = FLASH_FKEY1; + FLASH->KEYR = FLASH_FKEY2; + } - // erase page if address even divisable by 1024 - if ((add % page_size) == 0) { - FLASH->CR = FLASH_CR_PER; - FLASH->AR = add; - FLASH->CR |= FLASH_CR_STRT; - while ((FLASH->SR & FLASH_SR_BSY) != 0) { - /* add time-out */ - } - FLASH->SR = FLASH_SR_EOP; - FLASH->CR &= ~FLASH_CR_PER; + // erase page if address even divisable by 1024 + if ((add % page_size) == 0) { + FLASH->CR = FLASH_CR_PER; + FLASH->AR = add; + FLASH->CR |= FLASH_CR_STRT; + while ((FLASH->SR & FLASH_SR_BSY) != 0) { + /* add time-out */ } + FLASH->SR = FLASH_SR_EOP; + FLASH->CR &= ~FLASH_CR_PER; + } - volatile uint32_t write_cnt = 0, index = 0; - while (index < data_length) { - uint16_t word16; - memcpy(&word16, &data[index*2], sizeof(word16)); - FLASH->CR = FLASH_CR_PG; /* (1) */ - *(__IO uint16_t*)(add + write_cnt) = word16; - while ((FLASH->SR & FLASH_SR_BSY) != 0) { /* add time-out */ - } - FLASH->SR = FLASH_SR_EOP; - FLASH->CR = 0; - write_cnt += 2; - index++; + volatile uint32_t write_cnt = 0, index = 0; + while (index < data_length) { + uint16_t word16; + memcpy(&word16, &data[index*2], sizeof(word16)); + FLASH->CR = FLASH_CR_PG; /* (1) */ + *(__IO uint16_t*)(add + write_cnt) = word16; + while ((FLASH->SR & FLASH_SR_BSY) != 0) { /* add time-out */ } - SET_BIT(FLASH->CR, FLASH_CR_LOCK); + FLASH->SR = FLASH_SR_EOP; + FLASH->CR = 0; + write_cnt += 2; + index++; + } + SET_BIT(FLASH->CR, FLASH_CR_LOCK); - // ensure data is correct - return memcmp(data, (const void *)add, length) == 0; + // ensure data is correct + return memcmp(data, (const void *)add, length) == 0; } void read_flash_bin(uint8_t* data, uint32_t add, int out_buff_len) { - memcpy(data, (const uint8_t *)add, out_buff_len); + memcpy(data, (const uint8_t *)add, out_buff_len); } diff --git a/Mcu/f051/Inc/blutil.h b/Mcu/f051/Inc/blutil.h index 18f24deb..854d5afa 100644 --- a/Mcu/f051/Inc/blutil.h +++ b/Mcu/f051/Inc/blutil.h @@ -29,29 +29,29 @@ uint32_t SystemCoreClock = 8000000U; static inline void gpio_mode_set_input(uint32_t pin, uint32_t pull_up_down) { - LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_INPUT); - LL_GPIO_SetPinPull(input_port, pin, pull_up_down); + LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_INPUT); + LL_GPIO_SetPinPull(input_port, pin, pull_up_down); } static inline void gpio_mode_set_output(uint32_t pin, uint32_t output_mode) { - LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_OUTPUT); - LL_GPIO_SetPinOutputType(input_port, pin, output_mode); + LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_OUTPUT); + LL_GPIO_SetPinOutputType(input_port, pin, output_mode); } static inline void gpio_set(uint32_t pin) { - LL_GPIO_SetOutputPin(input_port, pin); + LL_GPIO_SetOutputPin(input_port, pin); } static inline void gpio_clear(uint32_t pin) { - LL_GPIO_ResetOutputPin(input_port, pin); + LL_GPIO_ResetOutputPin(input_port, pin); } static inline bool gpio_read(uint32_t pin) { - return LL_GPIO_IsInputPinSet(input_port, pin); + return LL_GPIO_IsInputPinSet(input_port, pin); } #define BL_TIMER TIM2 @@ -61,23 +61,23 @@ static inline bool gpio_read(uint32_t pin) */ static inline void bl_timer_init(void) { - LL_TIM_InitTypeDef TIM_InitStruct = {0}; - - /* Peripheral clock enable */ - LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2); - - TIM_InitStruct.Prescaler = 47; - TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP; - TIM_InitStruct.Autoreload = 0xFFFFFFFF; - TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; - LL_TIM_Init(BL_TIMER, &TIM_InitStruct); - LL_TIM_DisableARRPreload(BL_TIMER); - LL_TIM_SetClockSource(BL_TIMER, LL_TIM_CLOCKSOURCE_INTERNAL); - LL_TIM_SetTriggerOutput(BL_TIMER, LL_TIM_TRGO_RESET); - LL_TIM_DisableMasterSlaveMode(BL_TIMER); - - LL_TIM_SetCounterMode(BL_TIMER, LL_TIM_COUNTERMODE_UP); - LL_TIM_EnableCounter(BL_TIMER); + LL_TIM_InitTypeDef TIM_InitStruct = {0}; + + /* Peripheral clock enable */ + LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2); + + TIM_InitStruct.Prescaler = 47; + TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP; + TIM_InitStruct.Autoreload = 0xFFFFFFFF; + TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; + LL_TIM_Init(BL_TIMER, &TIM_InitStruct); + LL_TIM_DisableARRPreload(BL_TIMER); + LL_TIM_SetClockSource(BL_TIMER, LL_TIM_CLOCKSOURCE_INTERNAL); + LL_TIM_SetTriggerOutput(BL_TIMER, LL_TIM_TRGO_RESET); + LL_TIM_DisableMasterSlaveMode(BL_TIMER); + + LL_TIM_SetCounterMode(BL_TIMER, LL_TIM_COUNTERMODE_UP); + LL_TIM_EnableCounter(BL_TIMER); } /* @@ -85,17 +85,12 @@ static inline void bl_timer_init(void) */ static inline void bl_timer_disable(void) { - LL_TIM_DeInit(BL_TIMER); + LL_TIM_DeInit(BL_TIMER); } -static inline uint32_t bl_timer_us(void) +static inline uint16_t bl_timer_us(void) { - return LL_TIM_GetCounter(BL_TIMER); -} - -static inline void bl_timer_reset(void) -{ - LL_TIM_SetCounter(BL_TIMER, 0); + return LL_TIM_GetCounter(BL_TIMER); } /* @@ -103,50 +98,50 @@ static inline void bl_timer_reset(void) */ static inline void bl_clock_config(void) { - FLASH->ACR |= FLASH_ACR_PRFTBE; // prefetch buffer enable + FLASH->ACR |= FLASH_ACR_PRFTBE; // prefetch buffer enable - LL_FLASH_SetLatency(LL_FLASH_LATENCY_1); + LL_FLASH_SetLatency(LL_FLASH_LATENCY_1); - LL_RCC_HSI_Enable(); + LL_RCC_HSI_Enable(); - /* Wait till HSI is ready */ - while (LL_RCC_HSI_IsReady() != 1) ; - LL_RCC_HSI_SetCalibTrimming(16); - LL_RCC_HSI14_Enable(); + /* Wait till HSI is ready */ + while (LL_RCC_HSI_IsReady() != 1) ; + LL_RCC_HSI_SetCalibTrimming(16); + LL_RCC_HSI14_Enable(); - /* Wait till HSI14 is ready */ - while (LL_RCC_HSI14_IsReady() != 1) ; - LL_RCC_HSI14_SetCalibTrimming(16); - LL_RCC_LSI_Enable(); + /* Wait till HSI14 is ready */ + while (LL_RCC_HSI14_IsReady() != 1) ; + LL_RCC_HSI14_SetCalibTrimming(16); + LL_RCC_LSI_Enable(); - /* Wait till LSI is ready */ - while (LL_RCC_LSI_IsReady() != 1) ; - LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI_DIV_2, LL_RCC_PLL_MUL_12); - LL_RCC_PLL_Enable(); + /* Wait till LSI is ready */ + while (LL_RCC_LSI_IsReady() != 1) ; + LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI_DIV_2, LL_RCC_PLL_MUL_12); + LL_RCC_PLL_Enable(); - /* Wait till PLL is ready */ - while (LL_RCC_PLL_IsReady() != 1) ; - LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1); - LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1); - LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); + /* Wait till PLL is ready */ + while (LL_RCC_PLL_IsReady() != 1) ; + LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1); + LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1); + LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); - /* Wait till System clock is ready */ - while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) ; - LL_Init1msTick(48000000); - LL_SetSystemCoreClock(48000000); + /* Wait till System clock is ready */ + while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) ; + LL_Init1msTick(48000000); + LL_SetSystemCoreClock(48000000); } static inline void bl_gpio_init(void) { - LL_GPIO_InitTypeDef GPIO_InitStruct = {0}; - LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOB); - LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOA); - - /**/ - GPIO_InitStruct.Pin = input_pin; - GPIO_InitStruct.Mode = LL_GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = LL_GPIO_PULL_UP; - LL_GPIO_Init(input_port, &GPIO_InitStruct); + LL_GPIO_InitTypeDef GPIO_InitStruct = {0}; + LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOB); + LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOA); + + /**/ + GPIO_InitStruct.Pin = input_pin; + GPIO_InitStruct.Mode = LL_GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = LL_GPIO_PULL_UP; + LL_GPIO_Init(input_port, &GPIO_InitStruct); } /* @@ -154,7 +149,7 @@ static inline void bl_gpio_init(void) */ static inline bool bl_was_software_reset(void) { - return (RCC->CSR & RCC_CSR_SFTRSTF) != 0; + return (RCC->CSR & RCC_CSR_SFTRSTF) != 0; } /* @@ -169,17 +164,17 @@ void SystemInit() */ static inline void jump_to_application(void) { - __disable_irq(); - bl_timer_disable(); - const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; - const uint32_t *app_data = (const uint32_t *)app_address; - const uint32_t stack_top = app_data[0]; - const uint32_t JumpAddress = app_data[1]; - - // setup sp, msp and jump - asm volatile( - "mov sp, %0 \n" - "msr msp, %0 \n" - "bx %1 \n" - : : "r"(stack_top), "r"(JumpAddress) :); + __disable_irq(); + bl_timer_disable(); + const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; + const uint32_t *app_data = (const uint32_t *)app_address; + const uint32_t stack_top = app_data[0]; + const uint32_t JumpAddress = app_data[1]; + + // setup sp, msp and jump + asm volatile( + "mov sp, %0 \n" + "msr msp, %0 \n" + "bx %1 \n" + : : "r"(stack_top), "r"(JumpAddress) :); } diff --git a/Mcu/f051/Src/eeprom.c b/Mcu/f051/Src/eeprom.c index 5448b572..b9107e58 100644 --- a/Mcu/f051/Src/eeprom.c +++ b/Mcu/f051/Src/eeprom.c @@ -17,52 +17,52 @@ static const uint32_t FLASH_FKEY2 = 0xCDEF89AB; bool save_flash_nolib(const uint8_t* data, uint32_t length, uint32_t add) { - if ((add & 0x1) != 0 || (length & 0x1) != 0) { - return false; - } - const uint32_t data_length = length / 2; + if ((add & 0x1) != 0 || (length & 0x1) != 0) { + return false; + } + const uint32_t data_length = length / 2; - // unlock flash - while ((FLASH->SR & FLASH_SR_BSY) != 0) { - /* add time-out*/ - } - if ((FLASH->CR & FLASH_CR_LOCK) != 0) { - FLASH->KEYR = FLASH_FKEY1; - FLASH->KEYR = FLASH_FKEY2; - } + // unlock flash + while ((FLASH->SR & FLASH_SR_BSY) != 0) { + /* add time-out*/ + } + if ((FLASH->CR & FLASH_CR_LOCK) != 0) { + FLASH->KEYR = FLASH_FKEY1; + FLASH->KEYR = FLASH_FKEY2; + } - // erase page if address even divisable by 1024 - if ((add % page_size) == 0) { - FLASH->CR = FLASH_CR_PER; - FLASH->AR = add; - FLASH->CR |= FLASH_CR_STRT; - while ((FLASH->SR & FLASH_SR_BSY) != 0) { - /* add time-out */ - } - FLASH->SR = FLASH_SR_EOP; - FLASH->CR = 0; + // erase page if address even divisable by 1024 + if ((add % page_size) == 0) { + FLASH->CR = FLASH_CR_PER; + FLASH->AR = add; + FLASH->CR |= FLASH_CR_STRT; + while ((FLASH->SR & FLASH_SR_BSY) != 0) { + /* add time-out */ } + FLASH->SR = FLASH_SR_EOP; + FLASH->CR = 0; + } - volatile uint32_t write_cnt = 0, index = 0; - while (index < data_length) { - uint16_t word16; - memcpy(&word16, &data[index*2], sizeof(word16)); - FLASH->CR = FLASH_CR_PG; /* (1) */ - *(__IO uint16_t*)(add + write_cnt) = word16; - while ((FLASH->SR & FLASH_SR_BSY) != 0) { /* add time-out */ - } - FLASH->SR = FLASH_SR_EOP; - FLASH->CR = 0; - write_cnt += 2; - index++; + volatile uint32_t write_cnt = 0, index = 0; + while (index < data_length) { + uint16_t word16; + memcpy(&word16, &data[index*2], sizeof(word16)); + FLASH->CR = FLASH_CR_PG; /* (1) */ + *(__IO uint16_t*)(add + write_cnt) = word16; + while ((FLASH->SR & FLASH_SR_BSY) != 0) { /* add time-out */ } - SET_BIT(FLASH->CR, FLASH_CR_LOCK); + FLASH->SR = FLASH_SR_EOP; + FLASH->CR = 0; + write_cnt += 2; + index++; + } + SET_BIT(FLASH->CR, FLASH_CR_LOCK); - // ensure data is correct - return memcmp(data, (const void *)add, length) == 0; + // ensure data is correct + return memcmp(data, (const void *)add, length) == 0; } void read_flash_bin(uint8_t* data, uint32_t add, int out_buff_len) { - memcpy(data, (const uint8_t *)add, out_buff_len); + memcpy(data, (const uint8_t *)add, out_buff_len); } diff --git a/Mcu/f415/Drivers/drivers/inc/at32f415_gpio.h b/Mcu/f415/Drivers/drivers/inc/at32f415_gpio.h index 7eb92aea..b341c6ab 100644 --- a/Mcu/f415/Drivers/drivers/inc/at32f415_gpio.h +++ b/Mcu/f415/Drivers/drivers/inc/at32f415_gpio.h @@ -168,6 +168,7 @@ extern "C" { * @{ */ +#define CAN1_GMUX_0000 IOMUX_MAKE_VALUE(0x2C, 0, 4, 0x00) /*!< can_rx(pa11), can_tx(pa12) */ #define CAN1_GMUX_0010 IOMUX_MAKE_VALUE(0x2C, 0, 4, 0x02) /*!< can_rx(pb8), can_tx(pb9) */ #define SDIO1_GMUX_0100 IOMUX_MAKE_VALUE(0x2C, 8, 4, 0x04) /*!< sdio1_ck(pc4), sdio1_cmd(pc5), sdio1_d0(pc0), sdio1_d1(pc1), sdio1_d2(pc2), sdio1_d3(pc3), sdio1_d4(pa4), sdio1_d5(pa5), sdio1_d6(pa6), sdio1_d7(pa7) */ #define SDIO1_GMUX_0101 IOMUX_MAKE_VALUE(0x2C, 8, 4, 0x05) /*!< sdio1_ck(pc4), sdio1_cmd(pc5), sdio1_d0(pa4), sdio1_d1(pa5), sdio1_d2(pa6), sdio1_d3(pa7) */ diff --git a/Mcu/f415/Inc/blutil.h b/Mcu/f415/Inc/blutil.h index 634354e9..764261ee 100644 --- a/Mcu/f415/Inc/blutil.h +++ b/Mcu/f415/Inc/blutil.h @@ -20,45 +20,47 @@ #define GPIO_PIN(n) (1U<<(n)) +#ifdef PORT_LETTER static inline void gpio_mode_set_input(uint32_t pin, uint32_t pull_up_down) { - if (pin < GPIO_PIN(8)) { - const uint32_t pin4 = (pin*pin*pin*pin); - input_port->cfglr = (input_port->cfglr & ~(pin4*0xfU)) | (pin4*pull_up_down); - } else { - pin >>= 8U; - const uint32_t pin4 = (pin*pin*pin*pin); - input_port->cfghr = (input_port->cfglr & ~(pin4*0xfU)) | (pin4*pull_up_down); - } + if (pin < GPIO_PIN(8)) { + const uint32_t pin4 = (pin*pin*pin*pin); + input_port->cfglr = (input_port->cfglr & ~(pin4*0xfU)) | (pin4*pull_up_down); + } else { + pin >>= 8U; + const uint32_t pin4 = (pin*pin*pin*pin); + input_port->cfghr = (input_port->cfglr & ~(pin4*0xfU)) | (pin4*pull_up_down); + } } static inline void gpio_mode_set_output(uint32_t pin, uint32_t output_mode) { - const uint32_t output_normal_strength = 2U; - if (pin < GPIO_PIN(8)) { - const uint32_t pin4 = (pin*pin*pin*pin); - input_port->cfglr = (input_port->cfglr & ~(pin4*0xfU)) | (pin4*(output_normal_strength | output_mode)); - } else { - pin >>= 8U; - const uint32_t pin4 = (pin*pin*pin*pin); - input_port->cfghr = (input_port->cfghr & ~(pin4*0xfU)) | (pin4*(output_normal_strength | output_mode)); - } + const uint32_t output_normal_strength = 2U; + if (pin < GPIO_PIN(8)) { + const uint32_t pin4 = (pin*pin*pin*pin); + input_port->cfglr = (input_port->cfglr & ~(pin4*0xfU)) | (pin4*(output_normal_strength | output_mode)); + } else { + pin >>= 8U; + const uint32_t pin4 = (pin*pin*pin*pin); + input_port->cfghr = (input_port->cfghr & ~(pin4*0xfU)) | (pin4*(output_normal_strength | output_mode)); + } } static inline void gpio_set(uint32_t pin) { - input_port->scr = pin; + input_port->scr = pin; } static inline void gpio_clear(uint32_t pin) { - input_port->clr = pin; + input_port->clr = pin; } static inline bool gpio_read(uint32_t pin) { - return (input_port->idt & pin) != 0; + return (input_port->idt & pin) != 0; } +#endif // PORT_LETTER #define BL_TIMER TMR3 @@ -67,15 +69,16 @@ static inline bool gpio_read(uint32_t pin) */ static inline void bl_timer_init(void) { - crm_periph_clock_enable(CRM_TMR3_PERIPH_CLOCK, TRUE); + crm_periph_clock_enable(CRM_TMR3_PERIPH_CLOCK, TRUE); - BL_TIMER->div = 143; - BL_TIMER->pr = 0xFFFF; - BL_TIMER->swevt_bit.ovfswtr = TRUE; - - BL_TIMER->ctrl1_bit.tmren = TRUE; + BL_TIMER->div = 143; + BL_TIMER->pr = 0xFFFF; + BL_TIMER->swevt_bit.ovfswtr = TRUE; + + BL_TIMER->ctrl1_bit.tmren = TRUE; } +#ifdef PORT_LETTER unsigned int system_core_clock = HICK_VALUE; /*!< system clock frequency (core clock) */ /* @@ -83,115 +86,112 @@ unsigned int system_core_clock = HICK_VALUE; /*!< system clock frequen */ void system_core_clock_update(void) { - uint32_t temp = 0, div_value = 0; - - static const uint8_t sys_ahb_div_table[16] = { 0, 0, 0, 0, 0, 0, 0, 0, - 1, 2, 3, 4, 6, 7, 8, 9 }; - - if (((CRM->misc2_bit.hick_to_sclk) != RESET) && ((CRM->misc1_bit.hickdiv) != RESET)) - system_core_clock = HICK_VALUE * 6; - else - system_core_clock = HICK_VALUE; - - /* compute sclk, ahbclk frequency */ - /* get ahb division */ - temp = CRM->cfg_bit.ahbdiv; - div_value = sys_ahb_div_table[temp]; - /* ahbclk frequency */ - system_core_clock = system_core_clock >> div_value; + uint32_t temp = 0, div_value = 0; + + static const uint8_t sys_ahb_div_table[16] = { 0, 0, 0, 0, 0, 0, 0, 0, + 1, 2, 3, 4, 6, 7, 8, 9 + }; + + if (((CRM->misc2_bit.hick_to_sclk) != RESET) && ((CRM->misc1_bit.hickdiv) != RESET)) { + system_core_clock = HICK_VALUE * 6; + } else { + system_core_clock = HICK_VALUE; + } + + /* compute sclk, ahbclk frequency */ + /* get ahb division */ + temp = CRM->cfg_bit.ahbdiv; + div_value = sys_ahb_div_table[temp]; + /* ahbclk frequency */ + system_core_clock = system_core_clock >> div_value; } +#endif // PORT_LETTER /* initialise clocks */ static inline void bl_clock_config(void) { - /* config flash psr register */ - flash_psr_set(FLASH_WAIT_CYCLE_4); + /* config flash psr register */ + flash_psr_set(FLASH_WAIT_CYCLE_4); - /* reset crm */ - crm_reset(); + /* reset crm */ + crm_reset(); - crm_clock_source_enable(CRM_CLOCK_SOURCE_HICK, TRUE); + crm_clock_source_enable(CRM_CLOCK_SOURCE_HICK, TRUE); - /* wait till hick is ready */ - while(crm_flag_get(CRM_HICK_STABLE_FLAG) != SET) - { - } + /* wait till hick is ready */ + while (crm_flag_get(CRM_HICK_STABLE_FLAG) != SET) { + } - /* config pll clock resource */ - crm_pll_config(CRM_PLL_SOURCE_HICK, CRM_PLL_MULT_36); + /* config pll clock resource */ + crm_pll_config(CRM_PLL_SOURCE_HICK, CRM_PLL_MULT_36); - /* enable pll */ - crm_clock_source_enable(CRM_CLOCK_SOURCE_PLL, TRUE); + /* enable pll */ + crm_clock_source_enable(CRM_CLOCK_SOURCE_PLL, TRUE); - /* wait till pll is ready */ - while(crm_flag_get(CRM_PLL_STABLE_FLAG) != SET) - { - } + /* wait till pll is ready */ + while (crm_flag_get(CRM_PLL_STABLE_FLAG) != SET) { + } - /* config ahbclk */ - crm_ahb_div_set(CRM_AHB_DIV_1); + /* config ahbclk */ + crm_ahb_div_set(CRM_AHB_DIV_1); - /* config apb2clk */ - crm_apb2_div_set(CRM_APB2_DIV_2); + /* config apb2clk */ + crm_apb2_div_set(CRM_APB2_DIV_2); - /* config apb1clk */ - crm_apb1_div_set(CRM_APB1_DIV_2); + /* config apb1clk */ + crm_apb1_div_set(CRM_APB1_DIV_2); - /* enable auto step mode */ - crm_auto_step_mode_enable(TRUE); + /* enable auto step mode */ + crm_auto_step_mode_enable(TRUE); - /* select pll as system clock source */ - crm_sysclk_switch(CRM_SCLK_PLL); + /* select pll as system clock source */ + crm_sysclk_switch(CRM_SCLK_PLL); - /* wait till pll is used as system clock source */ - while(crm_sysclk_switch_status_get() != CRM_SCLK_PLL) - { - } + /* wait till pll is used as system clock source */ + while (crm_sysclk_switch_status_get() != CRM_SCLK_PLL) { + } - /* disable auto step mode */ - crm_auto_step_mode_enable(FALSE); + /* disable auto step mode */ + crm_auto_step_mode_enable(FALSE); - /* update system_core_clock global variable */ - system_core_clock_update(); + /* update system_core_clock global variable */ + system_core_clock_update(); } +#ifdef PORT_LETTER static inline void bl_gpio_init(void) { - crm_periph_clock_enable(CRM_GPIOA_PERIPH_CLOCK, TRUE); - crm_periph_clock_enable(CRM_GPIOB_PERIPH_CLOCK, TRUE); - crm_periph_clock_enable(CRM_IOMUX_PERIPH_CLOCK , TRUE); - gpio_pin_remap_config(SWJTAG_GMUX_010, TRUE); // pb4 GPIO - - gpio_init_type gpio_init_struct; - gpio_default_para_init(&gpio_init_struct); - - gpio_init_struct.gpio_pins = input_pin; - gpio_init_struct.gpio_mode = GPIO_MODE_INPUT; - gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL; - gpio_init_struct.gpio_pull = GPIO_PULL_NONE; - gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER; - - gpio_init(input_port, &gpio_init_struct); + crm_periph_clock_enable(CRM_GPIOA_PERIPH_CLOCK, TRUE); + crm_periph_clock_enable(CRM_GPIOB_PERIPH_CLOCK, TRUE); + crm_periph_clock_enable(CRM_IOMUX_PERIPH_CLOCK, TRUE); + gpio_pin_remap_config(SWJTAG_GMUX_010, TRUE); // pb4 GPIO + + gpio_init_type gpio_init_struct; + gpio_default_para_init(&gpio_init_struct); + + gpio_init_struct.gpio_pins = input_pin; + gpio_init_struct.gpio_mode = GPIO_MODE_INPUT; + gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL; + gpio_init_struct.gpio_pull = GPIO_PULL_NONE; + gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER; + + gpio_init(input_port, &gpio_init_struct); } +#endif // PORT_LETTER /* disable timer ready for app start */ static inline void bl_timer_disable(void) { - BL_TIMER->ctrl1_bit.tmren = FALSE; -} - -static inline uint32_t bl_timer_us(void) -{ - return BL_TIMER->cval; + BL_TIMER->ctrl1_bit.tmren = FALSE; } -static inline void bl_timer_reset(void) +static inline uint16_t bl_timer_us(void) { - BL_TIMER->cval = 0; + return BL_TIMER->cval; } /* @@ -199,9 +199,10 @@ static inline void bl_timer_reset(void) */ static inline bool bl_was_software_reset(void) { - return crm_flag_get(CRM_SW_RESET_FLAG) == SET; + return crm_flag_get(CRM_SW_RESET_FLAG) == SET; } +#ifdef PORT_LETTER /* no need for any action in SystemInit */ @@ -214,17 +215,18 @@ void SystemInit() */ static inline void jump_to_application(void) { - __disable_irq(); - bl_timer_disable(); - const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; - const uint32_t *app_data = (const uint32_t *)app_address; - const uint32_t stack_top = app_data[0]; - const uint32_t JumpAddress = app_data[1]; - - // setup sp, msp and jump - asm volatile( - "mov sp, %0 \n" - "msr msp, %0 \n" - "bx %1 \n" - : : "r"(stack_top), "r"(JumpAddress) :); + __disable_irq(); + bl_timer_disable(); + const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; + const uint32_t *app_data = (const uint32_t *)app_address; + const uint32_t stack_top = app_data[0]; + const uint32_t JumpAddress = app_data[1]; + + // setup sp, msp and jump + asm volatile( + "mov sp, %0 \n" + "msr msp, %0 \n" + "bx %1 \n" + : : "r"(stack_top), "r"(JumpAddress) :); } +#endif // PORT_LETTER diff --git a/Mcu/f415/Inc/functions.h b/Mcu/f415/Inc/functions.h index 77d984c8..042e9241 100644 --- a/Mcu/f415/Inc/functions.h +++ b/Mcu/f415/Inc/functions.h @@ -12,7 +12,7 @@ #include "main.h" void gpio_mode_QUICK(gpio_type* gpio_periph, uint32_t mode, - uint32_t pull_up_down, uint32_t pin); + uint32_t pull_up_down, uint32_t pin); void gpio_mode_set(uint32_t mode, uint32_t pull_up_down, uint32_t pin); int getAbsDif(int number1, int number2); void delayMicros(uint32_t micros); diff --git a/Mcu/f415/Inc/system_at32f415.h b/Mcu/f415/Inc/system_at32f415.h index 4c439802..dbd2cf78 100644 --- a/Mcu/f415/Inc/system_at32f415.h +++ b/Mcu/f415/Inc/system_at32f415.h @@ -56,7 +56,7 @@ extern "C" { */ extern unsigned int - system_core_clock; /*!< system clock frequency (core clock) */ +system_core_clock; /*!< system clock frequency (core clock) */ /** * @} diff --git a/Mcu/f415/Src/eeprom.c b/Mcu/f415/Src/eeprom.c index e6b0dfcf..2407a356 100644 --- a/Mcu/f415/Src/eeprom.c +++ b/Mcu/f415/Src/eeprom.c @@ -12,49 +12,49 @@ */ static inline uint32_t sector_size() { - const uint16_t *F_SIZE = (const uint16_t *)0x1FFFF7E0; - if (*F_SIZE <= 128) { - // 1k sectors for 128k flash or less - return 1024; - } - // 256k flash is 2k sectors - return 2048; + const uint16_t *F_SIZE = (const uint16_t *)0x1FFFF7E0; + if (*F_SIZE <= 128) { + // 1k sectors for 128k flash or less + return 1024; + } + // 256k flash is 2k sectors + return 2048; } bool save_flash_nolib(const uint8_t* data, uint32_t length, uint32_t add) { - if ((add & 0x3) != 0 || (length & 0x3) != 0) { - return false; - } - /* - we need the data to be 32 bit aligned - */ - const uint32_t word_length = length / 4; - - // unlock flash - flash_unlock(); - - // erase page if address even divisable by sector size - if ((add % sector_size()) == 0) { - flash_sector_erase(add); - } - - uint32_t index = 0; - while (index < word_length) { - uint32_t word; - memcpy(&word, &data[index*4], sizeof(word)); - flash_word_program(add + (index * 4), word); - flash_flag_clear(FLASH_PROGRAM_ERROR | FLASH_EPP_ERROR | FLASH_OPERATE_DONE); - index++; - } - flash_lock(); - - // ensure data is correct - return memcmp(data, (const void *)add, length) == 0; + if ((add & 0x3) != 0 || (length & 0x3) != 0) { + return false; + } + /* + we need the data to be 32 bit aligned + */ + const uint32_t word_length = length / 4; + + // unlock flash + flash_unlock(); + + // erase page if address even divisable by sector size + if ((add % sector_size()) == 0) { + flash_sector_erase(add); + } + + uint32_t index = 0; + while (index < word_length) { + uint32_t word; + memcpy(&word, &data[index*4], sizeof(word)); + flash_word_program(add + (index * 4), word); + flash_flag_clear(FLASH_PROGRAM_ERROR | FLASH_EPP_ERROR | FLASH_OPERATE_DONE); + index++; + } + flash_lock(); + + // ensure data is correct + return memcmp(data, (const void *)add, length) == 0; } void read_flash_bin(uint8_t* data, uint32_t add, int out_buff_len) { - memcpy(data, (void*)add, out_buff_len); + memcpy(data, (void*)add, out_buff_len); } diff --git a/Mcu/f421/Inc/blutil.h b/Mcu/f421/Inc/blutil.h index 6b8813e6..e492469f 100644 --- a/Mcu/f421/Inc/blutil.h +++ b/Mcu/f421/Inc/blutil.h @@ -18,31 +18,31 @@ static inline void gpio_mode_set_input(uint32_t pin, uint32_t pull_up_down) { - const uint32_t pinsq = (pin*pin); - input_port->cfgr = (input_port->cfgr & ~(pinsq * 0x3U)) | (pinsq * GPIO_MODE_INPUT); - input_port->pull = (input_port->pull & ~(pinsq * 0x3U)) | (pinsq * pull_up_down); + const uint32_t pinsq = (pin*pin); + input_port->cfgr = (input_port->cfgr & ~(pinsq * 0x3U)) | (pinsq * GPIO_MODE_INPUT); + input_port->pull = (input_port->pull & ~(pinsq * 0x3U)) | (pinsq * pull_up_down); } static inline void gpio_mode_set_output(uint32_t pin, uint32_t output_mode) { - const uint32_t pinsq = (pin*pin); - input_port->cfgr = (input_port->cfgr & ~(pinsq * 0x3U)) | (pinsq * GPIO_MODE_OUTPUT); - input_port->omode = (input_port->omode & ~pin) | (output_mode << pin); + const uint32_t pinsq = (pin*pin); + input_port->cfgr = (input_port->cfgr & ~(pinsq * 0x3U)) | (pinsq * GPIO_MODE_OUTPUT); + input_port->omode = (input_port->omode & ~pin) | (output_mode << pin); } static inline void gpio_set(uint32_t pin) { - input_port->scr = pin; + input_port->scr = pin; } static inline void gpio_clear(uint32_t pin) { - input_port->clr = pin; + input_port->clr = pin; } static inline bool gpio_read(uint32_t pin) { - return (input_port->idt & pin) != 0; + return (input_port->idt & pin) != 0; } #define BL_TIMER TMR3 @@ -52,14 +52,14 @@ static inline bool gpio_read(uint32_t pin) */ static inline void bl_timer_init(void) { - crm_periph_clock_enable(CRM_TMR3_PERIPH_CLOCK, TRUE); - - BL_TIMER->div = 119; - BL_TIMER->pr = 0xFFFF; - BL_TIMER->ctrl1_bit.tmren = TRUE; - BL_TIMER->ctrl1_bit.clkdiv = TMR_CLOCK_DIV1; - BL_TIMER->ctrl1_bit.cnt_dir = TMR_COUNT_UP; - BL_TIMER->swevt_bit.ovfswtr = TRUE; + crm_periph_clock_enable(CRM_TMR3_PERIPH_CLOCK, TRUE); + + BL_TIMER->div = 119; + BL_TIMER->pr = 0xFFFF; + BL_TIMER->ctrl1_bit.tmren = TRUE; + BL_TIMER->ctrl1_bit.clkdiv = TMR_CLOCK_DIV1; + BL_TIMER->ctrl1_bit.cnt_dir = TMR_COUNT_UP; + BL_TIMER->swevt_bit.ovfswtr = TRUE; } /* @@ -67,17 +67,12 @@ static inline void bl_timer_init(void) */ static inline void bl_timer_disable(void) { - BL_TIMER->ctrl1_bit.tmren = FALSE; + BL_TIMER->ctrl1_bit.tmren = FALSE; } -static inline uint32_t bl_timer_us(void) +static inline uint16_t bl_timer_us(void) { - return BL_TIMER->cval; -} - -static inline void bl_timer_reset(void) -{ - BL_TIMER->cval = 0; + return BL_TIMER->cval; } /* @@ -85,43 +80,40 @@ static inline void bl_timer_reset(void) */ static inline void bl_clock_config(void) { - flash_psr_set(FLASH_WAIT_CYCLE_3); - crm_reset(); - crm_clock_source_enable(CRM_CLOCK_SOURCE_HICK, TRUE); - while(crm_flag_get(CRM_HICK_STABLE_FLAG) != SET) - { - } - crm_pll_config(CRM_PLL_SOURCE_HICK, CRM_PLL_MULT_30); - crm_clock_source_enable(CRM_CLOCK_SOURCE_PLL, TRUE); - while(crm_flag_get(CRM_PLL_STABLE_FLAG) != SET) - { - } - crm_ahb_div_set(CRM_AHB_DIV_1); - crm_apb2_div_set(CRM_APB2_DIV_1); - crm_apb1_div_set(CRM_APB1_DIV_1); - crm_auto_step_mode_enable(TRUE); - crm_sysclk_switch(CRM_SCLK_PLL); - while(crm_sysclk_switch_status_get() != CRM_SCLK_PLL) - { - } - crm_auto_step_mode_enable(FALSE); + flash_psr_set(FLASH_WAIT_CYCLE_3); + crm_reset(); + crm_clock_source_enable(CRM_CLOCK_SOURCE_HICK, TRUE); + while (crm_flag_get(CRM_HICK_STABLE_FLAG) != SET) { + } + crm_pll_config(CRM_PLL_SOURCE_HICK, CRM_PLL_MULT_30); + crm_clock_source_enable(CRM_CLOCK_SOURCE_PLL, TRUE); + while (crm_flag_get(CRM_PLL_STABLE_FLAG) != SET) { + } + crm_ahb_div_set(CRM_AHB_DIV_1); + crm_apb2_div_set(CRM_APB2_DIV_1); + crm_apb1_div_set(CRM_APB1_DIV_1); + crm_auto_step_mode_enable(TRUE); + crm_sysclk_switch(CRM_SCLK_PLL); + while (crm_sysclk_switch_status_get() != CRM_SCLK_PLL) { + } + crm_auto_step_mode_enable(FALSE); } static inline void bl_gpio_init(void) { - crm_periph_clock_enable(CRM_GPIOB_PERIPH_CLOCK, TRUE); - crm_periph_clock_enable(CRM_GPIOA_PERIPH_CLOCK, TRUE); - - gpio_init_type gpio_init_struct; - gpio_default_para_init(&gpio_init_struct); - - gpio_init_struct.gpio_pins = input_pin; - gpio_init_struct.gpio_mode = GPIO_MODE_INPUT; - gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL; - gpio_init_struct.gpio_pull = GPIO_PULL_NONE; - gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER; - - gpio_init(input_port, &gpio_init_struct); + crm_periph_clock_enable(CRM_GPIOB_PERIPH_CLOCK, TRUE); + crm_periph_clock_enable(CRM_GPIOA_PERIPH_CLOCK, TRUE); + + gpio_init_type gpio_init_struct; + gpio_default_para_init(&gpio_init_struct); + + gpio_init_struct.gpio_pins = input_pin; + gpio_init_struct.gpio_mode = GPIO_MODE_INPUT; + gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL; + gpio_init_struct.gpio_pull = GPIO_PULL_NONE; + gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER; + + gpio_init(input_port, &gpio_init_struct); } /* @@ -129,7 +121,7 @@ static inline void bl_gpio_init(void) */ static inline bool bl_was_software_reset(void) { - return crm_flag_get(CRM_SW_RESET_FLAG) == SET; + return crm_flag_get(CRM_SW_RESET_FLAG) == SET; } /* @@ -144,17 +136,17 @@ void SystemInit() */ static inline void jump_to_application(void) { - __disable_irq(); - bl_timer_disable(); - const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; - const uint32_t *app_data = (const uint32_t *)app_address; - const uint32_t stack_top = app_data[0]; - const uint32_t JumpAddress = app_data[1]; - - // setup sp, msp and jump - asm volatile( - "mov sp, %0 \n" - "msr msp, %0 \n" - "bx %1 \n" - : : "r"(stack_top), "r"(JumpAddress) :); + __disable_irq(); + bl_timer_disable(); + const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; + const uint32_t *app_data = (const uint32_t *)app_address; + const uint32_t stack_top = app_data[0]; + const uint32_t JumpAddress = app_data[1]; + + // setup sp, msp and jump + asm volatile( + "mov sp, %0 \n" + "msr msp, %0 \n" + "bx %1 \n" + : : "r"(stack_top), "r"(JumpAddress) :); } diff --git a/Mcu/f421/Inc/system_at32f421.h b/Mcu/f421/Inc/system_at32f421.h index 38c3be61..cbb23719 100644 --- a/Mcu/f421/Inc/system_at32f421.h +++ b/Mcu/f421/Inc/system_at32f421.h @@ -56,7 +56,7 @@ extern "C" { */ extern unsigned int - system_core_clock; /*!< system clock frequency (core clock) */ +system_core_clock; /*!< system clock frequency (core clock) */ /** * @} diff --git a/Mcu/f421/Src/eeprom.c b/Mcu/f421/Src/eeprom.c index b468dd17..262c9898 100644 --- a/Mcu/f421/Src/eeprom.c +++ b/Mcu/f421/Src/eeprom.c @@ -8,34 +8,34 @@ bool save_flash_nolib(const uint8_t* data, uint32_t length, uint32_t add) { - if ((add & 0x3) != 0 || (length & 0x3) != 0) { - return false; - } - const uint32_t data_length = length / 4; - - // unlock flash - flash_unlock(); - - // erase page if address even divisable by 1024 - if ((add % page_size) == 0) { - flash_sector_erase(add); - } - - uint32_t index = 0; - while (index < data_length) { - uint32_t word; - memcpy(&word, &data[index*4], sizeof(word)); - flash_word_program(add + (index * 4), word); - flash_flag_clear(FLASH_PROGRAM_ERROR | FLASH_EPP_ERROR | FLASH_OPERATE_DONE); - index++; - } - flash_lock(); - - // ensure data is correct - return memcmp(data, (const void *)add, length) == 0; + if ((add & 0x3) != 0 || (length & 0x3) != 0) { + return false; + } + const uint32_t data_length = length / 4; + + // unlock flash + flash_unlock(); + + // erase page if address even divisable by 1024 + if ((add % page_size) == 0) { + flash_sector_erase(add); + } + + uint32_t index = 0; + while (index < data_length) { + uint32_t word; + memcpy(&word, &data[index*4], sizeof(word)); + flash_word_program(add + (index * 4), word); + flash_flag_clear(FLASH_PROGRAM_ERROR | FLASH_EPP_ERROR | FLASH_OPERATE_DONE); + index++; + } + flash_lock(); + + // ensure data is correct + return memcmp(data, (const void *)add, length) == 0; } void read_flash_bin(uint8_t* data, uint32_t add, int out_buff_len) { - memcpy(data, (void*)add, out_buff_len); + memcpy(data, (void*)add, out_buff_len); } diff --git a/Mcu/g071/Inc/blutil.h b/Mcu/g071/Inc/blutil.h index 05ce0435..0f273e8f 100644 --- a/Mcu/g071/Inc/blutil.h +++ b/Mcu/g071/Inc/blutil.h @@ -33,29 +33,29 @@ uint32_t SystemCoreClock = 8000000U; static inline void gpio_mode_set_input(uint32_t pin, uint32_t pull_up_down) { - LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_INPUT); - LL_GPIO_SetPinPull(input_port, pin, pull_up_down); + LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_INPUT); + LL_GPIO_SetPinPull(input_port, pin, pull_up_down); } static inline void gpio_mode_set_output(uint32_t pin, uint32_t output_mode) { - LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_OUTPUT); - LL_GPIO_SetPinOutputType(input_port, pin, output_mode); + LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_OUTPUT); + LL_GPIO_SetPinOutputType(input_port, pin, output_mode); } static inline void gpio_set(uint32_t pin) { - LL_GPIO_SetOutputPin(input_port, pin); + LL_GPIO_SetOutputPin(input_port, pin); } static inline void gpio_clear(uint32_t pin) { - LL_GPIO_ResetOutputPin(input_port, pin); + LL_GPIO_ResetOutputPin(input_port, pin); } static inline bool gpio_read(uint32_t pin) { - return LL_GPIO_IsInputPinSet(input_port, pin); + return LL_GPIO_IsInputPinSet(input_port, pin); } #define BL_TIMER TIM2 @@ -65,23 +65,23 @@ static inline bool gpio_read(uint32_t pin) */ static inline void bl_timer_init(void) { - LL_TIM_InitTypeDef TIM_InitStruct = {0}; - - /* Peripheral clock enable */ - LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2); - - TIM_InitStruct.Prescaler = 63; - TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP; - TIM_InitStruct.Autoreload = 0xFFFFFFFF; - TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; - LL_TIM_Init(BL_TIMER, &TIM_InitStruct); - LL_TIM_DisableARRPreload(BL_TIMER); - LL_TIM_SetClockSource(BL_TIMER, LL_TIM_CLOCKSOURCE_INTERNAL); - LL_TIM_SetTriggerOutput(BL_TIMER, LL_TIM_TRGO_RESET); - LL_TIM_DisableMasterSlaveMode(BL_TIMER); - - LL_TIM_SetCounterMode(BL_TIMER, LL_TIM_COUNTERMODE_UP); - LL_TIM_EnableCounter(BL_TIMER); + LL_TIM_InitTypeDef TIM_InitStruct = {0}; + + /* Peripheral clock enable */ + LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2); + + TIM_InitStruct.Prescaler = 63; + TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP; + TIM_InitStruct.Autoreload = 0xFFFFFFFF; + TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; + LL_TIM_Init(BL_TIMER, &TIM_InitStruct); + LL_TIM_DisableARRPreload(BL_TIMER); + LL_TIM_SetClockSource(BL_TIMER, LL_TIM_CLOCKSOURCE_INTERNAL); + LL_TIM_SetTriggerOutput(BL_TIMER, LL_TIM_TRGO_RESET); + LL_TIM_DisableMasterSlaveMode(BL_TIMER); + + LL_TIM_SetCounterMode(BL_TIMER, LL_TIM_COUNTERMODE_UP); + LL_TIM_EnableCounter(BL_TIMER); } /* @@ -89,17 +89,12 @@ static inline void bl_timer_init(void) */ static inline void bl_timer_disable(void) { - LL_TIM_DeInit(BL_TIMER); + LL_TIM_DeInit(BL_TIMER); } -static inline uint32_t bl_timer_us(void) +static inline uint16_t bl_timer_us(void) { - return LL_TIM_GetCounter(BL_TIMER); -} - -static inline void bl_timer_reset(void) -{ - LL_TIM_SetCounter(BL_TIMER, 0); + return LL_TIM_GetCounter(BL_TIMER); } /* @@ -107,52 +102,49 @@ static inline void bl_timer_reset(void) */ static inline void bl_clock_config(void) { - LL_FLASH_SetLatency(LL_FLASH_LATENCY_2); - - /* HSI configuration and activation */ - LL_RCC_HSI_Enable(); - while(LL_RCC_HSI_IsReady() != 1) - { - } - - /* Main PLL configuration and activation */ - LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI, LL_RCC_PLLM_DIV_1, 8, LL_RCC_PLLR_DIV_2); - LL_RCC_PLL_Enable(); - LL_RCC_PLL_EnableDomain_SYS(); - while(LL_RCC_PLL_IsReady() != 1) - { - } - - /* Set AHB prescaler*/ - LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1); - - /* Sysclk activation on the main PLL */ - LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); - while(LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) - { - } - - /* Set APB1 prescaler*/ - LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1); - LL_Init1msTick(64000000); - LL_SetSystemCoreClock(64000000); - /* Update CMSIS variable (which can be updated also through SystemCoreClockUpdate function) */ - LL_SetSystemCoreClock(64000000); + LL_FLASH_SetLatency(LL_FLASH_LATENCY_2); + + /* HSI configuration and activation */ + LL_RCC_HSI_Enable(); + while (LL_RCC_HSI_IsReady() != 1) { + } + + /* Main PLL configuration and activation */ + LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI, LL_RCC_PLLM_DIV_1, 8, LL_RCC_PLLR_DIV_2); + LL_RCC_PLL_Enable(); + LL_RCC_PLL_EnableDomain_SYS(); + while (LL_RCC_PLL_IsReady() != 1) { + } + + /* Set AHB prescaler*/ + LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1); + + /* Sysclk activation on the main PLL */ + LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); + while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) { + } + + /* Set APB1 prescaler*/ + LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1); + LL_Init1msTick(64000000); + LL_SetSystemCoreClock(64000000); + /* Update CMSIS variable (which can be updated also through SystemCoreClockUpdate function) */ + LL_SetSystemCoreClock(64000000); } static inline void bl_gpio_init(void) { - LL_GPIO_InitTypeDef GPIO_InitStruct = {0}; + LL_GPIO_InitTypeDef GPIO_InitStruct = {0}; - /* GPIO Ports Clock Enable */ - LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA); - LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOB); + /* GPIO Ports Clock Enable */ + LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA); + LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOB); - /**/ - GPIO_InitStruct.Pin = input_pin; - GPIO_InitStruct.Mode = LL_GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = LL_GPIO_PULL_NO; - LL_GPIO_Init(input_port, &GPIO_InitStruct); + /**/ + GPIO_InitStruct.Pin = input_pin; + GPIO_InitStruct.Mode = LL_GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = LL_GPIO_PULL_NO; + LL_GPIO_Init(input_port, &GPIO_InitStruct); } /* @@ -160,7 +152,7 @@ static inline void bl_gpio_init(void) */ static inline bool bl_was_software_reset(void) { - return (RCC->CSR & RCC_CSR_SFTRSTF) != 0; + return (RCC->CSR & RCC_CSR_SFTRSTF) != 0; } /* @@ -175,20 +167,20 @@ void SystemInit() */ static inline void jump_to_application(void) { - __disable_irq(); - bl_timer_disable(); - const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; - const uint32_t *app_data = (const uint32_t *)app_address; - const uint32_t stack_top = app_data[0]; - const uint32_t JumpAddress = app_data[1]; - - // setup vector table - SCB->VTOR = app_address; - - // setup sp, msp and jump - asm volatile( - "mov sp, %0 \n" - "msr msp, %0 \n" - "bx %1 \n" - : : "r"(stack_top), "r"(JumpAddress) :); + __disable_irq(); + bl_timer_disable(); + const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; + const uint32_t *app_data = (const uint32_t *)app_address; + const uint32_t stack_top = app_data[0]; + const uint32_t JumpAddress = app_data[1]; + + // setup vector table + SCB->VTOR = app_address; + + // setup sp, msp and jump + asm volatile( + "mov sp, %0 \n" + "msr msp, %0 \n" + "bx %1 \n" + : : "r"(stack_top), "r"(JumpAddress) :); } diff --git a/Mcu/g071/Src/eeprom.c b/Mcu/g071/Src/eeprom.c index a8bbc749..b322d9cd 100644 --- a/Mcu/g071/Src/eeprom.c +++ b/Mcu/g071/Src/eeprom.c @@ -17,63 +17,63 @@ static const uint32_t FLASH_FKEY2 = 0xCDEF89AB; bool save_flash_nolib(const uint8_t* data, uint32_t length, uint32_t add) { - if ((add & 0x7) != 0 || (length & 0x7)) { - // address and length must be on 8 byte boundary - return false; - } - // we need to flash on 32 bit boundaries - const uint32_t data_length = length / 4; - volatile FLASH_TypeDef *flash = FLASH; - - // clear errors - flash->SR |= FLASH_SR_OPERR | FLASH_SR_PROGERR | FLASH_SR_WRPERR | FLASH_SR_PGAERR | - FLASH_SR_SIZERR | FLASH_SR_PGSERR | FLASH_SR_MISERR | FLASH_SR_FASTERR | - FLASH_SR_RDERR | FLASH_SR_OPTVERR; - - // unlock flash + if ((add & 0x7) != 0 || (length & 0x7)) { + // address and length must be on 8 byte boundary + return false; + } + // we need to flash on 32 bit boundaries + const uint32_t data_length = length / 4; + volatile FLASH_TypeDef *flash = FLASH; + + // clear errors + flash->SR |= FLASH_SR_OPERR | FLASH_SR_PROGERR | FLASH_SR_WRPERR | FLASH_SR_PGAERR | + FLASH_SR_SIZERR | FLASH_SR_PGSERR | FLASH_SR_MISERR | FLASH_SR_FASTERR | + FLASH_SR_RDERR | FLASH_SR_OPTVERR; + + // unlock flash + while ((flash->SR & FLASH_SR_BSY1) != 0) ; + + if ((flash->CR & FLASH_CR_LOCK) != 0) { + flash->KEYR = FLASH_FKEY1; + flash->KEYR = FLASH_FKEY2; + } + + // erase page if address is divisable by page size + if ((add % page_size) == 0) { + flash->CR = FLASH_CR_PER; + flash->CR |= (add/page_size) << 3; + flash->CR |= FLASH_CR_STRT; while ((flash->SR & FLASH_SR_BSY1) != 0) ; + } - if ((flash->CR & FLASH_CR_LOCK) != 0) { - flash->KEYR = FLASH_FKEY1; - flash->KEYR = FLASH_FKEY2; - } + uint32_t index = 0; + volatile uint32_t *fdata = (volatile uint32_t *)add; - // erase page if address is divisable by page size - if ((add % page_size) == 0){ - flash->CR = FLASH_CR_PER; - flash->CR |= (add/page_size) << 3; - flash->CR |= FLASH_CR_STRT; - while ((flash->SR & FLASH_SR_BSY1) != 0) ; - } + while (index < data_length) { + // flash two words at a time + uint32_t words[2]; + memcpy((void*)&words[0], &data[index*4], sizeof(words)); - uint32_t index = 0; - volatile uint32_t *fdata = (volatile uint32_t *)add; + flash->CR = FLASH_CR_PG; - while (index < data_length) { - // flash two words at a time - uint32_t words[2]; - memcpy((void*)&words[0], &data[index*4], sizeof(words)); + fdata[index] = words[0]; + fdata[index+1] = words[1]; - flash->CR = FLASH_CR_PG; - - fdata[index] = words[0]; - fdata[index+1] = words[1]; - - while ((flash->SR & FLASH_SR_BSY1) != 0) ; + while ((flash->SR & FLASH_SR_BSY1) != 0) ; - flash->SR |= FLASH_SR_EOP; - flash->CR = 0; - index += 2; - } + flash->SR |= FLASH_SR_EOP; + flash->CR = 0; + index += 2; + } - // lock flash again - SET_BIT(flash->CR, FLASH_CR_LOCK); + // lock flash again + SET_BIT(flash->CR, FLASH_CR_LOCK); - // ensure data is correct - return memcmp(data, (const void *)add, length) == 0; + // ensure data is correct + return memcmp(data, (const void *)add, length) == 0; } void read_flash_bin(uint8_t* data, uint32_t add, int out_buff_len) { - memcpy(data, (void*)add, out_buff_len); + memcpy(data, (void*)add, out_buff_len); } diff --git a/Mcu/g431/Inc/blutil.h b/Mcu/g431/Inc/blutil.h index debcd482..47cbf7cd 100644 --- a/Mcu/g431/Inc/blutil.h +++ b/Mcu/g431/Inc/blutil.h @@ -29,29 +29,29 @@ static inline void gpio_mode_set_input(uint32_t pin, uint32_t pull_up_down) { - LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_INPUT); - LL_GPIO_SetPinPull(input_port, pin, pull_up_down); + LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_INPUT); + LL_GPIO_SetPinPull(input_port, pin, pull_up_down); } static inline void gpio_mode_set_output(uint32_t pin, uint32_t output_mode) { - LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_OUTPUT); - LL_GPIO_SetPinOutputType(input_port, pin, output_mode); + LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_OUTPUT); + LL_GPIO_SetPinOutputType(input_port, pin, output_mode); } static inline void gpio_set(uint32_t pin) { - LL_GPIO_SetOutputPin(input_port, pin); + LL_GPIO_SetOutputPin(input_port, pin); } static inline void gpio_clear(uint32_t pin) { - LL_GPIO_ResetOutputPin(input_port, pin); + LL_GPIO_ResetOutputPin(input_port, pin); } static inline bool gpio_read(uint32_t pin) { - return LL_GPIO_IsInputPinSet(input_port, pin); + return LL_GPIO_IsInputPinSet(input_port, pin); } #define BL_TIMER TIM2 @@ -61,23 +61,23 @@ static inline bool gpio_read(uint32_t pin) */ static inline void bl_timer_init(void) { - LL_TIM_InitTypeDef TIM_InitStruct = {0}; - - /* Peripheral clock enable */ - LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2); - - TIM_InitStruct.Prescaler = (160-1); // HSI PLL clock is 160Mz, want 1MHz timer - TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP; - TIM_InitStruct.Autoreload = 0xFFFFFFFF; - TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; - LL_TIM_Init(BL_TIMER, &TIM_InitStruct); - LL_TIM_DisableARRPreload(BL_TIMER); - LL_TIM_SetClockSource(BL_TIMER, LL_TIM_CLOCKSOURCE_INTERNAL); - LL_TIM_SetTriggerOutput(BL_TIMER, LL_TIM_TRGO_RESET); - LL_TIM_DisableMasterSlaveMode(BL_TIMER); - - LL_TIM_SetCounterMode(BL_TIMER, LL_TIM_COUNTERMODE_UP); - LL_TIM_EnableCounter(BL_TIMER); + LL_TIM_InitTypeDef TIM_InitStruct = {0}; + + /* Peripheral clock enable */ + LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2); + + TIM_InitStruct.Prescaler = (160-1); // HSI PLL clock is 160Mz, want 1MHz timer + TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP; + TIM_InitStruct.Autoreload = 0xFFFFFFFF; + TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; + LL_TIM_Init(BL_TIMER, &TIM_InitStruct); + LL_TIM_DisableARRPreload(BL_TIMER); + LL_TIM_SetClockSource(BL_TIMER, LL_TIM_CLOCKSOURCE_INTERNAL); + LL_TIM_SetTriggerOutput(BL_TIMER, LL_TIM_TRGO_RESET); + LL_TIM_DisableMasterSlaveMode(BL_TIMER); + + LL_TIM_SetCounterMode(BL_TIMER, LL_TIM_COUNTERMODE_UP); + LL_TIM_EnableCounter(BL_TIMER); } /* @@ -85,17 +85,12 @@ static inline void bl_timer_init(void) */ static inline void bl_timer_disable(void) { - LL_TIM_DeInit(BL_TIMER); + LL_TIM_DeInit(BL_TIMER); } -static inline uint32_t bl_timer_us(void) +static inline uint16_t bl_timer_us(void) { - return LL_TIM_GetCounter(BL_TIMER); -} - -static inline void bl_timer_reset(void) -{ - LL_TIM_SetCounter(BL_TIMER, 0); + return LL_TIM_GetCounter(BL_TIMER); } /* @@ -103,44 +98,44 @@ static inline void bl_timer_reset(void) */ static inline void bl_clock_config(void) { - LL_FLASH_SetLatency(LL_FLASH_LATENCY_4); - while (LL_FLASH_GetLatency()!= LL_FLASH_LATENCY_4) ; - LL_PWR_SetRegulVoltageScaling(LL_PWR_REGU_VOLTAGE_SCALE1); - while (LL_PWR_IsActiveFlag_VOS() != 0) ; + LL_FLASH_SetLatency(LL_FLASH_LATENCY_4); + while (LL_FLASH_GetLatency()!= LL_FLASH_LATENCY_4) ; + LL_PWR_SetRegulVoltageScaling(LL_PWR_REGU_VOLTAGE_SCALE1); + while (LL_PWR_IsActiveFlag_VOS() != 0) ; - LL_RCC_HSI_Enable(); + LL_RCC_HSI_Enable(); - /* Wait till HSI is ready */ - while (LL_RCC_HSI_IsReady() != 1) ; + /* Wait till HSI is ready */ + while (LL_RCC_HSI_IsReady() != 1) ; - LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI, LL_RCC_PLLM_DIV_2, 40, LL_RCC_PLLR_DIV_2); - LL_RCC_PLL_EnableDomain_SYS(); - LL_RCC_PLL_Enable(); + LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI, LL_RCC_PLLM_DIV_2, 40, LL_RCC_PLLR_DIV_2); + LL_RCC_PLL_EnableDomain_SYS(); + LL_RCC_PLL_Enable(); - /* Wait till PLL is ready */ - while (LL_RCC_PLL_IsReady() != 1) ; - LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); + /* Wait till PLL is ready */ + while (LL_RCC_PLL_IsReady() != 1) ; + LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); - /* Wait till System clock is ready */ - while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) ; + /* Wait till System clock is ready */ + while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) ; - LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1); - LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1); - LL_RCC_SetAPB2Prescaler(LL_RCC_APB2_DIV_1); + LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1); + LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1); + LL_RCC_SetAPB2Prescaler(LL_RCC_APB2_DIV_1); } static inline void bl_gpio_init(void) { - LL_GPIO_InitTypeDef GPIO_InitStruct = {0}; + LL_GPIO_InitTypeDef GPIO_InitStruct = {0}; - LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOA); - LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOB); + LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOA); + LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOB); - GPIO_InitStruct.Pin = input_pin; - GPIO_InitStruct.Mode = LL_GPIO_MODE_OUTPUT; - GPIO_InitStruct.Pull = LL_GPIO_PULL_NO; + GPIO_InitStruct.Pin = input_pin; + GPIO_InitStruct.Mode = LL_GPIO_MODE_OUTPUT; + GPIO_InitStruct.Pull = LL_GPIO_PULL_NO; - LL_GPIO_Init(input_port, &GPIO_InitStruct); + LL_GPIO_Init(input_port, &GPIO_InitStruct); } /* @@ -148,12 +143,12 @@ static inline void bl_gpio_init(void) */ static inline bool bl_was_software_reset(void) { - return (RCC->CSR & RCC_CSR_SFTRSTF) != 0; + return (RCC->CSR & RCC_CSR_SFTRSTF) != 0; } void Error_Handler() { - while (1) {} + while (1) {} } /* @@ -161,22 +156,22 @@ void Error_Handler() */ static inline void jump_to_application(void) { - __disable_irq(); - bl_timer_disable(); - const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; - const uint32_t *app_data = (const uint32_t *)app_address; - const uint32_t stack_top = app_data[0]; - const uint32_t JumpAddress = app_data[1]; - - // setup vector table - SCB->VTOR = app_address; - - // setup sp, msp and jump - asm volatile( - "mov sp, %0 \n" - "msr msp, %0 \n" - "bx %1 \n" - : : "r"(stack_top), "r"(JumpAddress) :); + __disable_irq(); + bl_timer_disable(); + const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; + const uint32_t *app_data = (const uint32_t *)app_address; + const uint32_t stack_top = app_data[0]; + const uint32_t JumpAddress = app_data[1]; + + // setup vector table + SCB->VTOR = app_address; + + // setup sp, msp and jump + asm volatile( + "mov sp, %0 \n" + "msr msp, %0 \n" + "bx %1 \n" + : : "r"(stack_top), "r"(JumpAddress) :); } /* diff --git a/Mcu/g431/Src/eeprom.c b/Mcu/g431/Src/eeprom.c index 7be94da0..a79ec2c5 100644 --- a/Mcu/g431/Src/eeprom.c +++ b/Mcu/g431/Src/eeprom.c @@ -18,67 +18,68 @@ static const uint32_t FLASH_FKEY2 =0xCDEF89AB; bool save_flash_nolib(const uint8_t *data, uint32_t length, uint32_t add) { - if ((add & 0x7) != 0 || (length & 0x7)) { - // address and length must be on 8 byte boundary - return false; - } - // we need to flash on 32 bit boundaries - uint32_t data_length = length / 4; - volatile FLASH_TypeDef *flash = FLASH; - - // clear errors - flash->SR |= FLASH_SR_OPERR | FLASH_SR_PROGERR | FLASH_SR_WRPERR | FLASH_SR_PGAERR | - FLASH_SR_SIZERR | FLASH_SR_PGSERR | FLASH_SR_MISERR | FLASH_SR_FASTERR | - FLASH_SR_RDERR | FLASH_SR_OPTVERR; - - // unlock flash + if ((add & 0x7) != 0 || (length & 0x7)) { + // address and length must be on 8 byte boundary + return false; + } + // we need to flash on 32 bit boundaries + uint32_t data_length = length / 4; + volatile FLASH_TypeDef *flash = FLASH; + + // clear errors + flash->SR |= FLASH_SR_OPERR | FLASH_SR_PROGERR | FLASH_SR_WRPERR | FLASH_SR_PGAERR | + FLASH_SR_SIZERR | FLASH_SR_PGSERR | FLASH_SR_MISERR | FLASH_SR_FASTERR | + FLASH_SR_RDERR | FLASH_SR_OPTVERR; + + // unlock flash + while ((flash->SR & FLASH_SR_BSY) != 0) ; + + if ((flash->CR & FLASH_CR_LOCK) != 0) { + flash->KEYR = FLASH_FKEY1; + flash->KEYR = FLASH_FKEY2; + } + + // erase page if address is divisable by page size + if ((add % page_size) == 0) { + flash->CR = FLASH_CR_PER; + flash->CR |= (add/page_size) << 3; + flash->CR |= FLASH_CR_STRT; while ((flash->SR & FLASH_SR_BSY) != 0) ; + } - if ((flash->CR & FLASH_CR_LOCK) != 0) { - flash->KEYR = FLASH_FKEY1; - flash->KEYR = FLASH_FKEY2; - } + uint32_t index = 0; + volatile uint32_t *fdata = (volatile uint32_t *)add; - // erase page if address is divisable by page size - if ((add % page_size) == 0){ - flash->CR = FLASH_CR_PER; - flash->CR |= (add/page_size) << 3; - flash->CR |= FLASH_CR_STRT; - while ((flash->SR & FLASH_SR_BSY) != 0) ; - } + while (index < data_length) { + // flash two words at a time + uint32_t words[2]; + memcpy((void*)&words[0], &data[index*4], sizeof(words)); - uint32_t index = 0; - volatile uint32_t *fdata = (volatile uint32_t *)add; + flash->CR = FLASH_CR_PG; - while (index < data_length) { - // flash two words at a time - uint32_t words[2]; - memcpy((void*)&words[0], &data[index*4], sizeof(words)); + fdata[index] = words[0]; + fdata[index+1] = words[1]; - flash->CR = FLASH_CR_PG; - - fdata[index] = words[0]; - fdata[index+1] = words[1]; - - while ((flash->SR & FLASH_SR_BSY) != 0) ; + while ((flash->SR & FLASH_SR_BSY) != 0) ; - flash->SR |= FLASH_SR_EOP; - flash->CR = 0; - index += 2; - } + flash->SR |= FLASH_SR_EOP; + flash->CR = 0; + index += 2; + } - // lock flash again - SET_BIT(flash->CR, FLASH_CR_LOCK); + // lock flash again + SET_BIT(flash->CR, FLASH_CR_LOCK); - // ensure data is correct - return memcmp(data, (const void *)add, length) == 0; + // ensure data is correct + return memcmp(data, (const void *)add, length) == 0; } -void read_flash_bin(uint8_t* data , uint32_t add , int out_buff_len) { - memcpy(data, (void*)add, out_buff_len); +void read_flash_bin(uint8_t* data, uint32_t add, int out_buff_len) +{ + memcpy(data, (void*)add, out_buff_len); } diff --git a/Mcu/g431/Src/stm32g4xx_it.c b/Mcu/g431/Src/stm32g4xx_it.c index 9f9754f4..c9f23e07 100644 --- a/Mcu/g431/Src/stm32g4xx_it.c +++ b/Mcu/g431/Src/stm32g4xx_it.c @@ -4,32 +4,32 @@ void NMI_Handler(void) { - while (1) { - } + while (1) { + } } void HardFault_Handler(void) { - while (1) { - } + while (1) { + } } void MemManage_Handler(void) { - while (1) { - } + while (1) { + } } void BusFault_Handler(void) { - while (1) { - } + while (1) { + } } void UsageFault_Handler(void) { - while (1) { - } + while (1) { + } } void SVC_Handler(void) { } diff --git a/Mcu/l431/Inc/blutil.h b/Mcu/l431/Inc/blutil.h index fa0e336d..6de6c6f8 100644 --- a/Mcu/l431/Inc/blutil.h +++ b/Mcu/l431/Inc/blutil.h @@ -24,32 +24,34 @@ #define GPIO_OUTPUT_PUSH_PULL LL_GPIO_OUTPUT_PUSHPULL +#ifdef PORT_LETTER static inline void gpio_mode_set_input(uint32_t pin, uint32_t pull_up_down) { - LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_INPUT); - LL_GPIO_SetPinPull(input_port, pin, pull_up_down); + LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_INPUT); + LL_GPIO_SetPinPull(input_port, pin, pull_up_down); } static inline void gpio_mode_set_output(uint32_t pin, uint32_t output_mode) { - LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_OUTPUT); - LL_GPIO_SetPinOutputType(input_port, pin, output_mode); + LL_GPIO_SetPinMode(input_port, pin, LL_GPIO_MODE_OUTPUT); + LL_GPIO_SetPinOutputType(input_port, pin, output_mode); } static inline void gpio_set(uint32_t pin) { - LL_GPIO_SetOutputPin(input_port, pin); + LL_GPIO_SetOutputPin(input_port, pin); } static inline void gpio_clear(uint32_t pin) { - LL_GPIO_ResetOutputPin(input_port, pin); + LL_GPIO_ResetOutputPin(input_port, pin); } static inline bool gpio_read(uint32_t pin) { - return LL_GPIO_IsInputPinSet(input_port, pin); + return LL_GPIO_IsInputPinSet(input_port, pin); } +#endif // PORT_LETTER #define BL_TIMER TIM2 @@ -58,23 +60,23 @@ static inline bool gpio_read(uint32_t pin) */ static inline void bl_timer_init(void) { - LL_TIM_InitTypeDef TIM_InitStruct = {0}; - - /* Peripheral clock enable */ - LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2); - - TIM_InitStruct.Prescaler = 79; - TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP; - TIM_InitStruct.Autoreload = 0xFFFFFFFF; - TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; - LL_TIM_Init(BL_TIMER, &TIM_InitStruct); - LL_TIM_DisableARRPreload(BL_TIMER); - LL_TIM_SetClockSource(BL_TIMER, LL_TIM_CLOCKSOURCE_INTERNAL); - LL_TIM_SetTriggerOutput(BL_TIMER, LL_TIM_TRGO_RESET); - LL_TIM_DisableMasterSlaveMode(BL_TIMER); - - LL_TIM_SetCounterMode(BL_TIMER, LL_TIM_COUNTERMODE_UP); - LL_TIM_EnableCounter(BL_TIMER); + LL_TIM_InitTypeDef TIM_InitStruct = {0}; + + /* Peripheral clock enable */ + LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2); + + TIM_InitStruct.Prescaler = 79; + TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP; + TIM_InitStruct.Autoreload = 0xFFFFFFFF; + TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; + LL_TIM_Init(BL_TIMER, &TIM_InitStruct); + LL_TIM_DisableARRPreload(BL_TIMER); + LL_TIM_SetClockSource(BL_TIMER, LL_TIM_CLOCKSOURCE_INTERNAL); + LL_TIM_SetTriggerOutput(BL_TIMER, LL_TIM_TRGO_RESET); + LL_TIM_DisableMasterSlaveMode(BL_TIMER); + + LL_TIM_SetCounterMode(BL_TIMER, LL_TIM_COUNTERMODE_UP); + LL_TIM_EnableCounter(BL_TIMER); } /* @@ -82,17 +84,12 @@ static inline void bl_timer_init(void) */ static inline void bl_timer_disable(void) { - LL_TIM_DeInit(BL_TIMER); + LL_TIM_DeInit(BL_TIMER); } -static inline uint32_t bl_timer_us(void) +static inline uint16_t bl_timer_us(void) { - return LL_TIM_GetCounter(BL_TIMER); -} - -static inline void bl_timer_reset(void) -{ - LL_TIM_SetCounter(BL_TIMER, 0); + return LL_TIM_GetCounter(BL_TIMER); } /* @@ -100,39 +97,50 @@ static inline void bl_timer_reset(void) */ static inline void bl_clock_config(void) { - LL_FLASH_SetLatency(LL_FLASH_LATENCY_4); - while (LL_FLASH_GetLatency()!= LL_FLASH_LATENCY_4) ; - LL_PWR_SetRegulVoltageScaling(LL_PWR_REGU_VOLTAGE_SCALE1); - while (LL_PWR_IsActiveFlag_VOS() != 0) ; - LL_RCC_MSI_Enable(); - - /* Wait till MSI is ready */ - while (LL_RCC_MSI_IsReady() != 1) ; - - LL_RCC_MSI_EnableRangeSelection(); - LL_RCC_MSI_SetRange(LL_RCC_MSIRANGE_6); - LL_RCC_MSI_SetCalibTrimming(0); - LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_MSI, LL_RCC_PLLM_DIV_1, 40, LL_RCC_PLLR_DIV_2); - LL_RCC_PLL_EnableDomain_SYS(); - LL_RCC_PLL_Enable(); - - /* Wait till PLL is ready */ - while (LL_RCC_PLL_IsReady() != 1) ; - LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); - - /* Wait till System clock is ready */ - while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) ; - - LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1); - LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1); - LL_RCC_SetAPB2Prescaler(LL_RCC_APB2_DIV_1); + LL_FLASH_SetLatency(LL_FLASH_LATENCY_4); + while (LL_FLASH_GetLatency()!= LL_FLASH_LATENCY_4) ; + LL_PWR_SetRegulVoltageScaling(LL_PWR_REGU_VOLTAGE_SCALE1); + + while (LL_PWR_IsActiveFlag_VOS() != 0) ; + LL_RCC_HSI_Enable(); + LL_RCC_LSI_Enable(); + + /* Wait till MSI and LSI are ready */ + while (LL_RCC_LSI_IsReady() != 1) ; + while (LL_RCC_HSI_IsReady() != 1) ; + + LL_RCC_SetRTCClockSource(LL_RCC_RTC_CLKSOURCE_LSI); + LL_RCC_EnableRTC(); + + LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI, LL_RCC_PLLM_DIV_2, 20, LL_RCC_PLLR_DIV_2); + LL_RCC_PLL_EnableDomain_SYS(); + LL_RCC_PLL_Enable(); + + LL_RCC_MSI_EnableRangeSelection(); + LL_RCC_MSI_SetRange(LL_RCC_MSIRANGE_6); + LL_RCC_MSI_SetCalibTrimming(0); + LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_MSI, LL_RCC_PLLM_DIV_1, 40, LL_RCC_PLLR_DIV_2); + LL_RCC_PLL_EnableDomain_SYS(); + LL_RCC_PLL_Enable(); + + /* Wait till PLL is ready */ + while (LL_RCC_PLL_IsReady() != 1) ; + LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); + + /* Wait till System clock is ready */ + while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) ; + + LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1); + LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1); + LL_RCC_SetAPB2Prescaler(LL_RCC_APB2_DIV_1); } +#ifdef PORT_LETTER static inline void bl_gpio_init(void) { - LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOA); - LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOB); - LL_GPIO_ResetOutputPin(input_port, input_pin); + LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOA); + LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOB); + LL_GPIO_ResetOutputPin(input_port, input_pin); } /* @@ -140,12 +148,12 @@ static inline void bl_gpio_init(void) */ static inline bool bl_was_software_reset(void) { - return (RCC->CSR & RCC_CSR_SFTRSTF) != 0; + return (RCC->CSR & RCC_CSR_SFTRSTF) != 0; } void Error_Handler() { - while (1) {} + while (1) {} } #ifdef FIRMWARE_RELATIVE_START @@ -154,22 +162,22 @@ void Error_Handler() */ static inline void jump_to_application(void) { - __disable_irq(); - bl_timer_disable(); - const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; - const uint32_t *app_data = (const uint32_t *)app_address; - const uint32_t stack_top = app_data[0]; - const uint32_t JumpAddress = app_data[1]; - - // setup vector table - SCB->VTOR = app_address; - - // setup sp, msp and jump - asm volatile( - "mov sp, %0 \n" - "msr msp, %0 \n" - "bx %1 \n" - : : "r"(stack_top), "r"(JumpAddress) :); + __disable_irq(); + bl_timer_disable(); + const uint32_t app_address = MCU_FLASH_START + FIRMWARE_RELATIVE_START; + const uint32_t *app_data = (const uint32_t *)app_address; + const uint32_t stack_top = app_data[0]; + const uint32_t JumpAddress = app_data[1]; + + // setup vector table + SCB->VTOR = app_address; + + // setup sp, msp and jump + asm volatile( + "mov sp, %0 \n" + "msr msp, %0 \n" + "bx %1 \n" + : : "r"(stack_top), "r"(JumpAddress) :); } #endif // FIRMWARE_RELATIVE_START @@ -187,14 +195,11 @@ void SystemInit(void) /* Reset the RCC clock configuration to the default reset state ------------*/ /* Set MSION bit */ - RCC->CR |= RCC_CR_MSION; + RCC->CR |= RCC_CR_HSION; /* Reset CFGR register */ RCC->CFGR = 0x00000000U; - /* Reset HSEON, CSSON , HSION, and PLLON bits */ - RCC->CR &= 0xEAF6FFFFU; - /* Reset PLLCFGR register */ RCC->PLLCFGR = 0x00001000U; @@ -203,4 +208,9 @@ void SystemInit(void) /* Disable all interrupts */ RCC->CIER = 0x00000000U; + + // enable the backup domain + LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_PWR); + LL_PWR_EnableBkUpAccess(); } +#endif // PORT_LETTER diff --git a/Mcu/l431/Src/eeprom.c b/Mcu/l431/Src/eeprom.c index a1d7fa22..33a358d0 100644 --- a/Mcu/l431/Src/eeprom.c +++ b/Mcu/l431/Src/eeprom.c @@ -17,67 +17,68 @@ static const uint32_t FLASH_FKEY2 =0xCDEF89AB; bool save_flash_nolib(const uint8_t *data, uint32_t length, uint32_t add) { - if ((add & 0x7) != 0 || (length & 0x7)) { - // address and length must be on 8 byte boundary - return false; - } - // we need to flash on 32 bit boundaries - uint32_t data_length = length / 4; - volatile FLASH_TypeDef *flash = FLASH; - - // clear errors - flash->SR |= FLASH_SR_OPERR | FLASH_SR_PROGERR | FLASH_SR_WRPERR | FLASH_SR_PGAERR | - FLASH_SR_SIZERR | FLASH_SR_PGSERR | FLASH_SR_MISERR | FLASH_SR_FASTERR | - FLASH_SR_RDERR | FLASH_SR_OPTVERR; - - // unlock flash + if ((add & 0x7) != 0 || (length & 0x7)) { + // address and length must be on 8 byte boundary + return false; + } + // we need to flash on 32 bit boundaries + uint32_t data_length = length / 4; + volatile FLASH_TypeDef *flash = FLASH; + + // clear errors + flash->SR |= FLASH_SR_OPERR | FLASH_SR_PROGERR | FLASH_SR_WRPERR | FLASH_SR_PGAERR | + FLASH_SR_SIZERR | FLASH_SR_PGSERR | FLASH_SR_MISERR | FLASH_SR_FASTERR | + FLASH_SR_RDERR | FLASH_SR_OPTVERR; + + // unlock flash + while ((flash->SR & FLASH_SR_BSY) != 0) ; + + if ((flash->CR & FLASH_CR_LOCK) != 0) { + flash->KEYR = FLASH_FKEY1; + flash->KEYR = FLASH_FKEY2; + } + + // erase page if address is divisable by page size + if ((add % page_size) == 0) { + flash->CR = FLASH_CR_PER; + flash->CR |= (add/page_size) << 3; + flash->CR |= FLASH_CR_STRT; while ((flash->SR & FLASH_SR_BSY) != 0) ; + } - if ((flash->CR & FLASH_CR_LOCK) != 0) { - flash->KEYR = FLASH_FKEY1; - flash->KEYR = FLASH_FKEY2; - } + uint32_t index = 0; + volatile uint32_t *fdata = (volatile uint32_t *)add; - // erase page if address is divisable by page size - if ((add % page_size) == 0){ - flash->CR = FLASH_CR_PER; - flash->CR |= (add/page_size) << 3; - flash->CR |= FLASH_CR_STRT; - while ((flash->SR & FLASH_SR_BSY) != 0) ; - } + while (index < data_length) { + // flash two words at a time + uint32_t words[2]; + memcpy((void*)&words[0], &data[index*4], sizeof(words)); - uint32_t index = 0; - volatile uint32_t *fdata = (volatile uint32_t *)add; + flash->CR = FLASH_CR_PG; - while (index < data_length) { - // flash two words at a time - uint32_t words[2]; - memcpy((void*)&words[0], &data[index*4], sizeof(words)); + fdata[index] = words[0]; + fdata[index+1] = words[1]; - flash->CR = FLASH_CR_PG; - - fdata[index] = words[0]; - fdata[index+1] = words[1]; - - while ((flash->SR & FLASH_SR_BSY) != 0) ; + while ((flash->SR & FLASH_SR_BSY) != 0) ; - flash->SR |= FLASH_SR_EOP; - flash->CR = 0; - index += 2; - } + flash->SR |= FLASH_SR_EOP; + flash->CR = 0; + index += 2; + } - // lock flash again - SET_BIT(flash->CR, FLASH_CR_LOCK); + // lock flash again + SET_BIT(flash->CR, FLASH_CR_LOCK); - // ensure data is correct - return memcmp(data, (const void *)add, length) == 0; + // ensure data is correct + return memcmp(data, (const void *)add, length) == 0; } -void read_flash_bin(uint8_t* data , uint32_t add , int out_buff_len) { - memcpy(data, (void*)add, out_buff_len); +void read_flash_bin(uint8_t* data, uint32_t add, int out_buff_len) +{ + memcpy(data, (void*)add, out_buff_len); } diff --git a/Mcu/v203/Drivers/Debug/debug.c b/Mcu/v203/Drivers/Debug/debug.c deleted file mode 100644 index ad7c5b3f..00000000 --- a/Mcu/v203/Drivers/Debug/debug.c +++ /dev/null @@ -1,262 +0,0 @@ -/********************************** (C) COPYRIGHT ******************************* - * File Name : debug.c - * Author : WCH - * Version : V1.0.0 - * Date : 2021/06/06 - * Description : This file contains all the functions prototypes for UART - * Printf , Delay functions. -********************************************************************************* -* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd. -* Attention: This software (modified or not) and binary are used for -* microcontroller manufactured by Nanjing Qinheng Microelectronics. -*******************************************************************************/ -#include "debug.h" - -static uint8_t p_us = 0; -static uint16_t p_ms = 0; - - -/********************************************************************* - * @fn Delay_Init - * - * @brief Initializes Delay Funcation. - * - * @return none - */ -void Delay_Init(void) -{ - p_us = SystemCoreClock / 8000000; - p_ms = (uint16_t)p_us * 1000; -} - -/********************************************************************* - * @fn Delay_Us - * - * @brief Microsecond Delay Time. - * - * @param n - Microsecond number. - * - * @return None - */ -void Delay_Us(uint32_t n) -{ - uint32_t i; - - SysTick->SR &= ~(1 << 0); - i = (uint32_t)n * p_us; - - SysTick->CMP = i; - SysTick->CTLR |= (1 << 4); - SysTick->CTLR |= (1 << 5) | (1 << 0); - - while((SysTick->SR & (1 << 0)) != (1 << 0)); - SysTick->CTLR &= ~(1 << 0); -} - -/********************************************************************* - * @fn Delay_Ms - * - * @brief Millisecond Delay Time. - * - * @param n - Millisecond number. - * - * @return None - */ -void Delay_Ms(uint32_t n) -{ - uint32_t i; - - SysTick->SR &= ~(1 << 0); - i = (uint32_t)n * p_ms; - - SysTick->CMP = i; - SysTick->CTLR |= (1 << 4); - SysTick->CTLR |= (1 << 5) | (1 << 0); - - while((SysTick->SR & (1 << 0)) != (1 << 0)); - SysTick->CTLR &= ~(1 << 0); -} - -/********************************************************************* - * @fn USART_Printf_Init - * - * @brief Initializes the USARTx peripheral. - * - * @param baudrate - USART communication baud rate. - * - * @return None - */ -void USART_Printf_Init(uint32_t baudrate) -{ - GPIO_InitTypeDef GPIO_InitStructure; - USART_InitTypeDef USART_InitStructure; - -#if(DEBUG == DEBUG_UART1) - RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOB|RCC_APB2Periph_AFIO, ENABLE); - GPIO_PinRemapConfig(GPIO_Remap_USART1,ENABLE); - - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; - GPIO_Init(GPIOB, &GPIO_InitStructure); - -#elif(DEBUG == DEBUG_UART2) - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); - - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; - GPIO_Init(GPIOA, &GPIO_InitStructure); - -#elif(DEBUG == DEBUG_UART3) - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE); - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); - - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; - GPIO_Init(GPIOB, &GPIO_InitStructure); - -#endif - - USART_InitStructure.USART_BaudRate = baudrate; - USART_InitStructure.USART_WordLength = USART_WordLength_8b; - USART_InitStructure.USART_StopBits = USART_StopBits_1; - USART_InitStructure.USART_Parity = USART_Parity_No; - USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; - USART_InitStructure.USART_Mode = USART_Mode_Tx; - -#if(DEBUG == DEBUG_UART1) - USART_Init(USART1, &USART_InitStructure); - USART_Cmd(USART1, ENABLE); - -#elif(DEBUG == DEBUG_UART2) - USART_Init(USART2, &USART_InitStructure); - USART_Cmd(USART2, ENABLE); - -#elif(DEBUG == DEBUG_UART3) - USART_Init(USART3, &USART_InitStructure); - USART_Cmd(USART3, ENABLE); - -#endif -} - -void delay_bittime(void) -{ // 921600 �����ر�׼����������linke�Ĵ�����ʶ�𣬶Ե����а��� - uint8_t i; - for(i=0;i<166;i++) - { - asm("nop"); - } -} - -void serialwriteChar(char data) -{ - GPIOA->BCR = GPIO_Pin_13; //start - char bits_to_read = 0; - while (bits_to_read < 8) - { - delay_bittime( ); - if (data & 0x01) - { - GPIOA->BSHR = GPIO_Pin_13; - } - else - { - GPIOA->BCR = GPIO_Pin_13; - } - bits_to_read++; - data = data >> 1; - } - delay_bittime( ); - GPIOA->BSHR = GPIO_Pin_13; //write the stop bit -} - -//�����ַ��� -void sendString(uint8_t *data, int len) -{ - for(int i = 0; i < len; i++) - { - serialwriteChar(data[i]); - delay_bittime( ); //stop bit delay - } -} - - -void SDI_Printf_Enable(void) -{ - GPIO_InitTypeDef GPIO_InitStructure = {0}; - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA|RCC_APB2Periph_AFIO, ENABLE); - delay_bittime( ); - delay_bittime( ); - GPIO_PinRemapConfig(GPIO_Remap_SWJ_Disable,ENABLE); - - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; - GPIO_Init(GPIOA, &GPIO_InitStructure); - GPIOA->BSHR = GPIO_Pin_13; //���� - delay_bittime( ); -} - - -/********************************************************************* - * @fn _write - * - * @brief Support Printf Function - * - * @param *buf - UART send Data. - * size - Data length - * - * @return size: Data length - */ -__attribute__((used)) -int _write(int fd, char *buf, int size) -{ - int i = 0; - -#if(1) - for(i = 0; i < size; i++) - { - serialwriteChar(buf[i]); - delay_bittime( ); //stop bit delay - } - -#else - for(i = 0; i < size; i++){ -#if(DEBUG == DEBUG_UART1) - while(USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET); - USART_SendData(USART1, *buf++); -#elif(DEBUG == DEBUG_UART2) - while(USART_GetFlagStatus(USART2, USART_FLAG_TC) == RESET); - USART_SendData(USART2, *buf++); -#elif(DEBUG == DEBUG_UART3) - while(USART_GetFlagStatus(USART3, USART_FLAG_TC) == RESET); - USART_SendData(USART3, *buf++); -#endif - } -#endif - return size; -} - -/********************************************************************* - * @fn _sbrk - * - * @brief Change the spatial position of data segment. - * - * @return size: Data length - */ -__attribute__((used)) -void *_sbrk(ptrdiff_t incr) -{ - extern char _end[]; - extern char _heap_end[]; - static char *curbrk = _end; - - if ((curbrk + incr < _end) || (curbrk + incr > _heap_end)) - return NULL - 1; - - curbrk += incr; - return curbrk - incr; -} diff --git a/Mcu/v203/Drivers/Debug/debug.h b/Mcu/v203/Drivers/Debug/debug.h deleted file mode 100644 index 958bb754..00000000 --- a/Mcu/v203/Drivers/Debug/debug.h +++ /dev/null @@ -1,71 +0,0 @@ -/********************************** (C) COPYRIGHT ******************************* - * File Name : debug.h - * Author : WCH - * Version : V1.0.0 - * Date : 2021/06/06 - * Description : This file contains all the functions prototypes for UART - * Printf , Delay functions. -********************************************************************************* -* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd. -* Attention: This software (modified or not) and binary are used for -* microcontroller manufactured by Nanjing Qinheng Microelectronics. -*******************************************************************************/ -#ifndef __DEBUG_H -#define __DEBUG_H - -#include "stdio.h" -#include "ch32v20x.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* UART Printf Definition */ -#define DEBUG_UART1 1 -#define DEBUG_UART2 2 -#define DEBUG_UART3 3 - -/* DEBUG UATR Definition */ -#ifndef DEBUG -#define DEBUG DEBUG_UART1 -#endif - - -#define SET_BIT(REG, BIT) ((REG) |= (BIT)) - -#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) - -#define READ_BIT(REG, BIT) ((REG) & (BIT)) - -#define CLEAR_REG(REG) ((REG) = (0x0)) - -#define WRITE_REG(REG, VAL) ((REG) = (VAL)) - -#define READ_REG(REG) ((REG)) - -#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) - - - - -void Delay_Init(void); -void Delay_Us(uint32_t n); -void Delay_Ms(uint32_t n); -void USART_Printf_Init(uint32_t baudrate); -void SDI_Printf_Enable(void); - -//#define DEBUG_SDI - -#ifdef DEBUG_SDI - #define PRINT(format, ...) printf(format, ##__VA_ARGS__) -#else - #define PRINT(X...) -#endif - - - -#ifdef __cplusplus -} -#endif - -#endif diff --git a/Mcu/v203/Inc/blutil.h b/Mcu/v203/Inc/blutil.h index 281011e1..db3bf43e 100644 --- a/Mcu/v203/Inc/blutil.h +++ b/Mcu/v203/Inc/blutil.h @@ -33,79 +33,82 @@ static NOINLINE void gpio_mode_set_input(uint32_t pin, uint32_t pull_up_down) { - volatile uint32_t *cfgr; - if (pin >= GPIO_PIN(8)) { - pin >>= 8; - cfgr = &input_port->CFGHR; - } else { - cfgr = &input_port->CFGLR; - } - const uint32_t mul = pin*pin*pin*pin; - const uint32_t CFG = (*cfgr) & ~(0xf * mul); - switch (pull_up_down) { - case GPIO_PULL_NONE: - *cfgr = CFG | (0x4*mul); - break; - case GPIO_PULL_UP: - input_port->OUTDR |= pin; - *cfgr = CFG | (0x8*mul); - break; - case GPIO_PULL_DOWN: - input_port->OUTDR &= ~pin; - *cfgr = CFG | (0x8*mul); - break; - } + volatile uint32_t *cfgr; + if (pin >= GPIO_PIN(8)) { + pin >>= 8; + cfgr = &input_port->CFGHR; + } else { + cfgr = &input_port->CFGLR; + } + const uint32_t mul = pin*pin*pin*pin; + const uint32_t CFG = (*cfgr) & ~(0xf * mul); + switch (pull_up_down) { + case GPIO_PULL_NONE: + *cfgr = CFG | (0x4*mul); + break; + case GPIO_PULL_UP: + input_port->OUTDR |= pin; + *cfgr = CFG | (0x8*mul); + break; + case GPIO_PULL_DOWN: + input_port->OUTDR &= ~pin; + *cfgr = CFG | (0x8*mul); + break; + } } static inline void gpio_mode_set_output(uint32_t pin, uint32_t output_mode) { - volatile uint32_t *cfgr; - if (pin >= GPIO_PIN(8)) { - pin >>= 8; - cfgr = &input_port->CFGHR; - } else { - cfgr = &input_port->CFGLR; - } - const uint32_t mul = pin*pin*pin*pin; - const uint32_t CFG = (*cfgr) & ~(0xf * mul); - (*cfgr) = CFG | (output_mode*mul); + volatile uint32_t *cfgr; + if (pin >= GPIO_PIN(8)) { + pin >>= 8; + cfgr = &input_port->CFGHR; + } else { + cfgr = &input_port->CFGLR; + } + const uint32_t mul = pin*pin*pin*pin; + const uint32_t CFG = (*cfgr) & ~(0xf * mul); + (*cfgr) = CFG | (output_mode*mul); } static inline void gpio_set(uint32_t pin) { - input_port->BSHR = pin; + input_port->BSHR = pin; } static inline void gpio_clear(uint32_t pin) { - input_port->BCR = pin; + input_port->BCR = pin; } static inline bool gpio_read(uint32_t pin) { - return (input_port->INDR & pin) != 0; + return (input_port->INDR & pin) != 0; } -#define BL_TIMER TIM1 +#define BL_TIMER TIM2 /* initialise timer for 1us per tick */ static inline void bl_timer_init(void) { - RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); - - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); - TIM_TimeBaseStructure.TIM_Prescaler = 47; - TIM_TimeBaseStructure.TIM_Period = 0xFFFF; - TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseInit(BL_TIMER, &TIM_TimeBaseStructure); - TIM_SetCounter(BL_TIMER, 0); - TIM_ARRPreloadConfig(BL_TIMER, ENABLE); - - TIM_Cmd(BL_TIMER, ENABLE); + RCC->APB1PCENR |= RCC_APB1Periph_TIM2; + + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; + TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); + TIM_TimeBaseStructure.TIM_Prescaler = 143; + TIM_TimeBaseStructure.TIM_Period = 0xFFFF; + TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; + TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseInit(BL_TIMER, &TIM_TimeBaseStructure); + TIM_SetCounter(BL_TIMER, 0); + + // enable preload + BL_TIMER->CTLR1 |= TIM_ARPE; + + // enable timer + BL_TIMER->CTLR1 |= TIM_CEN; } /* @@ -113,17 +116,12 @@ static inline void bl_timer_init(void) */ static inline void bl_timer_disable(void) { - RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, DISABLE); + RCC->APB1PCENR &= ~RCC_APB1Periph_TIM2; } -static inline uint32_t bl_timer_us(void) +static inline uint16_t bl_timer_us(void) { - return BL_TIMER->CNT; -} - -static inline void bl_timer_reset(void) -{ - BL_TIMER->CNT = 0; + return BL_TIMER->CNT; } /* @@ -131,20 +129,20 @@ static inline void bl_timer_reset(void) */ static inline void bl_clock_config(void) { - SystemInit(); + SystemInit(); } static inline void bl_gpio_init(void) { - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE ); - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE ); - - GPIO_InitTypeDef GPIO_InitStruct = {0}; - GPIO_StructInit(&GPIO_InitStruct); - GPIO_InitStruct.GPIO_Pin = input_pin; - GPIO_InitStruct.GPIO_Mode = GPIO_Mode_IN_FLOATING; - GPIO_InitStruct.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_Init(input_port, &GPIO_InitStruct); + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE ); + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE ); + + GPIO_InitTypeDef GPIO_InitStruct = {0}; + GPIO_StructInit(&GPIO_InitStruct); + GPIO_InitStruct.GPIO_Pin = input_pin; + GPIO_InitStruct.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_InitStruct.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_Init(input_port, &GPIO_InitStruct); } /* @@ -152,12 +150,12 @@ static inline void bl_gpio_init(void) */ static inline bool bl_was_software_reset(void) { - return (RCC->RSTSCKR & RCC_SFTRSTF) != 0; + return (RCC->RSTSCKR & RCC_SFTRSTF) != 0; } void Error_Handler() { - while (1) {} + while (1) {} } /* @@ -165,17 +163,17 @@ void Error_Handler() */ static inline void jump_to_application(void) { - __disable_irq(); - bl_timer_disable(); - const uint32_t app_address = FIRMWARE_RELATIVE_START; - const uint32_t stack_top = RAM_BASE + RAM_SIZE; - - // set the stack pointer and jump to the application - asm volatile( - "mv sp, %0 \n" - "jr %1 \n" - : // No output operands - : "r"(stack_top), "r"(app_address) - : // No clobbered registers - ); + __disable_irq(); + bl_timer_disable(); + const uint32_t app_address = FIRMWARE_RELATIVE_START; + const uint32_t stack_top = RAM_BASE + RAM_SIZE; + + // set the stack pointer and jump to the application + asm volatile( + "mv sp, %0 \n" + "jr %1 \n" + : // No output operands + : "r"(stack_top), "r"(app_address) + : // No clobbered registers + ); } diff --git a/Mcu/v203/Inc/ch32v20x_conf.h b/Mcu/v203/Inc/ch32v20x_conf.h index d1eeb38a..d35ed706 100644 --- a/Mcu/v203/Inc/ch32v20x_conf.h +++ b/Mcu/v203/Inc/ch32v20x_conf.h @@ -6,37 +6,37 @@ * Description : Library configuration file. ********************************************************************************* * Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd. -* Attention: This software (modified or not) and binary are used for +* Attention: This software (modified or not) and binary are used for * microcontroller manufactured by Nanjing Qinheng Microelectronics. *******************************************************************************/ #ifndef __CH32V20x_CONF_H #define __CH32V20x_CONF_H -#include "ch32v20x_adc.h" -#include "ch32v20x_bkp.h" -#include "ch32v20x_can.h" -#include "ch32v20x_crc.h" -#include "ch32v20x_dbgmcu.h" -#include "ch32v20x_dma.h" -#include "ch32v20x_exti.h" +//#include "ch32v20x_adc.h" +//#include "ch32v20x_bkp.h" +//#include "ch32v20x_can.h" +//#include "ch32v20x_crc.h" +//#include "ch32v20x_dbgmcu.h" +//#include "ch32v20x_dma.h" +//#include "ch32v20x_exti.h" #include "ch32v20x_flash.h" #include "ch32v20x_gpio.h" -#include "ch32v20x_i2c.h" -#include "ch32v20x_iwdg.h" -#include "ch32v20x_pwr.h" +//#include "ch32v20x_i2c.h" +//#include "ch32v20x_iwdg.h" +//#include "ch32v20x_pwr.h" #include "ch32v20x_rcc.h" -#include "ch32v20x_rtc.h" -#include "ch32v20x_spi.h" +//#include "ch32v20x_rtc.h" +//#include "ch32v20x_spi.h" #include "ch32v20x_tim.h" -#include "ch32v20x_usart.h" -#include "ch32v20x_wwdg.h" -#include "ch32v20x_it.h" -#include "ch32v20x_misc.h" +//#include "ch32v20x_usart.h" +//#include "ch32v20x_wwdg.h" +//#include "ch32v20x_it.h" +//#include "ch32v20x_misc.h" #endif /* __CH32V20x_CONF_H */ - - - + + + diff --git a/Mcu/v203/Inc/ch32v20x_it.h b/Mcu/v203/Inc/ch32v20x_it.h deleted file mode 100644 index f68b2034..00000000 --- a/Mcu/v203/Inc/ch32v20x_it.h +++ /dev/null @@ -1,20 +0,0 @@ -/********************************** (C) COPYRIGHT ******************************* - * File Name : ch32v20x_it.h - * Author : WCH - * Version : V1.0.0 - * Date : 2021/06/06 - * Description : This file contains the headers of the interrupt handlers. -********************************************************************************* -* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd. -* Attention: This software (modified or not) and binary are used for -* microcontroller manufactured by Nanjing Qinheng Microelectronics. -*******************************************************************************/ -#ifndef __CH32V20x_IT_H -#define __CH32V20x_IT_H - -#include "debug.h" - - -#endif /* __CH32V20x_IT_H */ - - diff --git a/Mcu/v203/Inc/system_ch32v20x.h b/Mcu/v203/Inc/system_ch32v20x.h index 9c8a3f71..65d2e2c7 100644 --- a/Mcu/v203/Inc/system_ch32v20x.h +++ b/Mcu/v203/Inc/system_ch32v20x.h @@ -6,19 +6,19 @@ * Description : CH32V20x Device Peripheral Access Layer System Header File. ********************************************************************************* * Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd. -* Attention: This software (modified or not) and binary are used for +* Attention: This software (modified or not) and binary are used for * microcontroller manufactured by Nanjing Qinheng Microelectronics. *******************************************************************************/ -#ifndef __SYSTEM_ch32v20x_H +#ifndef __SYSTEM_ch32v20x_H #define __SYSTEM_ch32v20x_H #ifdef __cplusplus - extern "C" { -#endif +extern "C" { +#endif extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */ -/* System_Exported_Functions */ +/* System_Exported_Functions */ extern void SystemInit(void); extern void SystemCoreClockUpdate(void); diff --git a/Mcu/v203/Src/ch32v20x_it.c b/Mcu/v203/Src/ch32v20x_it.c index 524edc7d..5a781b16 100644 --- a/Mcu/v203/Src/ch32v20x_it.c +++ b/Mcu/v203/Src/ch32v20x_it.c @@ -6,31 +6,27 @@ * Description : Main Interrupt Service Routines. ********************************************************************************* * Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd. -* Attention: This software (modified or not) and binary are used for +* Attention: This software (modified or not) and binary are used for * microcontroller manufactured by Nanjing Qinheng Microelectronics. *******************************************************************************/ -#include "ch32v20x_it.h" void NMI_Handler(void) __attribute__((interrupt)); void HardFault_Handler(void) __attribute__((interrupt)); void NMI_Handler(void) { - while (1) - { + while (1) { } } void HardFault_Handler(void) { - while (1) - { + while (1) { } } -//for tenkhz +// unused systick handler void SysTick_Handler(void) { - SysTick->SR = 0; } diff --git a/Mcu/v203/Src/eeprom.c b/Mcu/v203/Src/eeprom.c index 9d2c6da8..2c0e62fc 100644 --- a/Mcu/v203/Src/eeprom.c +++ b/Mcu/v203/Src/eeprom.c @@ -12,46 +12,46 @@ static void wait_not_busy(void) { - while ((FLASH->STATR & FLASH_STATR_BSY) != 0) {} + while ((FLASH->STATR & FLASH_STATR_BSY) != 0) {} } bool save_flash_nolib(const uint8_t* data, uint32_t length, uint32_t add) { - if ((add & 0x03) != 0 || (length & 0x03) != 0 || (length+(add&0xFF)) > page_size) { - return false; - } + if ((add & 0x03) != 0 || (length & 0x03) != 0 || (length+(add&0xFF)) > page_size) { + return false; + } - wait_not_busy(); + wait_not_busy(); - FLASH_Unlock_Fast(); + FLASH_Unlock_Fast(); - uint32_t flash_buffer[page_size/4]; - const uint8_t page_offset = add & 0xFFU; - const uint32_t page_base = add & ~0xFFU; + uint32_t flash_buffer[page_size/4]; + const uint8_t page_offset = add & 0xFFU; + const uint32_t page_base = add & ~0xFFU; - // get existing data - memcpy(flash_buffer, (void*)page_base, page_size); + // get existing data + memcpy(flash_buffer, (void*)page_base, page_size); - // overwrite with new data - memcpy(&flash_buffer[page_offset/4], data, length); + // overwrite with new data + memcpy(&flash_buffer[page_offset/4], data, length); - // fast erase is 256 bytes at a time, normal Flash_Erasepage - // is 4k at a time - FLASH_ErasePage_Fast(page_base); + // fast erase is 256 bytes at a time, normal Flash_Erasepage + // is 4k at a time + FLASH_ErasePage_Fast(page_base); - wait_not_busy(); + wait_not_busy(); - FLASH_ProgramPage_Fast(page_base, flash_buffer); + FLASH_ProgramPage_Fast(page_base, flash_buffer); - wait_not_busy(); + wait_not_busy(); - FLASH_Lock_Fast(); + FLASH_Lock_Fast(); - // ensure data is correct - return memcmp(data, (const void *)add, length) == 0; + // ensure data is correct + return memcmp(data, (const void *)add, length) == 0; } void read_flash_bin(uint8_t* data, uint32_t add, int out_buff_len) { - memcpy(data, (const uint8_t *)add, out_buff_len); + memcpy(data, (const uint8_t *)add, out_buff_len); } diff --git a/Mcu/v203/Src/system_ch32v20x.c b/Mcu/v203/Src/system_ch32v20x.c index 5d736a1c..4e8d0ce3 100644 --- a/Mcu/v203/Src/system_ch32v20x.c +++ b/Mcu/v203/Src/system_ch32v20x.c @@ -8,15 +8,15 @@ * For HSE = 8Mhz (other CH32V203x) ********************************************************************************* * Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd. -* Attention: This software (modified or not) and binary are used for +* Attention: This software (modified or not) and binary are used for * microcontroller manufactured by Nanjing Qinheng Microelectronics. *******************************************************************************/ -#include "ch32v20x.h" +#include "ch32v20x.h" -/* -* Uncomment the line corresponding to the desired System clock (SYSCLK) frequency (after +/* +* Uncomment the line corresponding to the desired System clock (SYSCLK) frequency (after * reset the HSI is used as SYSCLK source). -* If none of the define below is enabled, the HSI is used as System clock source. +* If none of the define below is enabled, the HSI is used as System clock source. */ //#define SYSCLK_FREQ_HSE HSE_VALUE //#define SYSCLK_FREQ_48MHz_HSE 48000000 @@ -29,9 +29,9 @@ //#define SYSCLK_FREQ_48MHz_HSI 48000000 //#define SYSCLK_FREQ_56MHz_HSI 56000000 //#define SYSCLK_FREQ_72MHz_HSI 72000000 -#define SYSCLK_FREQ_96MHz_HSI 96000000 +//#define SYSCLK_FREQ_96MHz_HSI 96000000 //#define SYSCLK_FREQ_120MHz_HSI 120000000 -//#define SYSCLK_FREQ_144MHz_HSI 144000000 +#define SYSCLK_FREQ_144MHz_HSI 144000000 /* Clock Definitions */ #ifdef SYSCLK_FREQ_HSE @@ -115,87 +115,10 @@ void SystemInit (void) RCC->CTLR &= (uint32_t)0xFEF6FFFF; RCC->CTLR &= (uint32_t)0xFFFBFFFF; RCC->CFGR0 &= (uint32_t)0xFF00FFFF; - RCC->INTR = 0x009F0000; + RCC->INTR = 0x009F0000; SetSysClock(); } - -/********************************************************************* - * @fn SystemCoreClockUpdate - * - * @brief Update SystemCoreClock variable according to Clock Register Values. - * - * @return none - */ -void SystemCoreClockUpdate (void) -{ - uint32_t tmp = 0, pllmull = 0, pllsource = 0, Pll_6_5 = 0; - - tmp = RCC->CFGR0 & RCC_SWS; - - switch (tmp) - { - case 0x00: - SystemCoreClock = HSI_VALUE; - break; - case 0x04: - SystemCoreClock = HSE_VALUE; - break; - case 0x08: - pllmull = RCC->CFGR0 & RCC_PLLMULL; - pllsource = RCC->CFGR0 & RCC_PLLSRC; - pllmull = ( pllmull >> 18) + 2; - - if(pllmull == 17) pllmull = 18; - - if (pllsource == 0x00) - { - if(EXTEN->EXTEN_CTR & EXTEN_PLL_HSI_PRE){ - SystemCoreClock = HSI_VALUE * pllmull; - } - else{ - SystemCoreClock = (HSI_VALUE >> 1) * pllmull; - } - } - else - { -#if defined (CH32V20x_D8W) - if((RCC->CFGR0 & (3<<22)) == (3<<22)) - { - SystemCoreClock = ((HSE_VALUE>>1)) * pllmull; - } - else -#endif - if ((RCC->CFGR0 & RCC_PLLXTPRE) != (uint32_t)RESET) - { -#if defined (CH32V20x_D8) || defined (CH32V20x_D8W) - SystemCoreClock = ((HSE_VALUE>>2) >> 1) * pllmull; -#else - SystemCoreClock = (HSE_VALUE >> 1) * pllmull; -#endif - } - else - { -#if defined (CH32V20x_D8) || defined (CH32V20x_D8W) - SystemCoreClock = (HSE_VALUE>>2) * pllmull; -#else - SystemCoreClock = HSE_VALUE * pllmull; -#endif - } - } - - if(Pll_6_5 == 1) SystemCoreClock = (SystemCoreClock / 2); - - break; - default: - SystemCoreClock = HSI_VALUE; - break; - } - - tmp = AHBPrescTable[((RCC->CFGR0 & RCC_HPRE) >> 4)]; - SystemCoreClock >>= tmp; -} - /********************************************************************* * @fn SetSysClock * @@ -207,37 +130,37 @@ static void SetSysClock(void) { //GPIO_IPD_Unused(); #ifdef SYSCLK_FREQ_HSE - SetSysClockToHSE(); + SetSysClockToHSE(); #elif defined SYSCLK_FREQ_48MHz_HSE - SetSysClockTo48_HSE(); + SetSysClockTo48_HSE(); #elif defined SYSCLK_FREQ_56MHz_HSE - SetSysClockTo56_HSE(); + SetSysClockTo56_HSE(); #elif defined SYSCLK_FREQ_72MHz_HSE - SetSysClockTo72_HSE(); + SetSysClockTo72_HSE(); #elif defined SYSCLK_FREQ_96MHz_HSE - SetSysClockTo96_HSE(); + SetSysClockTo96_HSE(); #elif defined SYSCLK_FREQ_120MHz_HSE - SetSysClockTo120_HSE(); + SetSysClockTo120_HSE(); #elif defined SYSCLK_FREQ_144MHz_HSE - SetSysClockTo144_HSE(); + SetSysClockTo144_HSE(); #elif defined SYSCLK_FREQ_48MHz_HSI - SetSysClockTo48_HSI(); + SetSysClockTo48_HSI(); #elif defined SYSCLK_FREQ_56MHz_HSI - SetSysClockTo56_HSI(); + SetSysClockTo56_HSI(); #elif defined SYSCLK_FREQ_72MHz_HSI - SetSysClockTo72_HSI(); + SetSysClockTo72_HSI(); #elif defined SYSCLK_FREQ_96MHz_HSI - SetSysClockTo96_HSI(); + SetSysClockTo96_HSI(); #elif defined SYSCLK_FREQ_120MHz_HSI - SetSysClockTo120_HSI(); + SetSysClockTo120_HSI(); #elif defined SYSCLK_FREQ_144MHz_HSI - SetSysClockTo144_HSI(); + SetSysClockTo144_HSI(); #endif - - /* If none of the define above is enabled, the HSI is used as System clock - * source (default after reset) - */ + + /* If none of the define above is enabled, the HSI is used as System clock + * source (default after reset) + */ } @@ -253,54 +176,46 @@ static void SetSysClock(void) static void SetSysClockToHSE(void) { __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - - + + RCC->CTLR |= ((uint32_t)RCC_HSEON); - + /* Wait till HSE is ready and if Time out is reached exit */ - do - { + do { HSEStatus = RCC->CTLR & RCC_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + StartUpCounter++; + } while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); - if ((RCC->CTLR & RCC_HSERDY) != RESET) - { + if ((RCC->CTLR & RCC_HSERDY) != RESET) { HSEStatus = (uint32_t)0x01; - } - else - { + } else { HSEStatus = (uint32_t)0x00; - } + } - if (HSEStatus == (uint32_t)0x01) - { + if (HSEStatus == (uint32_t)0x01) { /* HCLK = SYSCLK */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; /* PCLK2 = HCLK */ RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; /* PCLK1 = HCLK */ RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV1; - + /* Select HSE as system clock source * CH32V20x_D6 (HSE=8MHZ) * CH32V20x_D8 (HSE=32MHZ) * CH32V20x_D8W (HSE=32MHZ) */ RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); - RCC->CFGR0 |= (uint32_t)RCC_SW_HSE; + RCC->CFGR0 |= (uint32_t)RCC_SW_HSE; /* Wait till HSE is used as system clock source */ - while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x04) - { + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x04) { } + } else { + /* If HSE fails to start-up, the application will have wrong clock + * configuration. User can add here some code to deal with this error + */ } - else - { - /* If HSE fails to start-up, the application will have wrong clock - * configuration. User can add here some code to deal with this error - */ - } } #elif defined SYSCLK_FREQ_48MHz_HSE @@ -315,31 +230,26 @@ static void SetSysClockToHSE(void) static void SetSysClockTo48_HSE(void) { __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - - + + RCC->CTLR |= ((uint32_t)RCC_HSEON); /* Wait till HSE is ready and if Time out is reached exit */ - do - { + do { HSEStatus = RCC->CTLR & RCC_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + StartUpCounter++; + } while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); - if ((RCC->CTLR & RCC_HSERDY) != RESET) - { + if ((RCC->CTLR & RCC_HSERDY) != RESET) { HSEStatus = (uint32_t)0x01; - } - else - { + } else { HSEStatus = (uint32_t)0x00; - } + } - if (HSEStatus == (uint32_t)0x01) - { + if (HSEStatus == (uint32_t)0x01) { /* HCLK = SYSCLK */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; /* PCLK2 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; + RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; /* PCLK1 = HCLK */ RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; @@ -349,29 +259,25 @@ static void SetSysClockTo48_HSE(void) */ RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL)); - RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL6); + RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL6); /* Enable PLL */ RCC->CTLR |= RCC_PLLON; /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { + while ((RCC->CTLR & RCC_PLLRDY) == 0) { } /* Select PLL as system clock source */ RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); - RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; + RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { } + } else { + /* + * If HSE fails to start-up, the application will have wrong clock + * configuration. User can add here some code to deal with this error + */ } - else - { - /* - * If HSE fails to start-up, the application will have wrong clock - * configuration. User can add here some code to deal with this error - */ - } } #elif defined SYSCLK_FREQ_56MHz_HSE @@ -386,34 +292,29 @@ static void SetSysClockTo48_HSE(void) static void SetSysClockTo56_HSE(void) { __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - + RCC->CTLR |= ((uint32_t)RCC_HSEON); /* Wait till HSE is ready and if Time out is reached exit */ - do - { + do { HSEStatus = RCC->CTLR & RCC_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + StartUpCounter++; + } while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); - if ((RCC->CTLR & RCC_HSERDY) != RESET) - { + if ((RCC->CTLR & RCC_HSERDY) != RESET) { HSEStatus = (uint32_t)0x01; - } - else - { + } else { HSEStatus = (uint32_t)0x00; - } + } - if (HSEStatus == (uint32_t)0x01) - { + if (HSEStatus == (uint32_t)0x01) { /* HCLK = SYSCLK */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; /* PCLK2 = HCLK */ RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; /* PCLK1 = HCLK */ RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; - + /* CH32V20x_D6-PLL configuration: PLLCLK = HSE * 7 = 56 MHz (HSE=8MHZ) * CH32V20x_D8-PLL configuration: PLLCLK = HSE/4 * 7 = 56 MHz (HSE=32MHZ) * CH32V20x_D8W-PLL configuration: PLLCLK = HSE/4 * 7 = 56 MHz (HSE=32MHZ) @@ -425,25 +326,21 @@ static void SetSysClockTo56_HSE(void) /* Enable PLL */ RCC->CTLR |= RCC_PLLON; /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { + while ((RCC->CTLR & RCC_PLLRDY) == 0) { } /* Select PLL as system clock source */ RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); - RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; + RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { } + } else { + /* + * If HSE fails to start-up, the application will have wrong clock + * configuration. User can add here some code to deal with this error + */ } - else - { - /* - * If HSE fails to start-up, the application will have wrong clock - * configuration. User can add here some code to deal with this error - */ - } } #elif defined SYSCLK_FREQ_72MHz_HSE @@ -458,63 +355,54 @@ static void SetSysClockTo56_HSE(void) static void SetSysClockTo72_HSE(void) { __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - + RCC->CTLR |= ((uint32_t)RCC_HSEON); - + /* Wait till HSE is ready and if Time out is reached exit */ - do - { + do { HSEStatus = RCC->CTLR & RCC_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + StartUpCounter++; + } while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); - if ((RCC->CTLR & RCC_HSERDY) != RESET) - { + if ((RCC->CTLR & RCC_HSERDY) != RESET) { HSEStatus = (uint32_t)0x01; - } - else - { + } else { HSEStatus = (uint32_t)0x00; - } + } - if (HSEStatus == (uint32_t)0x01) - { + if (HSEStatus == (uint32_t)0x01) { /* HCLK = SYSCLK */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; /* PCLK2 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; + RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; /* PCLK1 = HCLK */ RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; - + /* CH32V20x_D6-PLL configuration: PLLCLK = HSE * 9 = 72 MHz (HSE=8MHZ) * CH32V20x_D8-PLL configuration: PLLCLK = HSE/4 * 9 = 72 MHz (HSE=32MHZ) * CH32V20x_D8W-PLL configuration: PLLCLK = HSE/4 * 9 = 72 MHz (HSE=32MHZ) */ RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | - RCC_PLLMULL)); + RCC_PLLMULL)); RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL9); /* Enable PLL */ RCC->CTLR |= RCC_PLLON; /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { - } + while ((RCC->CTLR & RCC_PLLRDY) == 0) { + } /* Select PLL as system clock source */ RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); - RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; + RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { } - } - else - { - /* - * If HSE fails to start-up, the application will have wrong clock - * configuration. User can add here some code to deal with this error - */ + } else { + /* + * If HSE fails to start-up, the application will have wrong clock + * configuration. User can add here some code to deal with this error + */ } } @@ -535,23 +423,18 @@ static void SetSysClockTo96_HSE(void) RCC->CTLR |= ((uint32_t)RCC_HSEON); /* Wait till HSE is ready and if Time out is reached exit */ - do - { + do { HSEStatus = RCC->CTLR & RCC_HSERDY; StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + } while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); - if ((RCC->CTLR & RCC_HSERDY) != RESET) - { + if ((RCC->CTLR & RCC_HSERDY) != RESET) { HSEStatus = (uint32_t)0x01; - } - else - { + } else { HSEStatus = (uint32_t)0x00; } - if (HSEStatus == (uint32_t)0x01) - { + if (HSEStatus == (uint32_t)0x01) { /* HCLK = SYSCLK */ RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; /* PCLK2 = HCLK */ @@ -564,30 +447,26 @@ static void SetSysClockTo96_HSE(void) * CH32V20x_D8W-PLL configuration: PLLCLK = HSE/4 * 12 = 96 MHz (HSE=32MHZ) */ RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | - RCC_PLLMULL)); + RCC_PLLMULL)); RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL12); /* Enable PLL */ RCC->CTLR |= RCC_PLLON; /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { + while ((RCC->CTLR & RCC_PLLRDY) == 0) { } /* Select PLL as system clock source */ RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { } - } - else - { - /* - * If HSE fails to start-up, the application will have wrong clock - * configuration. User can add here some code to deal with this error - */ + } else { + /* + * If HSE fails to start-up, the application will have wrong clock + * configuration. User can add here some code to deal with this error + */ } } @@ -603,71 +482,62 @@ static void SetSysClockTo96_HSE(void) */ static void SetSysClockTo120_HSE(void) { - __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - RCC->CTLR |= ((uint32_t)RCC_HSEON); + RCC->CTLR |= ((uint32_t)RCC_HSEON); - /* Wait till HSE is ready and if Time out is reached exit */ - do - { - HSEStatus = RCC->CTLR & RCC_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + /* Wait till HSE is ready and if Time out is reached exit */ + do { + HSEStatus = RCC->CTLR & RCC_HSERDY; + StartUpCounter++; + } while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); - if((RCC->CTLR & RCC_HSERDY) != RESET) - { - HSEStatus = (uint32_t)0x01; - } - else - { - HSEStatus = (uint32_t)0x00; - } + if ((RCC->CTLR & RCC_HSERDY) != RESET) { + HSEStatus = (uint32_t)0x01; + } else { + HSEStatus = (uint32_t)0x00; + } - if(HSEStatus == (uint32_t)0x01) - { + if (HSEStatus == (uint32_t)0x01) { #if defined (CH32V20x_D8W) - RCC->CFGR0 |= (uint32_t)(3<<22); - /* HCLK = SYSCLK/2 */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV2; + RCC->CFGR0 |= (uint32_t)(3<<22); + /* HCLK = SYSCLK/2 */ + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV2; #else - /* HCLK = SYSCLK */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; + /* HCLK = SYSCLK */ + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; #endif - /* PCLK2 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; - /* PCLK1 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; - - /* CH32V20x_D6-PLL configuration: PLLCLK = HSE * 15 = 120 MHz (HSE=8MHZ) - * CH32V20x_D8-PLL configuration: PLLCLK = HSE/4 * 15 = 120 MHz (HSE=32MHZ) - * CH32V20x_D8W-PLL configuration: PLLCLK = HSE/2 * 15 = 240 MHz (HSE=32MHZ) - */ - RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | - RCC_PLLMULL)); - - RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL15); - - /* Enable PLL */ - RCC->CTLR |= RCC_PLLON; - /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { - } - /* Select PLL as system clock source */ - RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW)); - RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; - /* Wait till PLL is used as system clock source */ - while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { - } + /* PCLK2 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; + /* PCLK1 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; + + /* CH32V20x_D6-PLL configuration: PLLCLK = HSE * 15 = 120 MHz (HSE=8MHZ) + * CH32V20x_D8-PLL configuration: PLLCLK = HSE/4 * 15 = 120 MHz (HSE=32MHZ) + * CH32V20x_D8W-PLL configuration: PLLCLK = HSE/2 * 15 = 240 MHz (HSE=32MHZ) + */ + RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | + RCC_PLLMULL)); + + RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL15); + + /* Enable PLL */ + RCC->CTLR |= RCC_PLLON; + /* Wait till PLL is ready */ + while ((RCC->CTLR & RCC_PLLRDY) == 0) { } - else - { - /* - * If HSE fails to start-up, the application will have wrong clock - * configuration. User can add here some code to deal with this error - */ + /* Select PLL as system clock source */ + RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW)); + RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { } + } else { + /* + * If HSE fails to start-up, the application will have wrong clock + * configuration. User can add here some code to deal with this error + */ + } } #elif defined SYSCLK_FREQ_144MHz_HSE @@ -685,23 +555,18 @@ static void SetSysClockTo144_HSE(void) RCC->CTLR |= ((uint32_t)RCC_HSEON); /* Wait till HSE is ready and if Time out is reached exit */ - do - { + do { HSEStatus = RCC->CTLR & RCC_HSERDY; StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + } while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); - if ((RCC->CTLR & RCC_HSERDY) != RESET) - { + if ((RCC->CTLR & RCC_HSERDY) != RESET) { HSEStatus = (uint32_t)0x01; - } - else - { + } else { HSEStatus = (uint32_t)0x00; } - if (HSEStatus == (uint32_t)0x01) - { + if (HSEStatus == (uint32_t)0x01) { /* HCLK = SYSCLK */ RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; /* PCLK2 = HCLK */ @@ -714,30 +579,26 @@ static void SetSysClockTo144_HSE(void) * CH32V20x_D8W-PLL configuration: PLLCLK = HSE/4 * 18 = 144 MHz (HSE=32MHZ) */ RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | - RCC_PLLMULL)); + RCC_PLLMULL)); RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL18); /* Enable PLL */ RCC->CTLR |= RCC_PLLON; /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { + while ((RCC->CTLR & RCC_PLLRDY) == 0) { } /* Select PLL as system clock source */ RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { } - } - else - { - /* - * If HSE fails to start-up, the application will have wrong clock - * configuration. User can add here some code to deal with this error - */ + } else { + /* + * If HSE fails to start-up, the application will have wrong clock + * configuration. User can add here some code to deal with this error + */ } } @@ -752,33 +613,31 @@ static void SetSysClockTo144_HSE(void) */ static void SetSysClockTo48_HSI(void) { - EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; + EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; - /* HCLK = SYSCLK */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; - /* PCLK2 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; - /* PCLK1 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; + /* HCLK = SYSCLK */ + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; + /* PCLK2 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; + /* PCLK1 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; - /* PLL configuration: PLLCLK = HSI * 6 = 48 MHz */ - RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL)); + /* PLL configuration: PLLCLK = HSI * 6 = 48 MHz */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL)); - RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL6); + RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL6); - /* Enable PLL */ - RCC->CTLR |= RCC_PLLON; - /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { - } - /* Select PLL as system clock source */ - RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); - RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; - /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { - } + /* Enable PLL */ + RCC->CTLR |= RCC_PLLON; + /* Wait till PLL is ready */ + while ((RCC->CTLR & RCC_PLLRDY) == 0) { + } + /* Select PLL as system clock source */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); + RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { + } } #elif defined SYSCLK_FREQ_56MHz_HSI @@ -792,33 +651,31 @@ static void SetSysClockTo48_HSI(void) */ static void SetSysClockTo56_HSI(void) { - EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; + EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; - /* HCLK = SYSCLK */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; - /* PCLK2 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; - /* PCLK1 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; + /* HCLK = SYSCLK */ + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; + /* PCLK2 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; + /* PCLK1 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; - /* PLL configuration: PLLCLK = HSI * 7 = 48 MHz */ - RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL)); + /* PLL configuration: PLLCLK = HSI * 7 = 48 MHz */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL)); - RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL7); + RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL7); - /* Enable PLL */ - RCC->CTLR |= RCC_PLLON; - /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { - } - /* Select PLL as system clock source */ - RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); - RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; - /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { - } + /* Enable PLL */ + RCC->CTLR |= RCC_PLLON; + /* Wait till PLL is ready */ + while ((RCC->CTLR & RCC_PLLRDY) == 0) { + } + /* Select PLL as system clock source */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); + RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { + } } #elif defined SYSCLK_FREQ_72MHz_HSI @@ -832,33 +689,31 @@ static void SetSysClockTo56_HSI(void) */ static void SetSysClockTo72_HSI(void) { - EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; + EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; - /* HCLK = SYSCLK */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; - /* PCLK2 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; - /* PCLK1 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; + /* HCLK = SYSCLK */ + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; + /* PCLK2 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; + /* PCLK1 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; - /* PLL configuration: PLLCLK = HSI * 9 = 72 MHz */ - RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL)); + /* PLL configuration: PLLCLK = HSI * 9 = 72 MHz */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL)); - RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL9); + RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL9); - /* Enable PLL */ - RCC->CTLR |= RCC_PLLON; - /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { - } - /* Select PLL as system clock source */ - RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); - RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; - /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { - } + /* Enable PLL */ + RCC->CTLR |= RCC_PLLON; + /* Wait till PLL is ready */ + while ((RCC->CTLR & RCC_PLLRDY) == 0) { + } + /* Select PLL as system clock source */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); + RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { + } } @@ -873,33 +728,31 @@ static void SetSysClockTo72_HSI(void) */ static void SetSysClockTo96_HSI(void) { - EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; + EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; - /* HCLK = SYSCLK */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; - /* PCLK2 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV4; - /* PCLK1 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV4; + /* HCLK = SYSCLK */ + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; + /* PCLK2 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV4; + /* PCLK1 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV4; - /* PLL configuration: PLLCLK = HSI * 12 = 96 MHz */ - RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL)); + /* PLL configuration: PLLCLK = HSI * 12 = 96 MHz */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL)); - RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL12); + RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL12); - /* Enable PLL */ - RCC->CTLR |= RCC_PLLON; - /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { - } - /* Select PLL as system clock source */ - RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); - RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; - /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { - } + /* Enable PLL */ + RCC->CTLR |= RCC_PLLON; + /* Wait till PLL is ready */ + while ((RCC->CTLR & RCC_PLLRDY) == 0) { + } + /* Select PLL as system clock source */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); + RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { + } } @@ -914,34 +767,32 @@ static void SetSysClockTo96_HSI(void) */ static void SetSysClockTo120_HSI(void) { - EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; + EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; - /* HCLK = SYSCLK */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; - /* PCLK2 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; - /* PCLK1 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; + /* HCLK = SYSCLK */ + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; + /* PCLK2 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; + /* PCLK1 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; - /* PLL configuration: PLLCLK = HSI * 15 = 120 MHz */ - RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | - RCC_PLLMULL)); + /* PLL configuration: PLLCLK = HSI * 15 = 120 MHz */ + RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | + RCC_PLLMULL)); - RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL15); + RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL15); - /* Enable PLL */ - RCC->CTLR |= RCC_PLLON; - /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { - } - /* Select PLL as system clock source */ - RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW)); - RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; - /* Wait till PLL is used as system clock source */ - while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { - } + /* Enable PLL */ + RCC->CTLR |= RCC_PLLON; + /* Wait till PLL is ready */ + while ((RCC->CTLR & RCC_PLLRDY) == 0) { + } + /* Select PLL as system clock source */ + RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW)); + RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { + } } #elif defined SYSCLK_FREQ_144MHz_HSI @@ -954,33 +805,31 @@ static void SetSysClockTo120_HSI(void) */ static void SetSysClockTo144_HSI(void) { - EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; + EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; - /* HCLK = SYSCLK */ - RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; - /* PCLK2 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; - /* PCLK1 = HCLK */ - RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; + /* HCLK = SYSCLK */ + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; + /* PCLK2 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; + /* PCLK1 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; - /* PLL configuration: PLLCLK = HSI * 18 = 144 MHz */ - RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL)); + /* PLL configuration: PLLCLK = HSI * 18 = 144 MHz */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL)); - RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL18); + RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL18); - /* Enable PLL */ - RCC->CTLR |= RCC_PLLON; - /* Wait till PLL is ready */ - while((RCC->CTLR & RCC_PLLRDY) == 0) - { - } - /* Select PLL as system clock source */ - RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); - RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; - /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) - { - } + /* Enable PLL */ + RCC->CTLR |= RCC_PLLON; + /* Wait till PLL is ready */ + while ((RCC->CTLR & RCC_PLLRDY) == 0) { + } + /* Select PLL as system clock source */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW)); + RCC->CFGR0 |= (uint32_t)RCC_SW_PLL; + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08) { + } } diff --git a/bl_update/ldscript_bl.ld b/bl_update/ldscript_bl.ld index 8f5f4eb5..b581eb9a 100644 --- a/bl_update/ldscript_bl.ld +++ b/bl_update/ldscript_bl.ld @@ -123,6 +123,13 @@ SECTIONS . = ALIGN(8); } >RAM + /* Ensure flash content is padded to 32 bytes with 0xFF */ + .padding : + { + . = ALIGN(32); + BYTE(0xFF); . = ALIGN(32); + } >FLASH + /* Remove information from the standard libraries */ /DISCARD/ : { diff --git a/bl_update/ldscript_bl_CAN.ld b/bl_update/ldscript_bl_CAN.ld new file mode 100644 index 00000000..39b9d2ea --- /dev/null +++ b/bl_update/ldscript_bl_CAN.ld @@ -0,0 +1,144 @@ +/* + linker file for AM32 bootloader updater +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +_estack = 0x20001000; /* end of RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +FLASH (rx) : ORIGIN = 0x08004000, LENGTH = 20K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 4K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + KEEP(*(.app_signature)) + . = 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 + + /* Ensure flash content is padded to 32 bytes with 0xFF */ + .padding : + { + . = ALIGN(32); + BYTE(0xFF); . = ALIGN(32); + } >FLASH + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/bl_update/main.c b/bl_update/main.c index 98298639..5c10cb0e 100644 --- a/bl_update/main.c +++ b/bl_update/main.c @@ -20,10 +20,40 @@ // dummy pin and port so we can re-use blutil.h static GPIO_PORT_TYPE input_port; static uint32_t input_pin; -#define FIRMWARE_RELATIVE_START 0x1000 #define MCU_FLASH_START 0x08000000 + +#if !DRONECAN_SUPPORT +#define FIRMWARE_RELATIVE_START 0x1000 +#else + +#define FIRMWARE_RELATIVE_START 0x4000 + +#define APP_SIGNATURE_MAGIC1 0x68f058e6 +#define APP_SIGNATURE_MAGIC2 0xafcee5a0 + +/* + application signature, filled in by set_app_signature.py + */ +const struct { + uint32_t magic1; + uint32_t magic2; + uint32_t fwlen; // total fw length in bytes + uint32_t crc1; // crc32 up to start of app_signature + uint32_t crc2; // crc32 from end of app_signature to end of fw + char mcu[16]; + uint32_t unused[2]; +} app_signature __attribute__((section(".app_signature"))) = { + .magic1 = APP_SIGNATURE_MAGIC1, + .magic2 = APP_SIGNATURE_MAGIC2, + .fwlen = 0, + .crc1 = 0, + .crc2 = 0, + .mcu = AM32_MCU, +}; +#endif + /* use stringize to construct an include of the right bootloader header */ @@ -32,55 +62,57 @@ static uint32_t input_pin; #define str(x) xstr(x) #include str(bl_header) +#define PORT_LETTER 0 // dummy + #include static void delayMicroseconds(uint32_t micros) { - while (micros > 0) { - uint32_t us = micros>10000?10000:micros; - bl_timer_reset(); - while (bl_timer_us() < us) ; - micros -= us; - } + while (micros > 0) { + uint16_t us = micros>10000?10000:micros; + const uint16_t us_start = bl_timer_us(); + while ((uint16_t)(bl_timer_us() - us_start) < us) ; + micros -= us; + } } static void flash_bootloader(void) { - uint32_t length = sizeof(bl_image); - uint32_t address = MCU_FLASH_START; - const uint8_t *bl = &bl_image[0]; - - while (length > 0) { - uint32_t chunk = 256; - if (chunk > length) { - chunk = length; - } - // loop until the flash succeeds. We expect it to pass - // first time, so this is paranoia - while (!save_flash_nolib(bl, chunk, address)) { - } - length -= chunk; - address += chunk; - bl += chunk; + uint32_t length = sizeof(bl_image); + uint32_t address = MCU_FLASH_START; + const uint8_t *bl = &bl_image[0]; + + while (length > 0) { + uint32_t chunk = 256; + if (chunk > length) { + chunk = length; + } + // loop until the flash succeeds. We expect it to pass + // first time, so this is paranoia + while (!save_flash_nolib(bl, chunk, address)) { } + length -= chunk; + address += chunk; + bl += chunk; + } } int main(void) { - bl_clock_config(); - bl_timer_init(); + bl_clock_config(); + bl_timer_init(); - // don't risk erasing the bootloader if it already matches - if (memcmp((const void*)MCU_FLASH_START, bl_image, sizeof(bl_image)) != 0) { - // give 1.5s for debugger to attach - delayMicroseconds(1500000); + // don't risk erasing the bootloader if it already matches + if (memcmp((const void*)MCU_FLASH_START, bl_image, sizeof(bl_image)) != 0) { + // give 1.5s for debugger to attach + delayMicroseconds(1500000); - // do the flash - flash_bootloader(); - } + // do the flash + flash_bootloader(); + } - // and reset - NVIC_SystemReset(); + // and reset + NVIC_SystemReset(); - return 0; + return 0; } diff --git a/bl_update/set_app_signature.py b/bl_update/set_app_signature.py new file mode 100755 index 00000000..aa52d2f5 --- /dev/null +++ b/bl_update/set_app_signature.py @@ -0,0 +1,85 @@ +#!/usr/bin/env python3 +''' +set application signature in bin and elf files +''' + +import struct +import sys + +APP_SIGNATURE_MAGIC1 = 0x68f058e6 +APP_SIGNATURE_MAGIC2 = 0xafcee5a0 + +def crc32(buf): + '''crc32 implementation''' + crc = 0 + size = len(buf) + for i in range(size): + byte = buf[i] + crc ^= byte + for _ in range(8): + mask = -(crc & 1) + crc >>= 1 + crc ^= (0xEDB88320 & mask) + return crc + +# Example usage: +# buf = bytearray([0x31, 0x32, 0x33, 0x34]) # Sample input +# result = crc32(buf, len(buf)) +# print(f"CRC32: {hex(result)}") + +def set_app_descriptor(bin_file, elf_file): + '''setup app descriptor in bin file and elf file''' + descriptor = struct.pack(" +#include +#include +#include +#include +#include "sys_can.h" +#include +#include +#include + +// include the headers for the generated DroneCAN messages from the +// dronecan_dsdlc compiler +#include "dsdl_generated/dronecan_msgs.h" + +#ifndef PREFERRED_NODE_ID +#define PREFERRED_NODE_ID 0 +#endif + +#ifndef CANARD_POOL_SIZE +#define CANARD_POOL_SIZE 4096 +#endif + +#ifndef DRONECAN_DEBUG +#define DRONECAN_DEBUG 0 +#endif + +// assume that main fw starts at 16k +#define MAIN_FW_START_ADDR 0x08004000 + +static CanardInstance canard; +static uint8_t canard_memory_pool[CANARD_POOL_SIZE]; + +#ifndef MCU_FLASH_START +#define MCU_FLASH_START 0x08000000 +#endif + +#if BOARD_FLASH_SIZE == 128 +#define EEPROM_START_ADD (MCU_FLASH_START+0x1f800) +#else +#error "Only 128K flash size supported for DroneCAN" +#endif + +/* + keep the state for firmware update +*/ +static struct { + char path[256]; + uint8_t node_id; + uint8_t transfer_id; + uint32_t last_read_ms; + uint32_t offset; +} fwupdate; + +static bool have_raw_command; + +// some convenience macros +#define MIN(a,b) ((a)<(b)?(a):(b)) +#define ARRAY_SIZE(x) (sizeof(x)/sizeof(x[0])) + +/* + hold our node status as a static variable. It will be updated on any errors +*/ +static struct uavcan_protocol_NodeStatus node_status; + +enum boot_code { + CHECK_FW_OK = 0, + FAIL_REASON_NO_APP_SIG = 10, + FAIL_REASON_BAD_LENGTH_APP = 11, + FAIL_REASON_BAD_BOARD_ID = 12, + FAIL_REASON_BAD_CRC = 13, + FAIL_REASON_IN_UPDATE = 14, + FAIL_REASON_WATCHDOG = 15, + FAIL_REASON_BAD_LENGTH_DESCRIPTOR = 16, + FAIL_REASON_BAD_FIRMWARE_SIGNATURE = 17, + FAIL_REASON_VERIFICATION = 18, + FAIL_REASON_NO_SIGNAL = 19, +}; + +#define APP_SIGNATURE_MAGIC1 0x68f058e6 +#define APP_SIGNATURE_MAGIC2 0xafcee5a0 + +/* + application signature + */ +struct app_signature { + uint32_t magic1; + uint32_t magic2; + uint32_t fwlen; // total fw length in bytes + uint32_t crc1; // crc32 up to start of app_signature + uint32_t crc2; // crc32 from end of app_signature to end of fw + char mcu[16]; + uint32_t unused[2]; +}; + +/* + simple 16 bit random number generator +*/ +static uint16_t get_random16(void) +{ + static uint32_t m_z = 1234; + static uint32_t m_w = 76542; + m_z = 36969 * (m_z & 0xFFFFu) + (m_z >> 16); + m_w = 18000 * (m_w & 0xFFFFu) + (m_w >> 16); + return ((m_z << 16) + m_w) & 0xFFFF; +} + +/* + get a 64 bit monotonic timestamp in microseconds since start. This + is platform specific + + NOTE: this should be in functions.c +*/ +static uint64_t micros64(void) +{ + static uint64_t base_us; + static uint16_t last_cnt; + uint16_t cnt = bl_timer_us(); + if (cnt < last_cnt) { + base_us += 0x10000; + } + last_cnt = cnt; + return base_us + cnt; +} + +/* + get monotonic time in milliseconds since startup +*/ +static uint32_t millis32(void) +{ + return micros64() / 1000ULL; +} + +/* + default settings, based on public/assets/eeprom_default.bin in AM32 configurator + */ +static const uint8_t default_settings[] = { + 0x01, 0x02, BOOTLOADER_VERSION, 0x01, 0x23, 0x4e, 0x45, 0x4f, 0x45, 0x53, 0x43, 0x20, 0x66, 0x30, 0x35, 0x31, + 0x20, 0x00, 0x00, 0x00, 0x01, 0x01, 0x01, 0x02, 0x18, 0x64, 0x37, 0x0e, 0x00, 0x00, 0x05, 0x00, + 0x80, 0x80, 0x80, 0x32, 0x00, 0x32, 0x00, 0x00, 0x0f, 0x0a, 0x0a, 0x8d, 0x66, 0x06, 0x00, 0x00 +}; + +// crc32 implementation, slow method for small flash cost +static uint32_t crc32(const uint8_t *buf, uint32_t size) +{ + uint32_t crc = 0; + while (size--) { + const uint8_t byte = *buf++; + crc ^= byte; + for (uint8_t i=0; i<8; i++) { + const uint32_t mask = -(crc & 1); + crc >>= 1; + crc ^= (0xEDB88320 & mask); + } + } + return crc; +} + +// print to CAN LogMessage for debugging +static void can_print(const char *s) +{ + struct uavcan_protocol_debug_LogMessage pkt; + memset(&pkt, 0, sizeof(pkt)); + + uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE]; + pkt.text.len = strlen(s); + memcpy(pkt.text.data, s, pkt.text.len); + + uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer); + static uint8_t logmsg_transfer_id; + + canardBroadcast(&canard, + UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE, + UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID, + &logmsg_transfer_id, + CANARD_TRANSFER_PRIORITY_LOW, + buffer, len); +} + +/* + handle parameter executeopcode request +*/ +static void handle_param_ExecuteOpcode(CanardInstance* ins, CanardRxTransfer* transfer) +{ + struct uavcan_protocol_param_ExecuteOpcodeRequest req; + if (uavcan_protocol_param_ExecuteOpcodeRequest_decode(transfer, &req)) { + return; + } + struct uavcan_protocol_param_ExecuteOpcodeResponse pkt; + memset(&pkt, 0, sizeof(pkt)); + + pkt.ok = false; + + if (req.opcode == UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_ERASE) { + can_print("resetting to defaults"); + save_flash_nolib(default_settings, sizeof(default_settings), EEPROM_START_ADD); + pkt.ok = true; + } + + + uint8_t buffer[UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE]; + uint16_t total_size = uavcan_protocol_param_ExecuteOpcodeResponse_encode(&pkt, buffer); + + canardRequestOrRespond(ins, + transfer->source_node_id, + UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE, + UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID, + &transfer->transfer_id, + transfer->priority, + CanardResponse, + &buffer[0], + total_size); +} + +/* + handle RestartNode request +*/ +static void handle_RestartNode(CanardInstance* ins, CanardRxTransfer* transfer) +{ + set_rtc_backup_register(0, 0); + // reboot the ESC + NVIC_SystemReset(); +} + +/* + handle a GetNodeInfo request +*/ +static void handle_GetNodeInfo(CanardInstance *ins, CanardRxTransfer *transfer) +{ + uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE]; + struct uavcan_protocol_GetNodeInfoResponse pkt; + + memset(&pkt, 0, sizeof(pkt)); + + node_status.uptime_sec = micros64() / 1000000ULL; + pkt.status = node_status; + + // fill in your major and minor firmware version + pkt.software_version.major = BOOTLOADER_VERSION; + pkt.software_version.minor = 0; + pkt.software_version.optional_field_flags = 0; + pkt.software_version.vcs_commit = 0; // should put git hash in here + + // should fill in hardware version + pkt.hardware_version.major = 2; + pkt.hardware_version.minor = 3; + + sys_can_getUniqueID(pkt.hardware_version.unique_id); + + strncpy((char*)pkt.name.data, "AM32_BOOTLOADER_" AM32_MCU, sizeof(pkt.name.data)); + pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data)); + + uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer); + + canardRequestOrRespond(ins, + transfer->source_node_id, + UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE, + UAVCAN_PROTOCOL_GETNODEINFO_ID, + &transfer->transfer_id, + transfer->priority, + CanardResponse, + &buffer[0], + total_size); +} + +/* + handle a BeginFirmwareUpdate request from a management tool like + DroneCAN GUI tool or MissionPlanner + */ +static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* transfer) +{ + /* + decode the request + */ + struct uavcan_protocol_file_BeginFirmwareUpdateRequest req; + if (uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(transfer, &req)) { + return; + } + + /* + check for a repeated BeginFirmwareUpdateRequest + */ + if (fwupdate.node_id == transfer->source_node_id && + memcmp(fwupdate.path, req.image_file_remote_path.path.data, req.image_file_remote_path.path.len) == 0) { + /* ignore duplicate request */ + return; + } + + fwupdate.offset = 0; + fwupdate.node_id = transfer->source_node_id; + strncpy(fwupdate.path, (char*)req.image_file_remote_path.path.data, req.image_file_remote_path.path.len); + + uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE]; + struct uavcan_protocol_file_BeginFirmwareUpdateResponse reply; + memset(&reply, 0, sizeof(reply)); + reply.error = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK; + + uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer); + + canardRequestOrRespond(ins, + transfer->source_node_id, + UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE, + UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID, + &transfer->transfer_id, + transfer->priority, + CanardResponse, + &buffer[0], + total_size); + + can_print("Started firmware update"); +} + +/* + send a read for a firmware update. This asks the client (firmware + server) for a piece of the new firmware + */ +static void send_firmware_read(void) +{ + uint32_t now = millis32(); + if (fwupdate.last_read_ms != 0 && now - fwupdate.last_read_ms < 750) { + // the server may still be responding + return; + } + fwupdate.last_read_ms = now; + + uint8_t buffer[UAVCAN_PROTOCOL_FILE_READ_REQUEST_MAX_SIZE]; + + struct uavcan_protocol_file_ReadRequest pkt; + memset(&pkt, 0, sizeof(pkt)); + + pkt.path.path.len = strlen((const char *)fwupdate.path); + pkt.offset = fwupdate.offset; + memcpy(pkt.path.path.data, fwupdate.path, pkt.path.path.len); + + uint16_t total_size = uavcan_protocol_file_ReadRequest_encode(&pkt, buffer); + + canardRequestOrRespond(&canard, + fwupdate.node_id, + UAVCAN_PROTOCOL_FILE_READ_SIGNATURE, + UAVCAN_PROTOCOL_FILE_READ_ID, + &fwupdate.transfer_id, + CANARD_TRANSFER_PRIORITY_HIGH, + CanardRequest, + &buffer[0], + total_size); +} + +/* + handle response to send_firmware_read() + */ +static void handle_file_read_response(CanardInstance* ins, CanardRxTransfer* transfer) +{ + if ((transfer->transfer_id+1)%32 != fwupdate.transfer_id || + transfer->source_node_id != fwupdate.node_id) { + /* not for us */ + can_print("Firmware update: not for us"); + return; + } + struct uavcan_protocol_file_ReadResponse pkt; + if (uavcan_protocol_file_ReadResponse_decode(transfer, &pkt)) { + /* bad packet */ + can_print("Firmware update: bad packet"); + return; + } + if (pkt.error.value != UAVCAN_PROTOCOL_FILE_ERROR_OK) { + if (fwupdate.offset == 0) { + // MissionPlanner does this sometimes, ignore + return; + } + /* read failed */ + fwupdate.node_id = 0; + can_print("Firmware update read failure"); + return; + } + + uint32_t len = pkt.data.len; + len = (len+7U) & ~7U; + save_flash_nolib(pkt.data.data, len, (uint32_t)MAIN_FW_START_ADDR + fwupdate.offset); + + fwupdate.offset += pkt.data.len; + + if (pkt.data.len < 256) { + /* firmware updare done */ + can_print("Firmwate update complete"); + fwupdate.node_id = 0; + set_rtc_backup_register(0, 0); + NVIC_SystemReset(); + return; + } + + /* trigger a new read */ + fwupdate.last_read_ms = 0; + send_firmware_read(); + + DroneCAN_processTxQueue(); +} + +/* + data for dynamic node allocation process +*/ +static struct { + uint32_t send_next_node_id_allocation_request_at_ms; + uint32_t node_id_allocation_unique_id_offset; +} DNA; + +/* + handle a DNA allocation packet +*/ +static void handle_DNA_Allocation(CanardInstance *ins, CanardRxTransfer *transfer) +{ + if (canardGetLocalNodeID(&canard) != CANARD_BROADCAST_NODE_ID) { + // already allocated + return; + } + + // Rule C - updating the randomized time interval + DNA.send_next_node_id_allocation_request_at_ms = + millis32() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS + + (get_random16() % UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS); + + if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID) { + DNA.node_id_allocation_unique_id_offset = 0; + return; + } + + // Copying the unique ID from the message + struct uavcan_protocol_dynamic_node_id_Allocation msg; + + if (uavcan_protocol_dynamic_node_id_Allocation_decode(transfer, &msg)) { + /* bad packet */ + return; + } + + // Obtaining the local unique ID + uint8_t my_unique_id[sizeof(msg.unique_id.data)]; + sys_can_getUniqueID(my_unique_id); + + // Matching the received UID against the local one + if (memcmp(msg.unique_id.data, my_unique_id, msg.unique_id.len) != 0) { + DNA.node_id_allocation_unique_id_offset = 0; + // No match, return + return; + } + + if (msg.unique_id.len < sizeof(msg.unique_id.data)) { + // The allocator has confirmed part of unique ID, switching to + // the next stage and updating the timeout. + DNA.node_id_allocation_unique_id_offset = msg.unique_id.len; + DNA.send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS; + + } else { + // Allocation complete - copying the allocated node ID from the message + canardSetLocalNodeID(ins, msg.node_id); + } +} + +/* + ask for a dynamic node allocation +*/ +static void request_DNA() +{ + const uint32_t now = millis32(); + static uint8_t node_id_allocation_transfer_id = 0; + + DNA.send_next_node_id_allocation_request_at_ms = + now + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS + + (get_random16() % UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS); + + // Structure of the request is documented in the DSDL definition + // See http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation + uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1]; + allocation_request[0] = (uint8_t)(PREFERRED_NODE_ID << 1U); + + if (DNA.node_id_allocation_unique_id_offset == 0) { + allocation_request[0] |= 1; // First part of unique ID + } + + uint8_t my_unique_id[16]; + sys_can_getUniqueID(my_unique_id); + + static const uint8_t MaxLenOfUniqueIDInRequest = 6; + uint8_t uid_size = (uint8_t)(16 - DNA.node_id_allocation_unique_id_offset); + + if (uid_size > MaxLenOfUniqueIDInRequest) { + uid_size = MaxLenOfUniqueIDInRequest; + } + + memmove(&allocation_request[1], &my_unique_id[DNA.node_id_allocation_unique_id_offset], uid_size); + + // Broadcasting the request + canardBroadcast(&canard, + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE, + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID, + &node_id_allocation_transfer_id, + CANARD_TRANSFER_PRIORITY_LOW, + &allocation_request[0], + (uint16_t) (uid_size + 1)); + + // Preparing for timeout; if response is received, this value will be updated from the callback. + DNA.node_id_allocation_unique_id_offset = 0; +} + +/* + This callback is invoked by the library when a new message or request or response is received. +*/ +static void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer) +{ + // switch on data type ID to pass to the right handler function + if (transfer->transfer_type == CanardTransferTypeRequest) { + // check if we want to handle a specific service request + switch (transfer->data_type_id) { + case UAVCAN_PROTOCOL_GETNODEINFO_ID: { + handle_GetNodeInfo(ins, transfer); + break; + } + case UAVCAN_PROTOCOL_RESTARTNODE_ID: { + handle_RestartNode(ins, transfer); + break; + } + case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID: { + handle_begin_firmware_update(ins, transfer); + break; + } + case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID: { + handle_param_ExecuteOpcode(ins, transfer); + break; + } + } + } + if (transfer->transfer_type == CanardTransferTypeResponse) { + switch (transfer->data_type_id) { + case UAVCAN_PROTOCOL_FILE_READ_ID: + handle_file_read_response(ins, transfer); + break; + } + } + if (transfer->transfer_type == CanardTransferTypeBroadcast) { + // check if we want to handle a specific broadcast message + switch (transfer->data_type_id) { + case UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID: { + handle_DNA_Allocation(ins, transfer); + break; + } + } + } +} + + +/* + This callback is invoked by the library when it detects beginning of a new transfer on the bus that can be received + by the local node. + If the callback returns true, the library will receive the transfer. + If the callback returns false, the library will ignore the transfer. + All transfers that are addressed to other nodes are always ignored. + + This function must fill in the out_data_type_signature to be the signature of the message. +*/ +static bool shouldAcceptTransfer(const CanardInstance *ins, + uint64_t *out_data_type_signature, + uint16_t data_type_id, + CanardTransferType transfer_type, + uint8_t source_node_id) +{ + if (transfer_type == CanardTransferTypeRequest) { + // check if we want to handle a specific service request + switch (data_type_id) { + case UAVCAN_PROTOCOL_GETNODEINFO_ID: { + *out_data_type_signature = UAVCAN_PROTOCOL_GETNODEINFO_REQUEST_SIGNATURE; + return true; + } + case UAVCAN_PROTOCOL_RESTARTNODE_ID: { + *out_data_type_signature = UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE; + return true; + } + case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID: { + *out_data_type_signature = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE; + return true; + } + case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID: { + *out_data_type_signature = UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE; + return true; + } + } + } + if (transfer_type == CanardTransferTypeResponse) { + // check if we want to handle a specific service request + switch (data_type_id) { + case UAVCAN_PROTOCOL_FILE_READ_ID: + *out_data_type_signature = UAVCAN_PROTOCOL_FILE_READ_SIGNATURE; + return true; + } + } + if (transfer_type == CanardTransferTypeBroadcast) { + // see if we want to handle a specific broadcast packet + switch (data_type_id) { + case UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID: { + *out_data_type_signature = UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE; + return true; + } + case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID: { + // we are receiving RawCommand, we should boot to the main firmware + have_raw_command = true; + } + } + } + // we don't want any other messages + return false; +} + +/* + send the 1Hz NodeStatus message. This is what allows a node to show + up in the DroneCAN GUI tool and in the flight controller logs +*/ +static void send_NodeStatus(void) +{ + uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE]; + + node_status.uptime_sec = micros64() / 1000000ULL; + node_status.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; + node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE; + node_status.sub_mode = 0; + + /* + when doing a firmware update put the size in kbytes in VSSC so + the user can see how far it has reached + */ + if (fwupdate.node_id != 0) { + node_status.vendor_specific_status_code = fwupdate.offset / 1024; + node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_SOFTWARE_UPDATE; + } + + uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer); + + // we need a static variable for the transfer ID. This is + // incremeneted on each transfer, allowing for detection of packet + // loss + static uint8_t transfer_id; + + canardBroadcast(&canard, + UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, + UAVCAN_PROTOCOL_NODESTATUS_ID, + &transfer_id, + CANARD_TRANSFER_PRIORITY_LOW, + buffer, + len); +} + +/* + This function is called at 1 Hz rate from the main loop. +*/ +static void process1HzTasks(uint64_t timestamp_usec) +{ + /* + Purge transfers that are no longer transmitted. This can free up some memory + */ + canardCleanupStaleTransfers(&canard, timestamp_usec); + + /* + Transmit the node status message + */ + send_NodeStatus(); +} + +/* + receive one frame, only called from interrupt context +*/ +void DroneCAN_receiveFrame(void) +{ + CanardCANFrame rx_frame = {0}; + while (sys_can_receive(&rx_frame) > 0) { + canardHandleRxFrame(&canard, &rx_frame, micros64()); + } +} + +/* + handle a frame from interrupt context +*/ +void DroneCAN_handleFrame(CanardCANFrame *frame) +{ + canardHandleRxFrame(&canard, frame, micros64()); +} + +/* + Transmits all frames from the TX queue +*/ +void DroneCAN_processTxQueue(void) +{ + for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;) { + const int16_t tx_res = sys_can_transmit(txf); + if (tx_res == 0) { + // no space, stop trying + break; + } + // success or error, remove frame + canardPopTxQueue(&canard); + } +} + +//#pragma GCC optimize("O0") + +static void DroneCAN_Startup(void) +{ + canardInit(&canard, + canard_memory_pool, // Raw memory chunk used for dynamic allocation + sizeof(canard_memory_pool), + onTransferReceived, // Callback, see CanardOnTransferReception + shouldAcceptTransfer, // Callback, see CanardShouldAcceptTransfer + NULL); + + /* + if doing fw update get node ID from main firmware via RTC backup + register + */ + uint8_t node_id = 0; + const uint32_t rtc0 = get_rtc_backup_register(0); + if ((rtc0 & 0xFFFFU) == RTC_BKUP0_FWUPDATE) { + node_id = rtc0 >> 24; + uint8_t src_node = (rtc0 >> 16) & 0xFF; + uint32_t path[2]; + path[0] = get_rtc_backup_register(1); + path[1] = get_rtc_backup_register(2); + if (path[0] != 0 && src_node <= 127) { + // we have update path, can start immediately + fwupdate.node_id = src_node; + memset(fwupdate.path, 0, sizeof(fwupdate.path)); + memcpy(fwupdate.path, path, sizeof(path)); + } + } + + if (node_id == 0) { + // check for valid node ID in settings + const uint8_t *eeprom = (const uint8_t *)EEPROM_START_ADD; + if (eeprom[0] == 1 && eeprom[176] <= 127) { + node_id = eeprom[176]; + } + } + + canardSetLocalNodeID(&canard, node_id); + + // initialise low level CAN peripheral hardware + sys_can_init(); + +#if 0 + if (fwupdate.node_id != 0) { + can_print("fwupdate startup"); + can_print(fwupdate.path); + } else { + can_print("bootloader startup"); + } +#endif +} + +/* + handle DroneCAN packets. Return true if we are ready to boot the main firmware + */ +bool DroneCAN_update() +{ + static uint64_t next_1hz_service_at; + static bool done_startup; + if (!done_startup) { + done_startup = true; + DroneCAN_Startup(); + } + + sys_can_disable_IRQ(); + + DroneCAN_processTxQueue(); + + // see if we are still doing DNA + if (canardGetLocalNodeID(&canard) == CANARD_BROADCAST_NODE_ID) { + // we're still waiting for a DNA allocation of our node ID + if (millis32() > DNA.send_next_node_id_allocation_request_at_ms) { + request_DNA(); + } + sys_can_enable_IRQ(); + return false; + } + + const uint64_t ts = micros64(); + + if (ts >= next_1hz_service_at) { + next_1hz_service_at += 1000000ULL; + process1HzTasks(ts); + } + + if (fwupdate.node_id != 0) { + send_firmware_read(); + } + + DroneCAN_processTxQueue(); + + sys_can_enable_IRQ(); + + return DroneCAN_boot_ok(); +} + +/* + implementation of memmem() for finding app signature + */ +static void *memmem(const void *haystack, size_t haystacklen, const void *needle, size_t needlelen) +{ + while (haystacklen >= needlelen) { + char *p = (char *)memchr(haystack, *(const char *)needle, haystacklen-(needlelen-1)); + if (!p) { + return NULL; + } + if (memcmp(p, needle, needlelen) == 0) { + return p; + } + haystack = p+1; + haystacklen -= (p - (const char *)haystack) + 1; + } + return NULL; +} + +static void set_reason(enum boot_code code, const char *reason) +{ + static uint64_t last_msg_us; + node_status.vendor_specific_status_code = code; + const uint64_t now_us = micros64(); + if (now_us - last_msg_us > 5000000UL) { + last_msg_us = now_us; + can_print(reason); + } +} + +/* + see if we are OK to boot + */ +bool DroneCAN_boot_ok(void) +{ + if (fwupdate.node_id != 0) { + // in fw update + return false; + } + if ((get_rtc_backup_register(0) & 0xFFFFU) == RTC_BKUP0_FWUPDATE) { + // waiting for firmware update + node_status.vendor_specific_status_code = FAIL_REASON_IN_UPDATE; + return false; + } + /* + check application signature + */ + uint32_t sig[2] = { APP_SIGNATURE_MAGIC1, APP_SIGNATURE_MAGIC2 }; + const uint32_t app_max_len = (128-18)*1024; + const uint8_t *fw_base = (const uint8_t *)MAIN_FW_START_ADDR; + struct app_signature *appsig = memmem(fw_base, app_max_len, sig, sizeof(sig)); + if (appsig == NULL || (((uint32_t)appsig) & 3) != 0) { + set_reason(FAIL_REASON_NO_APP_SIG, "no app signature"); + return false; + } + if (appsig->fwlen > app_max_len) { + set_reason(FAIL_REASON_BAD_LENGTH_APP, "bad app length"); + return false; + } + if (memcmp(AM32_MCU, appsig->mcu, strlen(AM32_MCU)) != 0) { + set_reason(FAIL_REASON_BAD_BOARD_ID, "bad board type"); + return false; + } + const uint8_t *appsigend = (const uint8_t *)(appsig+1); + const uint32_t crc1 = crc32(fw_base, (uint32_t)((uint8_t*)appsig - fw_base)); + const uint32_t crc2 = crc32(appsigend, appsig->fwlen - (uint32_t)(appsigend - fw_base)); + if (appsig->crc1 != crc1 || + appsig->crc2 != crc2) { + set_reason(FAIL_REASON_BAD_CRC, "bad firmware CRC"); + return false; + } + + if (!have_raw_command) { + set_reason(FAIL_REASON_BAD_CRC, "no signal"); + return false; + } + + node_status.vendor_specific_status_code = CHECK_FW_OK; + + const uint8_t eeprom_magic = *(uint8_t*)(EEPROM_START_ADD); + if (eeprom_magic == 0 || eeprom_magic == 0xff) { + can_print("resetting to defaults"); + save_flash_nolib(default_settings, sizeof(default_settings), EEPROM_START_ADD); + } + if (eeprom_magic != 0x01) { + set_reason(FAIL_REASON_BAD_FIRMWARE_SIGNATURE, "bad eeprom header"); + } + + return true; +} + +#endif // DRONECAN_SUPPORT diff --git a/bootloader/DroneCAN/DroneCAN.h b/bootloader/DroneCAN/DroneCAN.h new file mode 100644 index 00000000..2e865bf2 --- /dev/null +++ b/bootloader/DroneCAN/DroneCAN.h @@ -0,0 +1,10 @@ +#pragma once + +#include + +#if DRONECAN_SUPPORT +void DroneCAN_Init(void); +bool DroneCAN_update(); +bool DroneCAN_boot_ok(void); + +#endif // DRONECAN_SUPPORT diff --git a/bootloader/DroneCAN/dsdl_generated/dronecan_msgs.h b/bootloader/DroneCAN/dsdl_generated/dronecan_msgs.h new file mode 100644 index 00000000..97830f1c --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/dronecan_msgs.h @@ -0,0 +1,57 @@ +#pragma once +#include "uavcan.equipment.esc.RawCommand.h" +#include "uavcan.equipment.esc.RPMCommand.h" +#include "uavcan.equipment.esc.StatusExtended.h" +#include "uavcan.equipment.esc.Status.h" +#include "uavcan.equipment.safety.ArmingStatus.h" +#include "uavcan.protocol.debug.KeyValue.h" +#include "uavcan.protocol.debug.LogLevel.h" +#include "uavcan.protocol.debug.LogMessage.h" +#include "uavcan.protocol.dynamic_node_id.Allocation.h" +#include "uavcan.protocol.dynamic_node_id.server.AppendEntries.h" +#include "uavcan.protocol.dynamic_node_id.server.AppendEntries_req.h" +#include "uavcan.protocol.dynamic_node_id.server.AppendEntries_res.h" +#include "uavcan.protocol.dynamic_node_id.server.Discovery.h" +#include "uavcan.protocol.dynamic_node_id.server.Entry.h" +#include "uavcan.protocol.dynamic_node_id.server.RequestVote.h" +#include "uavcan.protocol.dynamic_node_id.server.RequestVote_req.h" +#include "uavcan.protocol.dynamic_node_id.server.RequestVote_res.h" +#include "uavcan.protocol.file.BeginFirmwareUpdate.h" +#include "uavcan.protocol.file.BeginFirmwareUpdate_req.h" +#include "uavcan.protocol.file.BeginFirmwareUpdate_res.h" +#include "uavcan.protocol.file.Delete.h" +#include "uavcan.protocol.file.Delete_req.h" +#include "uavcan.protocol.file.Delete_res.h" +#include "uavcan.protocol.file.EntryType.h" +#include "uavcan.protocol.file.Error.h" +#include "uavcan.protocol.file.GetDirectoryEntryInfo.h" +#include "uavcan.protocol.file.GetDirectoryEntryInfo_req.h" +#include "uavcan.protocol.file.GetDirectoryEntryInfo_res.h" +#include "uavcan.protocol.file.GetInfo.h" +#include "uavcan.protocol.file.GetInfo_req.h" +#include "uavcan.protocol.file.GetInfo_res.h" +#include "uavcan.protocol.file.Path.h" +#include "uavcan.protocol.file.Read.h" +#include "uavcan.protocol.file.Read_req.h" +#include "uavcan.protocol.file.Read_res.h" +#include "uavcan.protocol.file.Write.h" +#include "uavcan.protocol.file.Write_req.h" +#include "uavcan.protocol.file.Write_res.h" +#include "uavcan.protocol.GetNodeInfo.h" +#include "uavcan.protocol.GetNodeInfo_req.h" +#include "uavcan.protocol.GetNodeInfo_res.h" +#include "uavcan.protocol.HardwareVersion.h" +#include "uavcan.protocol.NodeStatus.h" +#include "uavcan.protocol.param.Empty.h" +#include "uavcan.protocol.param.ExecuteOpcode.h" +#include "uavcan.protocol.param.ExecuteOpcode_req.h" +#include "uavcan.protocol.param.ExecuteOpcode_res.h" +#include "uavcan.protocol.param.GetSet.h" +#include "uavcan.protocol.param.GetSet_req.h" +#include "uavcan.protocol.param.GetSet_res.h" +#include "uavcan.protocol.param.NumericValue.h" +#include "uavcan.protocol.param.Value.h" +#include "uavcan.protocol.RestartNode.h" +#include "uavcan.protocol.RestartNode_req.h" +#include "uavcan.protocol.RestartNode_res.h" +#include "uavcan.protocol.SoftwareVersion.h" diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.RPMCommand.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.RPMCommand.h new file mode 100644 index 00000000..b66bbc65 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.RPMCommand.h @@ -0,0 +1,96 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_EQUIPMENT_ESC_RPMCOMMAND_MAX_SIZE 46 +#define UAVCAN_EQUIPMENT_ESC_RPMCOMMAND_SIGNATURE (0xCE0F9F621CF7E70BULL) +#define UAVCAN_EQUIPMENT_ESC_RPMCOMMAND_ID 1031 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_equipment_esc_RPMCommand_cxx_iface; +#endif + +struct uavcan_equipment_esc_RPMCommand { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_equipment_esc_RPMCommand_cxx_iface; +#endif + struct { uint8_t len; int32_t data[20]; }rpm; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_equipment_esc_RPMCommand_encode(struct uavcan_equipment_esc_RPMCommand* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_equipment_esc_RPMCommand_decode(const CanardRxTransfer* transfer, struct uavcan_equipment_esc_RPMCommand* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_equipment_esc_RPMCommand_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_equipment_esc_RPMCommand* msg, bool tao); +static inline bool _uavcan_equipment_esc_RPMCommand_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_equipment_esc_RPMCommand* msg, bool tao); +void _uavcan_equipment_esc_RPMCommand_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_equipment_esc_RPMCommand* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t rpm_len = msg->rpm.len > 20 ? 20 : msg->rpm.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 5, &rpm_len); + *bit_ofs += 5; + } + for (size_t i=0; i < rpm_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 18, &msg->rpm.data[i]); + *bit_ofs += 18; + } +} + +/* + decode uavcan_equipment_esc_RPMCommand, return true on failure, false on success +*/ +bool _uavcan_equipment_esc_RPMCommand_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_equipment_esc_RPMCommand* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 5, false, &msg->rpm.len); + *bit_ofs += 5; + } else { + msg->rpm.len = ((transfer->payload_len*8)-*bit_ofs)/18; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->rpm.len > 20) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->rpm.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 18, true, &msg->rpm.data[i]); + *bit_ofs += 18; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_equipment_esc_RPMCommand sample_uavcan_equipment_esc_RPMCommand_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +BROADCAST_MESSAGE_CXX_IFACE(uavcan_equipment_esc_RPMCommand, UAVCAN_EQUIPMENT_ESC_RPMCOMMAND_ID, UAVCAN_EQUIPMENT_ESC_RPMCOMMAND_SIGNATURE, UAVCAN_EQUIPMENT_ESC_RPMCOMMAND_MAX_SIZE); +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.RawCommand.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.RawCommand.h new file mode 100644 index 00000000..8c1cc56b --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.RawCommand.h @@ -0,0 +1,96 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_MAX_SIZE 36 +#define UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_SIGNATURE (0x217F5C87D7EC951DULL) +#define UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID 1030 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_equipment_esc_RawCommand_cxx_iface; +#endif + +struct uavcan_equipment_esc_RawCommand { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_equipment_esc_RawCommand_cxx_iface; +#endif + struct { uint8_t len; int16_t data[20]; }cmd; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_equipment_esc_RawCommand_encode(struct uavcan_equipment_esc_RawCommand* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_equipment_esc_RawCommand_decode(const CanardRxTransfer* transfer, struct uavcan_equipment_esc_RawCommand* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_equipment_esc_RawCommand_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_equipment_esc_RawCommand* msg, bool tao); +static inline bool _uavcan_equipment_esc_RawCommand_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_equipment_esc_RawCommand* msg, bool tao); +void _uavcan_equipment_esc_RawCommand_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_equipment_esc_RawCommand* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t cmd_len = msg->cmd.len > 20 ? 20 : msg->cmd.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 5, &cmd_len); + *bit_ofs += 5; + } + for (size_t i=0; i < cmd_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 14, &msg->cmd.data[i]); + *bit_ofs += 14; + } +} + +/* + decode uavcan_equipment_esc_RawCommand, return true on failure, false on success +*/ +bool _uavcan_equipment_esc_RawCommand_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_equipment_esc_RawCommand* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 5, false, &msg->cmd.len); + *bit_ofs += 5; + } else { + msg->cmd.len = ((transfer->payload_len*8)-*bit_ofs)/14; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->cmd.len > 20) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->cmd.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 14, true, &msg->cmd.data[i]); + *bit_ofs += 14; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_equipment_esc_RawCommand sample_uavcan_equipment_esc_RawCommand_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +BROADCAST_MESSAGE_CXX_IFACE(uavcan_equipment_esc_RawCommand, UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID, UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_SIGNATURE, UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_MAX_SIZE); +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.Status.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.Status.h new file mode 100644 index 00000000..cef7bb64 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.Status.h @@ -0,0 +1,128 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE 14 +#define UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE (0xA9AF28AEA2FBB254ULL) +#define UAVCAN_EQUIPMENT_ESC_STATUS_ID 1034 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_equipment_esc_Status_cxx_iface; +#endif + +struct uavcan_equipment_esc_Status { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_equipment_esc_Status_cxx_iface; +#endif + uint32_t error_count; + float voltage; + float current; + float temperature; + int32_t rpm; + uint8_t power_rating_pct; + uint8_t esc_index; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_equipment_esc_Status_encode(struct uavcan_equipment_esc_Status* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_equipment_esc_Status_decode(const CanardRxTransfer* transfer, struct uavcan_equipment_esc_Status* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_equipment_esc_Status_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_equipment_esc_Status* msg, bool tao); +static inline bool _uavcan_equipment_esc_Status_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_equipment_esc_Status* msg, bool tao); +void _uavcan_equipment_esc_Status_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_equipment_esc_Status* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->error_count); + *bit_ofs += 32; + { + uint16_t float16_val = canardConvertNativeFloatToFloat16(msg->voltage); + canardEncodeScalar(buffer, *bit_ofs, 16, &float16_val); + } + *bit_ofs += 16; + { + uint16_t float16_val = canardConvertNativeFloatToFloat16(msg->current); + canardEncodeScalar(buffer, *bit_ofs, 16, &float16_val); + } + *bit_ofs += 16; + { + uint16_t float16_val = canardConvertNativeFloatToFloat16(msg->temperature); + canardEncodeScalar(buffer, *bit_ofs, 16, &float16_val); + } + *bit_ofs += 16; + canardEncodeScalar(buffer, *bit_ofs, 18, &msg->rpm); + *bit_ofs += 18; + canardEncodeScalar(buffer, *bit_ofs, 7, &msg->power_rating_pct); + *bit_ofs += 7; + canardEncodeScalar(buffer, *bit_ofs, 5, &msg->esc_index); + *bit_ofs += 5; +} + +/* + decode uavcan_equipment_esc_Status, return true on failure, false on success +*/ +bool _uavcan_equipment_esc_Status_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_equipment_esc_Status* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->error_count); + *bit_ofs += 32; + + { + uint16_t float16_val; + canardDecodeScalar(transfer, *bit_ofs, 16, true, &float16_val); + msg->voltage = canardConvertFloat16ToNativeFloat(float16_val); + } + *bit_ofs += 16; + + { + uint16_t float16_val; + canardDecodeScalar(transfer, *bit_ofs, 16, true, &float16_val); + msg->current = canardConvertFloat16ToNativeFloat(float16_val); + } + *bit_ofs += 16; + + { + uint16_t float16_val; + canardDecodeScalar(transfer, *bit_ofs, 16, true, &float16_val); + msg->temperature = canardConvertFloat16ToNativeFloat(float16_val); + } + *bit_ofs += 16; + + canardDecodeScalar(transfer, *bit_ofs, 18, true, &msg->rpm); + *bit_ofs += 18; + + canardDecodeScalar(transfer, *bit_ofs, 7, false, &msg->power_rating_pct); + *bit_ofs += 7; + + canardDecodeScalar(transfer, *bit_ofs, 5, false, &msg->esc_index); + *bit_ofs += 5; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_equipment_esc_Status sample_uavcan_equipment_esc_Status_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +BROADCAST_MESSAGE_CXX_IFACE(uavcan_equipment_esc_Status, UAVCAN_EQUIPMENT_ESC_STATUS_ID, UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE, UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE); +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.StatusExtended.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.StatusExtended.h new file mode 100644 index 00000000..bbf9d4ef --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.StatusExtended.h @@ -0,0 +1,101 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_MAX_SIZE 7 +#define UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_SIGNATURE (0x2DC203C50960EDCULL) +#define UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_ID 1036 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_equipment_esc_StatusExtended_cxx_iface; +#endif + +struct uavcan_equipment_esc_StatusExtended { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_equipment_esc_StatusExtended_cxx_iface; +#endif + uint8_t input_pct; + uint8_t output_pct; + int16_t motor_temperature_degC; + uint16_t motor_angle; + uint32_t status_flags; + uint8_t esc_index; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_equipment_esc_StatusExtended_encode(struct uavcan_equipment_esc_StatusExtended* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_equipment_esc_StatusExtended_decode(const CanardRxTransfer* transfer, struct uavcan_equipment_esc_StatusExtended* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_equipment_esc_StatusExtended_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_equipment_esc_StatusExtended* msg, bool tao); +static inline bool _uavcan_equipment_esc_StatusExtended_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_equipment_esc_StatusExtended* msg, bool tao); +void _uavcan_equipment_esc_StatusExtended_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_equipment_esc_StatusExtended* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 7, &msg->input_pct); + *bit_ofs += 7; + canardEncodeScalar(buffer, *bit_ofs, 7, &msg->output_pct); + *bit_ofs += 7; + canardEncodeScalar(buffer, *bit_ofs, 9, &msg->motor_temperature_degC); + *bit_ofs += 9; + canardEncodeScalar(buffer, *bit_ofs, 9, &msg->motor_angle); + *bit_ofs += 9; + canardEncodeScalar(buffer, *bit_ofs, 19, &msg->status_flags); + *bit_ofs += 19; + canardEncodeScalar(buffer, *bit_ofs, 5, &msg->esc_index); + *bit_ofs += 5; +} + +/* + decode uavcan_equipment_esc_StatusExtended, return true on failure, false on success +*/ +bool _uavcan_equipment_esc_StatusExtended_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_equipment_esc_StatusExtended* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 7, false, &msg->input_pct); + *bit_ofs += 7; + + canardDecodeScalar(transfer, *bit_ofs, 7, false, &msg->output_pct); + *bit_ofs += 7; + + canardDecodeScalar(transfer, *bit_ofs, 9, true, &msg->motor_temperature_degC); + *bit_ofs += 9; + + canardDecodeScalar(transfer, *bit_ofs, 9, false, &msg->motor_angle); + *bit_ofs += 9; + + canardDecodeScalar(transfer, *bit_ofs, 19, false, &msg->status_flags); + *bit_ofs += 19; + + canardDecodeScalar(transfer, *bit_ofs, 5, false, &msg->esc_index); + *bit_ofs += 5; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_equipment_esc_StatusExtended sample_uavcan_equipment_esc_StatusExtended_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +BROADCAST_MESSAGE_CXX_IFACE(uavcan_equipment_esc_StatusExtended, UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_ID, UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_SIGNATURE, UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_MAX_SIZE); +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.safety.ArmingStatus.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.safety.ArmingStatus.h new file mode 100644 index 00000000..d6232ae2 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.equipment.safety.ArmingStatus.h @@ -0,0 +1,74 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_MAX_SIZE 1 +#define UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_SIGNATURE (0x8700F375556A8003ULL) +#define UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID 1100 + +#define UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_DISARMED 0 +#define UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_FULLY_ARMED 255 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_equipment_safety_ArmingStatus_cxx_iface; +#endif + +struct uavcan_equipment_safety_ArmingStatus { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_equipment_safety_ArmingStatus_cxx_iface; +#endif + uint8_t status; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_equipment_safety_ArmingStatus_encode(struct uavcan_equipment_safety_ArmingStatus* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_equipment_safety_ArmingStatus_decode(const CanardRxTransfer* transfer, struct uavcan_equipment_safety_ArmingStatus* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_equipment_safety_ArmingStatus_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_equipment_safety_ArmingStatus* msg, bool tao); +static inline bool _uavcan_equipment_safety_ArmingStatus_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_equipment_safety_ArmingStatus* msg, bool tao); +void _uavcan_equipment_safety_ArmingStatus_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_equipment_safety_ArmingStatus* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->status); + *bit_ofs += 8; +} + +/* + decode uavcan_equipment_safety_ArmingStatus, return true on failure, false on success +*/ +bool _uavcan_equipment_safety_ArmingStatus_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_equipment_safety_ArmingStatus* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->status); + *bit_ofs += 8; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_equipment_safety_ArmingStatus sample_uavcan_equipment_safety_ArmingStatus_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +BROADCAST_MESSAGE_CXX_IFACE(uavcan_equipment_safety_ArmingStatus, UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID, UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_SIGNATURE, UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_MAX_SIZE); +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo.h new file mode 100644 index 00000000..242c1bfe --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_GETNODEINFO_ID 1 +#define UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE (0xEE468A8121C46A9EULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_GetNodeInfo, UAVCAN_PROTOCOL_GETNODEINFO_ID, UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE, UAVCAN_PROTOCOL_GETNODEINFO_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo_req.h new file mode 100644 index 00000000..c778974a --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo_req.h @@ -0,0 +1,64 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_GETNODEINFO_REQUEST_MAX_SIZE 0 +#define UAVCAN_PROTOCOL_GETNODEINFO_REQUEST_SIGNATURE (0xEE468A8121C46A9EULL) +#define UAVCAN_PROTOCOL_GETNODEINFO_REQUEST_ID 1 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_GetNodeInfo_cxx_iface; +#endif + +struct uavcan_protocol_GetNodeInfoRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_GetNodeInfo_cxx_iface; +#endif +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_GetNodeInfoRequest_encode(struct uavcan_protocol_GetNodeInfoRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_GetNodeInfoRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_GetNodeInfoRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_GetNodeInfoRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_GetNodeInfoRequest* msg, bool tao); +static inline bool _uavcan_protocol_GetNodeInfoRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_GetNodeInfoRequest* msg, bool tao); +void _uavcan_protocol_GetNodeInfoRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_GetNodeInfoRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + +} + +/* + decode uavcan_protocol_GetNodeInfoRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_GetNodeInfoRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_GetNodeInfoRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_GetNodeInfoRequest sample_uavcan_protocol_GetNodeInfoRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo_res.h new file mode 100644 index 00000000..0fe1abf8 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo_res.h @@ -0,0 +1,110 @@ +#pragma once +#include +#include +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE 377 +#define UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_SIGNATURE (0xEE468A8121C46A9EULL) +#define UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_ID 1 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_GetNodeInfo_cxx_iface; +#endif + +struct uavcan_protocol_GetNodeInfoResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_GetNodeInfo_cxx_iface; +#endif + struct uavcan_protocol_NodeStatus status; + struct uavcan_protocol_SoftwareVersion software_version; + struct uavcan_protocol_HardwareVersion hardware_version; + struct { uint8_t len; uint8_t data[80]; }name; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_GetNodeInfoResponse_encode(struct uavcan_protocol_GetNodeInfoResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_GetNodeInfoResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_GetNodeInfoResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_GetNodeInfoResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_GetNodeInfoResponse* msg, bool tao); +static inline bool _uavcan_protocol_GetNodeInfoResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_GetNodeInfoResponse* msg, bool tao); +void _uavcan_protocol_GetNodeInfoResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_GetNodeInfoResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + _uavcan_protocol_NodeStatus_encode(buffer, bit_ofs, &msg->status, false); + _uavcan_protocol_SoftwareVersion_encode(buffer, bit_ofs, &msg->software_version, false); + _uavcan_protocol_HardwareVersion_encode(buffer, bit_ofs, &msg->hardware_version, false); +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t name_len = msg->name.len > 80 ? 80 : msg->name.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 7, &name_len); + *bit_ofs += 7; + } + for (size_t i=0; i < name_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->name.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_GetNodeInfoResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_GetNodeInfoResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_GetNodeInfoResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + if (_uavcan_protocol_NodeStatus_decode(transfer, bit_ofs, &msg->status, false)) {return true;} + + if (_uavcan_protocol_SoftwareVersion_decode(transfer, bit_ofs, &msg->software_version, false)) {return true;} + + if (_uavcan_protocol_HardwareVersion_decode(transfer, bit_ofs, &msg->hardware_version, false)) {return true;} + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 7, false, &msg->name.len); + *bit_ofs += 7; + } else { + msg->name.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->name.len > 80) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->name.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->name.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_GetNodeInfoResponse sample_uavcan_protocol_GetNodeInfoResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.HardwareVersion.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.HardwareVersion.h new file mode 100644 index 00000000..a3d14b3e --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.HardwareVersion.h @@ -0,0 +1,110 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_HARDWAREVERSION_MAX_SIZE 274 +#define UAVCAN_PROTOCOL_HARDWAREVERSION_SIGNATURE (0xAD5C4C933F4A0C4ULL) + + +struct uavcan_protocol_HardwareVersion { + uint8_t major; + uint8_t minor; + uint8_t unique_id[16]; + struct { uint8_t len; uint8_t data[255]; }certificate_of_authenticity; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_HardwareVersion_encode(struct uavcan_protocol_HardwareVersion* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_HardwareVersion_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_HardwareVersion* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_HardwareVersion_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_HardwareVersion* msg, bool tao); +static inline bool _uavcan_protocol_HardwareVersion_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_HardwareVersion* msg, bool tao); +void _uavcan_protocol_HardwareVersion_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_HardwareVersion* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->major); + *bit_ofs += 8; + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->minor); + *bit_ofs += 8; + for (size_t i=0; i < 16; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->unique_id[i]); + *bit_ofs += 8; + } +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t certificate_of_authenticity_len = msg->certificate_of_authenticity.len > 255 ? 255 : msg->certificate_of_authenticity.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 8, &certificate_of_authenticity_len); + *bit_ofs += 8; + } + for (size_t i=0; i < certificate_of_authenticity_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->certificate_of_authenticity.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_HardwareVersion, return true on failure, false on success +*/ +bool _uavcan_protocol_HardwareVersion_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_HardwareVersion* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->major); + *bit_ofs += 8; + + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->minor); + *bit_ofs += 8; + + for (size_t i=0; i < 16; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->unique_id[i]); + *bit_ofs += 8; + } + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->certificate_of_authenticity.len); + *bit_ofs += 8; + } else { + msg->certificate_of_authenticity.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->certificate_of_authenticity.len > 255) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->certificate_of_authenticity.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->certificate_of_authenticity.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_HardwareVersion sample_uavcan_protocol_HardwareVersion_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.NodeStatus.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.NodeStatus.h new file mode 100644 index 00000000..854469dd --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.NodeStatus.h @@ -0,0 +1,108 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE 7 +#define UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE (0xF0868D0C1A7C6F1ULL) +#define UAVCAN_PROTOCOL_NODESTATUS_ID 341 + +#define UAVCAN_PROTOCOL_NODESTATUS_MAX_BROADCASTING_PERIOD_MS 1000 +#define UAVCAN_PROTOCOL_NODESTATUS_MIN_BROADCASTING_PERIOD_MS 2 +#define UAVCAN_PROTOCOL_NODESTATUS_OFFLINE_TIMEOUT_MS 3000 +#define UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK 0 +#define UAVCAN_PROTOCOL_NODESTATUS_HEALTH_WARNING 1 +#define UAVCAN_PROTOCOL_NODESTATUS_HEALTH_ERROR 2 +#define UAVCAN_PROTOCOL_NODESTATUS_HEALTH_CRITICAL 3 +#define UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL 0 +#define UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION 1 +#define UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE 2 +#define UAVCAN_PROTOCOL_NODESTATUS_MODE_SOFTWARE_UPDATE 3 +#define UAVCAN_PROTOCOL_NODESTATUS_MODE_OFFLINE 7 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_NodeStatus_cxx_iface; +#endif + +struct uavcan_protocol_NodeStatus { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_NodeStatus_cxx_iface; +#endif + uint32_t uptime_sec; + uint8_t health; + uint8_t mode; + uint8_t sub_mode; + uint16_t vendor_specific_status_code; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_NodeStatus_encode(struct uavcan_protocol_NodeStatus* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_NodeStatus_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_NodeStatus* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_NodeStatus_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_NodeStatus* msg, bool tao); +static inline bool _uavcan_protocol_NodeStatus_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_NodeStatus* msg, bool tao); +void _uavcan_protocol_NodeStatus_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_NodeStatus* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->uptime_sec); + *bit_ofs += 32; + canardEncodeScalar(buffer, *bit_ofs, 2, &msg->health); + *bit_ofs += 2; + canardEncodeScalar(buffer, *bit_ofs, 3, &msg->mode); + *bit_ofs += 3; + canardEncodeScalar(buffer, *bit_ofs, 3, &msg->sub_mode); + *bit_ofs += 3; + canardEncodeScalar(buffer, *bit_ofs, 16, &msg->vendor_specific_status_code); + *bit_ofs += 16; +} + +/* + decode uavcan_protocol_NodeStatus, return true on failure, false on success +*/ +bool _uavcan_protocol_NodeStatus_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_NodeStatus* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->uptime_sec); + *bit_ofs += 32; + + canardDecodeScalar(transfer, *bit_ofs, 2, false, &msg->health); + *bit_ofs += 2; + + canardDecodeScalar(transfer, *bit_ofs, 3, false, &msg->mode); + *bit_ofs += 3; + + canardDecodeScalar(transfer, *bit_ofs, 3, false, &msg->sub_mode); + *bit_ofs += 3; + + canardDecodeScalar(transfer, *bit_ofs, 16, false, &msg->vendor_specific_status_code); + *bit_ofs += 16; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_NodeStatus sample_uavcan_protocol_NodeStatus_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +BROADCAST_MESSAGE_CXX_IFACE(uavcan_protocol_NodeStatus, UAVCAN_PROTOCOL_NODESTATUS_ID, UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE); +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode.h new file mode 100644 index 00000000..db56f6f5 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_RESTARTNODE_ID 5 +#define UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE (0x569E05394A3017F0ULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_RestartNode, UAVCAN_PROTOCOL_RESTARTNODE_ID, UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE, UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode_req.h new file mode 100644 index 00000000..953302b7 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode_req.h @@ -0,0 +1,72 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_MAX_SIZE 5 +#define UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_SIGNATURE (0x569E05394A3017F0ULL) +#define UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_ID 5 + +#define UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_MAGIC_NUMBER 742196058910 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_RestartNode_cxx_iface; +#endif + +struct uavcan_protocol_RestartNodeRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_RestartNode_cxx_iface; +#endif + uint64_t magic_number; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_RestartNodeRequest_encode(struct uavcan_protocol_RestartNodeRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_RestartNodeRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_RestartNodeRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_RestartNodeRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_RestartNodeRequest* msg, bool tao); +static inline bool _uavcan_protocol_RestartNodeRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_RestartNodeRequest* msg, bool tao); +void _uavcan_protocol_RestartNodeRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_RestartNodeRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 40, &msg->magic_number); + *bit_ofs += 40; +} + +/* + decode uavcan_protocol_RestartNodeRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_RestartNodeRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_RestartNodeRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 40, false, &msg->magic_number); + *bit_ofs += 40; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_RestartNodeRequest sample_uavcan_protocol_RestartNodeRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode_res.h new file mode 100644 index 00000000..fe653f86 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode_res.h @@ -0,0 +1,70 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_MAX_SIZE 1 +#define UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_SIGNATURE (0x569E05394A3017F0ULL) +#define UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_ID 5 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_RestartNode_cxx_iface; +#endif + +struct uavcan_protocol_RestartNodeResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_RestartNode_cxx_iface; +#endif + bool ok; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_RestartNodeResponse_encode(struct uavcan_protocol_RestartNodeResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_RestartNodeResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_RestartNodeResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_RestartNodeResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_RestartNodeResponse* msg, bool tao); +static inline bool _uavcan_protocol_RestartNodeResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_RestartNodeResponse* msg, bool tao); +void _uavcan_protocol_RestartNodeResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_RestartNodeResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 1, &msg->ok); + *bit_ofs += 1; +} + +/* + decode uavcan_protocol_RestartNodeResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_RestartNodeResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_RestartNodeResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 1, false, &msg->ok); + *bit_ofs += 1; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_RestartNodeResponse sample_uavcan_protocol_RestartNodeResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.SoftwareVersion.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.SoftwareVersion.h new file mode 100644 index 00000000..c965cc0c --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.SoftwareVersion.h @@ -0,0 +1,90 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_SOFTWAREVERSION_MAX_SIZE 15 +#define UAVCAN_PROTOCOL_SOFTWAREVERSION_SIGNATURE (0xDD46FD376527FEA1ULL) + +#define UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_VCS_COMMIT 1 +#define UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_IMAGE_CRC 2 + + +struct uavcan_protocol_SoftwareVersion { + uint8_t major; + uint8_t minor; + uint8_t optional_field_flags; + uint32_t vcs_commit; + uint64_t image_crc; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_SoftwareVersion_encode(struct uavcan_protocol_SoftwareVersion* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_SoftwareVersion_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_SoftwareVersion* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_SoftwareVersion_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_SoftwareVersion* msg, bool tao); +static inline bool _uavcan_protocol_SoftwareVersion_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_SoftwareVersion* msg, bool tao); +void _uavcan_protocol_SoftwareVersion_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_SoftwareVersion* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->major); + *bit_ofs += 8; + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->minor); + *bit_ofs += 8; + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->optional_field_flags); + *bit_ofs += 8; + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->vcs_commit); + *bit_ofs += 32; + canardEncodeScalar(buffer, *bit_ofs, 64, &msg->image_crc); + *bit_ofs += 64; +} + +/* + decode uavcan_protocol_SoftwareVersion, return true on failure, false on success +*/ +bool _uavcan_protocol_SoftwareVersion_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_SoftwareVersion* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->major); + *bit_ofs += 8; + + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->minor); + *bit_ofs += 8; + + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->optional_field_flags); + *bit_ofs += 8; + + canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->vcs_commit); + *bit_ofs += 32; + + canardDecodeScalar(transfer, *bit_ofs, 64, false, &msg->image_crc); + *bit_ofs += 64; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_SoftwareVersion sample_uavcan_protocol_SoftwareVersion_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.KeyValue.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.KeyValue.h new file mode 100644 index 00000000..acd1aa23 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.KeyValue.h @@ -0,0 +1,102 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_DEBUG_KEYVALUE_MAX_SIZE 63 +#define UAVCAN_PROTOCOL_DEBUG_KEYVALUE_SIGNATURE (0xE02F25D6E0C98AE0ULL) +#define UAVCAN_PROTOCOL_DEBUG_KEYVALUE_ID 16370 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_debug_KeyValue_cxx_iface; +#endif + +struct uavcan_protocol_debug_KeyValue { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_debug_KeyValue_cxx_iface; +#endif + float value; + struct { uint8_t len; uint8_t data[58]; }key; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_debug_KeyValue_encode(struct uavcan_protocol_debug_KeyValue* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_debug_KeyValue_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_debug_KeyValue* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_debug_KeyValue_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_debug_KeyValue* msg, bool tao); +static inline bool _uavcan_protocol_debug_KeyValue_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_debug_KeyValue* msg, bool tao); +void _uavcan_protocol_debug_KeyValue_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_debug_KeyValue* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->value); + *bit_ofs += 32; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t key_len = msg->key.len > 58 ? 58 : msg->key.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 6, &key_len); + *bit_ofs += 6; + } + for (size_t i=0; i < key_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->key.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_debug_KeyValue, return true on failure, false on success +*/ +bool _uavcan_protocol_debug_KeyValue_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_debug_KeyValue* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 32, true, &msg->value); + *bit_ofs += 32; + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 6, false, &msg->key.len); + *bit_ofs += 6; + } else { + msg->key.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->key.len > 58) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->key.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->key.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_debug_KeyValue sample_uavcan_protocol_debug_KeyValue_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +BROADCAST_MESSAGE_CXX_IFACE(uavcan_protocol_debug_KeyValue, UAVCAN_PROTOCOL_DEBUG_KEYVALUE_ID, UAVCAN_PROTOCOL_DEBUG_KEYVALUE_SIGNATURE, UAVCAN_PROTOCOL_DEBUG_KEYVALUE_MAX_SIZE); +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.LogLevel.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.LogLevel.h new file mode 100644 index 00000000..237b8a34 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.LogLevel.h @@ -0,0 +1,68 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_MAX_SIZE 1 +#define UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_SIGNATURE (0x711BF141AF572346ULL) + +#define UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_DEBUG 0 +#define UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_INFO 1 +#define UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_WARNING 2 +#define UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_ERROR 3 + + +struct uavcan_protocol_debug_LogLevel { + uint8_t value; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_debug_LogLevel_encode(struct uavcan_protocol_debug_LogLevel* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_debug_LogLevel_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_debug_LogLevel* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_debug_LogLevel_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_debug_LogLevel* msg, bool tao); +static inline bool _uavcan_protocol_debug_LogLevel_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_debug_LogLevel* msg, bool tao); +void _uavcan_protocol_debug_LogLevel_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_debug_LogLevel* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 3, &msg->value); + *bit_ofs += 3; +} + +/* + decode uavcan_protocol_debug_LogLevel, return true on failure, false on success +*/ +bool _uavcan_protocol_debug_LogLevel_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_debug_LogLevel* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 3, false, &msg->value); + *bit_ofs += 3; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_debug_LogLevel sample_uavcan_protocol_debug_LogLevel_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.LogMessage.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.LogMessage.h new file mode 100644 index 00000000..034ba674 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.LogMessage.h @@ -0,0 +1,125 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE 123 +#define UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE (0xD654A48E0C049D75ULL) +#define UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID 16383 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_debug_LogMessage_cxx_iface; +#endif + +struct uavcan_protocol_debug_LogMessage { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_debug_LogMessage_cxx_iface; +#endif + struct uavcan_protocol_debug_LogLevel level; + struct { uint8_t len; uint8_t data[31]; }source; + struct { uint8_t len; uint8_t data[90]; }text; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_debug_LogMessage_encode(struct uavcan_protocol_debug_LogMessage* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_debug_LogMessage_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_debug_LogMessage* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_debug_LogMessage_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_debug_LogMessage* msg, bool tao); +static inline bool _uavcan_protocol_debug_LogMessage_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_debug_LogMessage* msg, bool tao); +void _uavcan_protocol_debug_LogMessage_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_debug_LogMessage* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + _uavcan_protocol_debug_LogLevel_encode(buffer, bit_ofs, &msg->level, false); +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t source_len = msg->source.len > 31 ? 31 : msg->source.len; +#pragma GCC diagnostic pop + canardEncodeScalar(buffer, *bit_ofs, 5, &source_len); + *bit_ofs += 5; + for (size_t i=0; i < source_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->source.data[i]); + *bit_ofs += 8; + } +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t text_len = msg->text.len > 90 ? 90 : msg->text.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 7, &text_len); + *bit_ofs += 7; + } + for (size_t i=0; i < text_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->text.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_debug_LogMessage, return true on failure, false on success +*/ +bool _uavcan_protocol_debug_LogMessage_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_debug_LogMessage* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + if (_uavcan_protocol_debug_LogLevel_decode(transfer, bit_ofs, &msg->level, false)) {return true;} + + canardDecodeScalar(transfer, *bit_ofs, 5, false, &msg->source.len); + *bit_ofs += 5; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->source.len > 31) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->source.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->source.data[i]); + *bit_ofs += 8; + } + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 7, false, &msg->text.len); + *bit_ofs += 7; + } else { + msg->text.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->text.len > 90) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->text.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->text.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_debug_LogMessage sample_uavcan_protocol_debug_LogMessage_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +BROADCAST_MESSAGE_CXX_IFACE(uavcan_protocol_debug_LogMessage, UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID, UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE, UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE); +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.Allocation.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.Allocation.h new file mode 100644 index 00000000..b68f930c --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.Allocation.h @@ -0,0 +1,116 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_SIZE 18 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE (0xB2A812620A11D40ULL) +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID 1 + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_REQUEST_PERIOD_MS 1000 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS 600 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS 400 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_FOLLOWUP_DELAY_MS 0 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_FOLLOWUP_TIMEOUT_MS 500 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_LENGTH_OF_UNIQUE_ID_IN_REQUEST 6 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ANY_NODE_ID 0 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_dynamic_node_id_Allocation_cxx_iface; +#endif + +struct uavcan_protocol_dynamic_node_id_Allocation { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_dynamic_node_id_Allocation_cxx_iface; +#endif + uint8_t node_id; + bool first_part_of_unique_id; + struct { uint8_t len; uint8_t data[16]; }unique_id; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_dynamic_node_id_Allocation_encode(struct uavcan_protocol_dynamic_node_id_Allocation* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_dynamic_node_id_Allocation_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_Allocation* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_dynamic_node_id_Allocation_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_Allocation* msg, bool tao); +static inline bool _uavcan_protocol_dynamic_node_id_Allocation_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_Allocation* msg, bool tao); +void _uavcan_protocol_dynamic_node_id_Allocation_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_Allocation* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 7, &msg->node_id); + *bit_ofs += 7; + canardEncodeScalar(buffer, *bit_ofs, 1, &msg->first_part_of_unique_id); + *bit_ofs += 1; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t unique_id_len = msg->unique_id.len > 16 ? 16 : msg->unique_id.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 5, &unique_id_len); + *bit_ofs += 5; + } + for (size_t i=0; i < unique_id_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->unique_id.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_dynamic_node_id_Allocation, return true on failure, false on success +*/ +bool _uavcan_protocol_dynamic_node_id_Allocation_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_Allocation* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 7, false, &msg->node_id); + *bit_ofs += 7; + + canardDecodeScalar(transfer, *bit_ofs, 1, false, &msg->first_part_of_unique_id); + *bit_ofs += 1; + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 5, false, &msg->unique_id.len); + *bit_ofs += 5; + } else { + msg->unique_id.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->unique_id.len > 16) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->unique_id.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->unique_id.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_Allocation sample_uavcan_protocol_dynamic_node_id_Allocation_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +BROADCAST_MESSAGE_CXX_IFACE(uavcan_protocol_dynamic_node_id_Allocation, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_SIZE); +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries.h new file mode 100644 index 00000000..a3ad5688 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_ID 30 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_SIGNATURE (0x8032C7097B48A3CCULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_dynamic_node_id_server_AppendEntries, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_ID, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_SIGNATURE, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.h new file mode 100644 index 00000000..0676005f --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.h @@ -0,0 +1,130 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_REQUEST_MAX_SIZE 32 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_REQUEST_SIGNATURE (0x8032C7097B48A3CCULL) +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_REQUEST_ID 30 + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_REQUEST_DEFAULT_MIN_ELECTION_TIMEOUT_MS 2000 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_REQUEST_DEFAULT_MAX_ELECTION_TIMEOUT_MS 4000 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_dynamic_node_id_server_AppendEntries_cxx_iface; +#endif + +struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_dynamic_node_id_server_AppendEntries_cxx_iface; +#endif + uint32_t term; + uint32_t prev_log_term; + uint8_t prev_log_index; + uint8_t leader_commit; + struct { uint8_t len; struct uavcan_protocol_dynamic_node_id_server_Entry data[1]; }entries; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_encode(struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest* msg, bool tao); +static inline bool _uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest* msg, bool tao); +void _uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->term); + *bit_ofs += 32; + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->prev_log_term); + *bit_ofs += 32; + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->prev_log_index); + *bit_ofs += 8; + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->leader_commit); + *bit_ofs += 8; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t entries_len = msg->entries.len > 1 ? 1 : msg->entries.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 1, &entries_len); + *bit_ofs += 1; + } + for (size_t i=0; i < entries_len; i++) { + _uavcan_protocol_dynamic_node_id_server_Entry_encode(buffer, bit_ofs, &msg->entries.data[i], false); + } +} + +/* + decode uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->term); + *bit_ofs += 32; + + canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->prev_log_term); + *bit_ofs += 32; + + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->prev_log_index); + *bit_ofs += 8; + + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->leader_commit); + *bit_ofs += 8; + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 1, false, &msg->entries.len); + *bit_ofs += 1; + } + + + if (tao) { + msg->entries.len = 0; + size_t max_len = 1; + uint32_t max_bits = (transfer->payload_len*8)-7; // TAO elements must be >= 8 bits + while (max_bits > *bit_ofs) { + if (!max_len-- || _uavcan_protocol_dynamic_node_id_server_Entry_decode(transfer, bit_ofs, &msg->entries.data[msg->entries.len], false)) {return true;} + msg->entries.len++; + } + } else { +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->entries.len > 1) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->entries.len; i++) { + if (_uavcan_protocol_dynamic_node_id_server_Entry_decode(transfer, bit_ofs, &msg->entries.data[i], false)) {return true;} + } + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest sample_uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.h new file mode 100644 index 00000000..bd99a0ac --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.h @@ -0,0 +1,76 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_RESPONSE_MAX_SIZE 5 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_RESPONSE_SIGNATURE (0x8032C7097B48A3CCULL) +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_RESPONSE_ID 30 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_dynamic_node_id_server_AppendEntries_cxx_iface; +#endif + +struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_dynamic_node_id_server_AppendEntries_cxx_iface; +#endif + uint32_t term; + bool success; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_encode(struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse* msg, bool tao); +static inline bool _uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse* msg, bool tao); +void _uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->term); + *bit_ofs += 32; + canardEncodeScalar(buffer, *bit_ofs, 1, &msg->success); + *bit_ofs += 1; +} + +/* + decode uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->term); + *bit_ofs += 32; + + canardDecodeScalar(transfer, *bit_ofs, 1, false, &msg->success); + *bit_ofs += 1; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse sample_uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.Discovery.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.Discovery.h new file mode 100644 index 00000000..8596b5eb --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.Discovery.h @@ -0,0 +1,104 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_DISCOVERY_MAX_SIZE 7 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_DISCOVERY_SIGNATURE (0x821AE2F525F69F21ULL) +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_DISCOVERY_ID 390 + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_DISCOVERY_BROADCASTING_PERIOD_MS 1000 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_dynamic_node_id_server_Discovery_cxx_iface; +#endif + +struct uavcan_protocol_dynamic_node_id_server_Discovery { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_dynamic_node_id_server_Discovery_cxx_iface; +#endif + uint8_t configured_cluster_size; + struct { uint8_t len; uint8_t data[5]; }known_nodes; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_Discovery_encode(struct uavcan_protocol_dynamic_node_id_server_Discovery* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_dynamic_node_id_server_Discovery_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_Discovery* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_dynamic_node_id_server_Discovery_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_Discovery* msg, bool tao); +static inline bool _uavcan_protocol_dynamic_node_id_server_Discovery_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_Discovery* msg, bool tao); +void _uavcan_protocol_dynamic_node_id_server_Discovery_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_Discovery* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->configured_cluster_size); + *bit_ofs += 8; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t known_nodes_len = msg->known_nodes.len > 5 ? 5 : msg->known_nodes.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 3, &known_nodes_len); + *bit_ofs += 3; + } + for (size_t i=0; i < known_nodes_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->known_nodes.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_dynamic_node_id_server_Discovery, return true on failure, false on success +*/ +bool _uavcan_protocol_dynamic_node_id_server_Discovery_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_Discovery* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->configured_cluster_size); + *bit_ofs += 8; + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 3, false, &msg->known_nodes.len); + *bit_ofs += 3; + } else { + msg->known_nodes.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->known_nodes.len > 5) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->known_nodes.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->known_nodes.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_Discovery sample_uavcan_protocol_dynamic_node_id_server_Discovery_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +BROADCAST_MESSAGE_CXX_IFACE(uavcan_protocol_dynamic_node_id_server_Discovery, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_DISCOVERY_ID, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_DISCOVERY_SIGNATURE, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_DISCOVERY_MAX_SIZE); +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.Entry.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.Entry.h new file mode 100644 index 00000000..bbb05d1b --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.Entry.h @@ -0,0 +1,82 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_ENTRY_MAX_SIZE 21 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_ENTRY_SIGNATURE (0x7FAA779D64FA75C2ULL) + + +struct uavcan_protocol_dynamic_node_id_server_Entry { + uint32_t term; + uint8_t unique_id[16]; + uint8_t node_id; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_Entry_encode(struct uavcan_protocol_dynamic_node_id_server_Entry* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_dynamic_node_id_server_Entry_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_Entry* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_dynamic_node_id_server_Entry_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_Entry* msg, bool tao); +static inline bool _uavcan_protocol_dynamic_node_id_server_Entry_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_Entry* msg, bool tao); +void _uavcan_protocol_dynamic_node_id_server_Entry_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_Entry* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->term); + *bit_ofs += 32; + for (size_t i=0; i < 16; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->unique_id[i]); + *bit_ofs += 8; + } + *bit_ofs += 1; + canardEncodeScalar(buffer, *bit_ofs, 7, &msg->node_id); + *bit_ofs += 7; +} + +/* + decode uavcan_protocol_dynamic_node_id_server_Entry, return true on failure, false on success +*/ +bool _uavcan_protocol_dynamic_node_id_server_Entry_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_Entry* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->term); + *bit_ofs += 32; + + for (size_t i=0; i < 16; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->unique_id[i]); + *bit_ofs += 8; + } + + *bit_ofs += 1; + + canardDecodeScalar(transfer, *bit_ofs, 7, false, &msg->node_id); + *bit_ofs += 7; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_Entry sample_uavcan_protocol_dynamic_node_id_server_Entry_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote.h new file mode 100644 index 00000000..8a4da271 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_ID 31 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_SIGNATURE (0xCDDE07BB89A56356ULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_dynamic_node_id_server_RequestVote, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_ID, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_SIGNATURE, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote_req.h new file mode 100644 index 00000000..c51d4420 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote_req.h @@ -0,0 +1,82 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_REQUEST_MAX_SIZE 9 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_REQUEST_SIGNATURE (0xCDDE07BB89A56356ULL) +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_REQUEST_ID 31 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_dynamic_node_id_server_RequestVote_cxx_iface; +#endif + +struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_dynamic_node_id_server_RequestVote_cxx_iface; +#endif + uint32_t term; + uint32_t last_log_term; + uint8_t last_log_index; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_encode(struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest* msg, bool tao); +static inline bool _uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest* msg, bool tao); +void _uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->term); + *bit_ofs += 32; + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->last_log_term); + *bit_ofs += 32; + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->last_log_index); + *bit_ofs += 8; +} + +/* + decode uavcan_protocol_dynamic_node_id_server_RequestVoteRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->term); + *bit_ofs += 32; + + canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->last_log_term); + *bit_ofs += 32; + + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->last_log_index); + *bit_ofs += 8; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest sample_uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote_res.h new file mode 100644 index 00000000..a1e79cac --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote_res.h @@ -0,0 +1,76 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_RESPONSE_MAX_SIZE 5 +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_RESPONSE_SIGNATURE (0xCDDE07BB89A56356ULL) +#define UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_RESPONSE_ID 31 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_dynamic_node_id_server_RequestVote_cxx_iface; +#endif + +struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_dynamic_node_id_server_RequestVote_cxx_iface; +#endif + uint32_t term; + bool vote_granted; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_encode(struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse* msg, bool tao); +static inline bool _uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse* msg, bool tao); +void _uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->term); + *bit_ofs += 32; + canardEncodeScalar(buffer, *bit_ofs, 1, &msg->vote_granted); + *bit_ofs += 1; +} + +/* + decode uavcan_protocol_dynamic_node_id_server_RequestVoteResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->term); + *bit_ofs += 32; + + canardDecodeScalar(transfer, *bit_ofs, 1, false, &msg->vote_granted); + *bit_ofs += 1; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse sample_uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate.h new file mode 100644 index 00000000..ab0678e6 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID 40 +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE (0xB7D725DF72724126ULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_file_BeginFirmwareUpdate, UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID, UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE, UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate_req.h new file mode 100644 index 00000000..7e012776 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate_req.h @@ -0,0 +1,75 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_REQUEST_MAX_SIZE 202 +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_REQUEST_SIGNATURE (0xB7D725DF72724126ULL) +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_REQUEST_ID 40 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_BeginFirmwareUpdate_cxx_iface; +#endif + +struct uavcan_protocol_file_BeginFirmwareUpdateRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_BeginFirmwareUpdate_cxx_iface; +#endif + uint8_t source_node_id; + struct uavcan_protocol_file_Path image_file_remote_path; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_BeginFirmwareUpdateRequest_encode(struct uavcan_protocol_file_BeginFirmwareUpdateRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_BeginFirmwareUpdateRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_BeginFirmwareUpdateRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_BeginFirmwareUpdateRequest* msg, bool tao); +static inline bool _uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_BeginFirmwareUpdateRequest* msg, bool tao); +void _uavcan_protocol_file_BeginFirmwareUpdateRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_BeginFirmwareUpdateRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->source_node_id); + *bit_ofs += 8; + _uavcan_protocol_file_Path_encode(buffer, bit_ofs, &msg->image_file_remote_path, tao); +} + +/* + decode uavcan_protocol_file_BeginFirmwareUpdateRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_BeginFirmwareUpdateRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->source_node_id); + *bit_ofs += 8; + + if (_uavcan_protocol_file_Path_decode(transfer, bit_ofs, &msg->image_file_remote_path, tao)) {return true;} + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_BeginFirmwareUpdateRequest sample_uavcan_protocol_file_BeginFirmwareUpdateRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate_res.h new file mode 100644 index 00000000..510920d4 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate_res.h @@ -0,0 +1,106 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE 129 +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_SIGNATURE (0xB7D725DF72724126ULL) +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ID 40 + +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK 0 +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_INVALID_MODE 1 +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_IN_PROGRESS 2 +#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_UNKNOWN 255 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_BeginFirmwareUpdate_cxx_iface; +#endif + +struct uavcan_protocol_file_BeginFirmwareUpdateResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_BeginFirmwareUpdate_cxx_iface; +#endif + uint8_t error; + struct { uint8_t len; uint8_t data[127]; }optional_error_message; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(struct uavcan_protocol_file_BeginFirmwareUpdateResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_BeginFirmwareUpdateResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_BeginFirmwareUpdateResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_BeginFirmwareUpdateResponse* msg, bool tao); +static inline bool _uavcan_protocol_file_BeginFirmwareUpdateResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_BeginFirmwareUpdateResponse* msg, bool tao); +void _uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_BeginFirmwareUpdateResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->error); + *bit_ofs += 8; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t optional_error_message_len = msg->optional_error_message.len > 127 ? 127 : msg->optional_error_message.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 7, &optional_error_message_len); + *bit_ofs += 7; + } + for (size_t i=0; i < optional_error_message_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->optional_error_message.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_file_BeginFirmwareUpdateResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_file_BeginFirmwareUpdateResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_BeginFirmwareUpdateResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->error); + *bit_ofs += 8; + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 7, false, &msg->optional_error_message.len); + *bit_ofs += 7; + } else { + msg->optional_error_message.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->optional_error_message.len > 127) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->optional_error_message.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->optional_error_message.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_BeginFirmwareUpdateResponse sample_uavcan_protocol_file_BeginFirmwareUpdateResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete.h new file mode 100644 index 00000000..f248e181 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_FILE_DELETE_ID 47 +#define UAVCAN_PROTOCOL_FILE_DELETE_SIGNATURE (0x78648C99170B47AAULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_file_Delete, UAVCAN_PROTOCOL_FILE_DELETE_ID, UAVCAN_PROTOCOL_FILE_DELETE_SIGNATURE, UAVCAN_PROTOCOL_FILE_DELETE_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_FILE_DELETE_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete_req.h new file mode 100644 index 00000000..2de184e0 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete_req.h @@ -0,0 +1,69 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_DELETE_REQUEST_MAX_SIZE 201 +#define UAVCAN_PROTOCOL_FILE_DELETE_REQUEST_SIGNATURE (0x78648C99170B47AAULL) +#define UAVCAN_PROTOCOL_FILE_DELETE_REQUEST_ID 47 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_Delete_cxx_iface; +#endif + +struct uavcan_protocol_file_DeleteRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_Delete_cxx_iface; +#endif + struct uavcan_protocol_file_Path path; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_DeleteRequest_encode(struct uavcan_protocol_file_DeleteRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_DeleteRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_DeleteRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_DeleteRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_DeleteRequest* msg, bool tao); +static inline bool _uavcan_protocol_file_DeleteRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_DeleteRequest* msg, bool tao); +void _uavcan_protocol_file_DeleteRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_DeleteRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + _uavcan_protocol_file_Path_encode(buffer, bit_ofs, &msg->path, tao); +} + +/* + decode uavcan_protocol_file_DeleteRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_file_DeleteRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_DeleteRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + if (_uavcan_protocol_file_Path_decode(transfer, bit_ofs, &msg->path, tao)) {return true;} + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_DeleteRequest sample_uavcan_protocol_file_DeleteRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete_res.h new file mode 100644 index 00000000..28e2d740 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete_res.h @@ -0,0 +1,69 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_DELETE_RESPONSE_MAX_SIZE 2 +#define UAVCAN_PROTOCOL_FILE_DELETE_RESPONSE_SIGNATURE (0x78648C99170B47AAULL) +#define UAVCAN_PROTOCOL_FILE_DELETE_RESPONSE_ID 47 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_Delete_cxx_iface; +#endif + +struct uavcan_protocol_file_DeleteResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_Delete_cxx_iface; +#endif + struct uavcan_protocol_file_Error error; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_DeleteResponse_encode(struct uavcan_protocol_file_DeleteResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_DeleteResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_DeleteResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_DeleteResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_DeleteResponse* msg, bool tao); +static inline bool _uavcan_protocol_file_DeleteResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_DeleteResponse* msg, bool tao); +void _uavcan_protocol_file_DeleteResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_DeleteResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + _uavcan_protocol_file_Error_encode(buffer, bit_ofs, &msg->error, tao); +} + +/* + decode uavcan_protocol_file_DeleteResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_file_DeleteResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_DeleteResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + if (_uavcan_protocol_file_Error_decode(transfer, bit_ofs, &msg->error, tao)) {return true;} + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_DeleteResponse sample_uavcan_protocol_file_DeleteResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.EntryType.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.EntryType.h new file mode 100644 index 00000000..ae475bc6 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.EntryType.h @@ -0,0 +1,69 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_MAX_SIZE 1 +#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_SIGNATURE (0x6924572FBB2086E5ULL) + +#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_FLAG_FILE 1 +#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_FLAG_DIRECTORY 2 +#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_FLAG_SYMLINK 4 +#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_FLAG_READABLE 8 +#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_FLAG_WRITEABLE 16 + + +struct uavcan_protocol_file_EntryType { + uint8_t flags; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_EntryType_encode(struct uavcan_protocol_file_EntryType* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_EntryType_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_EntryType* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_EntryType_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_EntryType* msg, bool tao); +static inline bool _uavcan_protocol_file_EntryType_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_EntryType* msg, bool tao); +void _uavcan_protocol_file_EntryType_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_EntryType* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->flags); + *bit_ofs += 8; +} + +/* + decode uavcan_protocol_file_EntryType, return true on failure, false on success +*/ +bool _uavcan_protocol_file_EntryType_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_EntryType* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->flags); + *bit_ofs += 8; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_EntryType sample_uavcan_protocol_file_EntryType_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Error.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Error.h new file mode 100644 index 00000000..f5f6176b --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Error.h @@ -0,0 +1,74 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_ERROR_MAX_SIZE 2 +#define UAVCAN_PROTOCOL_FILE_ERROR_SIGNATURE (0xA83071FFEA4FAE15ULL) + +#define UAVCAN_PROTOCOL_FILE_ERROR_OK 0 +#define UAVCAN_PROTOCOL_FILE_ERROR_UNKNOWN_ERROR 32767 +#define UAVCAN_PROTOCOL_FILE_ERROR_NOT_FOUND 2 +#define UAVCAN_PROTOCOL_FILE_ERROR_IO_ERROR 5 +#define UAVCAN_PROTOCOL_FILE_ERROR_ACCESS_DENIED 13 +#define UAVCAN_PROTOCOL_FILE_ERROR_IS_DIRECTORY 21 +#define UAVCAN_PROTOCOL_FILE_ERROR_INVALID_VALUE 22 +#define UAVCAN_PROTOCOL_FILE_ERROR_FILE_TOO_LARGE 27 +#define UAVCAN_PROTOCOL_FILE_ERROR_OUT_OF_SPACE 28 +#define UAVCAN_PROTOCOL_FILE_ERROR_NOT_IMPLEMENTED 38 + + +struct uavcan_protocol_file_Error { + int16_t value; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_Error_encode(struct uavcan_protocol_file_Error* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_Error_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_Error* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_Error_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_Error* msg, bool tao); +static inline bool _uavcan_protocol_file_Error_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_Error* msg, bool tao); +void _uavcan_protocol_file_Error_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_Error* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 16, &msg->value); + *bit_ofs += 16; +} + +/* + decode uavcan_protocol_file_Error, return true on failure, false on success +*/ +bool _uavcan_protocol_file_Error_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_Error* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 16, true, &msg->value); + *bit_ofs += 16; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_Error sample_uavcan_protocol_file_Error_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo.h new file mode 100644 index 00000000..f04fe6fd --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_ID 46 +#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_SIGNATURE (0x8C46E8AB568BDA79ULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_file_GetDirectoryEntryInfo, UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_ID, UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_SIGNATURE, UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo_req.h new file mode 100644 index 00000000..46532417 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo_req.h @@ -0,0 +1,75 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_REQUEST_MAX_SIZE 205 +#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_REQUEST_SIGNATURE (0x8C46E8AB568BDA79ULL) +#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_REQUEST_ID 46 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_GetDirectoryEntryInfo_cxx_iface; +#endif + +struct uavcan_protocol_file_GetDirectoryEntryInfoRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_GetDirectoryEntryInfo_cxx_iface; +#endif + uint32_t entry_index; + struct uavcan_protocol_file_Path directory_path; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode(struct uavcan_protocol_file_GetDirectoryEntryInfoRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_GetDirectoryEntryInfoRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetDirectoryEntryInfoRequest* msg, bool tao); +static inline bool _uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetDirectoryEntryInfoRequest* msg, bool tao); +void _uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetDirectoryEntryInfoRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->entry_index); + *bit_ofs += 32; + _uavcan_protocol_file_Path_encode(buffer, bit_ofs, &msg->directory_path, tao); +} + +/* + decode uavcan_protocol_file_GetDirectoryEntryInfoRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetDirectoryEntryInfoRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->entry_index); + *bit_ofs += 32; + + if (_uavcan_protocol_file_Path_decode(transfer, bit_ofs, &msg->directory_path, tao)) {return true;} + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_GetDirectoryEntryInfoRequest sample_uavcan_protocol_file_GetDirectoryEntryInfoRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo_res.h new file mode 100644 index 00000000..ad9432dc --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo_res.h @@ -0,0 +1,79 @@ +#pragma once +#include +#include +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_RESPONSE_MAX_SIZE 204 +#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_RESPONSE_SIGNATURE (0x8C46E8AB568BDA79ULL) +#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_RESPONSE_ID 46 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_GetDirectoryEntryInfo_cxx_iface; +#endif + +struct uavcan_protocol_file_GetDirectoryEntryInfoResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_GetDirectoryEntryInfo_cxx_iface; +#endif + struct uavcan_protocol_file_Error error; + struct uavcan_protocol_file_EntryType entry_type; + struct uavcan_protocol_file_Path entry_full_path; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode(struct uavcan_protocol_file_GetDirectoryEntryInfoResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_GetDirectoryEntryInfoResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetDirectoryEntryInfoResponse* msg, bool tao); +static inline bool _uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetDirectoryEntryInfoResponse* msg, bool tao); +void _uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetDirectoryEntryInfoResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + _uavcan_protocol_file_Error_encode(buffer, bit_ofs, &msg->error, false); + _uavcan_protocol_file_EntryType_encode(buffer, bit_ofs, &msg->entry_type, false); + _uavcan_protocol_file_Path_encode(buffer, bit_ofs, &msg->entry_full_path, tao); +} + +/* + decode uavcan_protocol_file_GetDirectoryEntryInfoResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetDirectoryEntryInfoResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + if (_uavcan_protocol_file_Error_decode(transfer, bit_ofs, &msg->error, false)) {return true;} + + if (_uavcan_protocol_file_EntryType_decode(transfer, bit_ofs, &msg->entry_type, false)) {return true;} + + if (_uavcan_protocol_file_Path_decode(transfer, bit_ofs, &msg->entry_full_path, tao)) {return true;} + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_GetDirectoryEntryInfoResponse sample_uavcan_protocol_file_GetDirectoryEntryInfoResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo.h new file mode 100644 index 00000000..96ef7506 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_FILE_GETINFO_ID 45 +#define UAVCAN_PROTOCOL_FILE_GETINFO_SIGNATURE (0x5004891EE8A27531ULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_file_GetInfo, UAVCAN_PROTOCOL_FILE_GETINFO_ID, UAVCAN_PROTOCOL_FILE_GETINFO_SIGNATURE, UAVCAN_PROTOCOL_FILE_GETINFO_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_FILE_GETINFO_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo_req.h new file mode 100644 index 00000000..b629fc3e --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo_req.h @@ -0,0 +1,69 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_GETINFO_REQUEST_MAX_SIZE 201 +#define UAVCAN_PROTOCOL_FILE_GETINFO_REQUEST_SIGNATURE (0x5004891EE8A27531ULL) +#define UAVCAN_PROTOCOL_FILE_GETINFO_REQUEST_ID 45 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_GetInfo_cxx_iface; +#endif + +struct uavcan_protocol_file_GetInfoRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_GetInfo_cxx_iface; +#endif + struct uavcan_protocol_file_Path path; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_GetInfoRequest_encode(struct uavcan_protocol_file_GetInfoRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_GetInfoRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_GetInfoRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_GetInfoRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetInfoRequest* msg, bool tao); +static inline bool _uavcan_protocol_file_GetInfoRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetInfoRequest* msg, bool tao); +void _uavcan_protocol_file_GetInfoRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetInfoRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + _uavcan_protocol_file_Path_encode(buffer, bit_ofs, &msg->path, tao); +} + +/* + decode uavcan_protocol_file_GetInfoRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_file_GetInfoRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetInfoRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + if (_uavcan_protocol_file_Path_decode(transfer, bit_ofs, &msg->path, tao)) {return true;} + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_GetInfoRequest sample_uavcan_protocol_file_GetInfoRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo_res.h new file mode 100644 index 00000000..cc408fcf --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo_res.h @@ -0,0 +1,80 @@ +#pragma once +#include +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_GETINFO_RESPONSE_MAX_SIZE 8 +#define UAVCAN_PROTOCOL_FILE_GETINFO_RESPONSE_SIGNATURE (0x5004891EE8A27531ULL) +#define UAVCAN_PROTOCOL_FILE_GETINFO_RESPONSE_ID 45 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_GetInfo_cxx_iface; +#endif + +struct uavcan_protocol_file_GetInfoResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_GetInfo_cxx_iface; +#endif + uint64_t size; + struct uavcan_protocol_file_Error error; + struct uavcan_protocol_file_EntryType entry_type; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_GetInfoResponse_encode(struct uavcan_protocol_file_GetInfoResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_GetInfoResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_GetInfoResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_GetInfoResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetInfoResponse* msg, bool tao); +static inline bool _uavcan_protocol_file_GetInfoResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetInfoResponse* msg, bool tao); +void _uavcan_protocol_file_GetInfoResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetInfoResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 40, &msg->size); + *bit_ofs += 40; + _uavcan_protocol_file_Error_encode(buffer, bit_ofs, &msg->error, false); + _uavcan_protocol_file_EntryType_encode(buffer, bit_ofs, &msg->entry_type, tao); +} + +/* + decode uavcan_protocol_file_GetInfoResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_file_GetInfoResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_GetInfoResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 40, false, &msg->size); + *bit_ofs += 40; + + if (_uavcan_protocol_file_Error_decode(transfer, bit_ofs, &msg->error, false)) {return true;} + + if (_uavcan_protocol_file_EntryType_decode(transfer, bit_ofs, &msg->entry_type, tao)) {return true;} + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_GetInfoResponse sample_uavcan_protocol_file_GetInfoResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Path.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Path.h new file mode 100644 index 00000000..025cfb1f --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Path.h @@ -0,0 +1,90 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_PATH_MAX_SIZE 201 +#define UAVCAN_PROTOCOL_FILE_PATH_SIGNATURE (0x12AEFC50878A43E2ULL) + +#define UAVCAN_PROTOCOL_FILE_PATH_SEPARATOR 47 + + +struct uavcan_protocol_file_Path { + struct { uint8_t len; uint8_t data[200]; }path; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_Path_encode(struct uavcan_protocol_file_Path* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_Path_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_Path* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_Path_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_Path* msg, bool tao); +static inline bool _uavcan_protocol_file_Path_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_Path* msg, bool tao); +void _uavcan_protocol_file_Path_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_Path* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t path_len = msg->path.len > 200 ? 200 : msg->path.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 8, &path_len); + *bit_ofs += 8; + } + for (size_t i=0; i < path_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->path.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_file_Path, return true on failure, false on success +*/ +bool _uavcan_protocol_file_Path_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_Path* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->path.len); + *bit_ofs += 8; + } else { + msg->path.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->path.len > 200) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->path.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->path.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_Path sample_uavcan_protocol_file_Path_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read.h new file mode 100644 index 00000000..8d0d55e7 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_FILE_READ_ID 48 +#define UAVCAN_PROTOCOL_FILE_READ_SIGNATURE (0x8DCDCA939F33F678ULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_file_Read, UAVCAN_PROTOCOL_FILE_READ_ID, UAVCAN_PROTOCOL_FILE_READ_SIGNATURE, UAVCAN_PROTOCOL_FILE_READ_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_FILE_READ_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read_req.h new file mode 100644 index 00000000..d2978a6a --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read_req.h @@ -0,0 +1,75 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_READ_REQUEST_MAX_SIZE 206 +#define UAVCAN_PROTOCOL_FILE_READ_REQUEST_SIGNATURE (0x8DCDCA939F33F678ULL) +#define UAVCAN_PROTOCOL_FILE_READ_REQUEST_ID 48 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_Read_cxx_iface; +#endif + +struct uavcan_protocol_file_ReadRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_Read_cxx_iface; +#endif + uint64_t offset; + struct uavcan_protocol_file_Path path; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_ReadRequest_encode(struct uavcan_protocol_file_ReadRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_ReadRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_ReadRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_ReadRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_ReadRequest* msg, bool tao); +static inline bool _uavcan_protocol_file_ReadRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_ReadRequest* msg, bool tao); +void _uavcan_protocol_file_ReadRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_ReadRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 40, &msg->offset); + *bit_ofs += 40; + _uavcan_protocol_file_Path_encode(buffer, bit_ofs, &msg->path, tao); +} + +/* + decode uavcan_protocol_file_ReadRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_file_ReadRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_ReadRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 40, false, &msg->offset); + *bit_ofs += 40; + + if (_uavcan_protocol_file_Path_decode(transfer, bit_ofs, &msg->path, tao)) {return true;} + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_ReadRequest sample_uavcan_protocol_file_ReadRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read_res.h new file mode 100644 index 00000000..f2a814e4 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read_res.h @@ -0,0 +1,100 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_READ_RESPONSE_MAX_SIZE 260 +#define UAVCAN_PROTOCOL_FILE_READ_RESPONSE_SIGNATURE (0x8DCDCA939F33F678ULL) +#define UAVCAN_PROTOCOL_FILE_READ_RESPONSE_ID 48 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_Read_cxx_iface; +#endif + +struct uavcan_protocol_file_ReadResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_Read_cxx_iface; +#endif + struct uavcan_protocol_file_Error error; + struct { uint16_t len; uint8_t data[256]; }data; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_ReadResponse_encode(struct uavcan_protocol_file_ReadResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_ReadResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_ReadResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_ReadResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_ReadResponse* msg, bool tao); +static inline bool _uavcan_protocol_file_ReadResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_ReadResponse* msg, bool tao); +void _uavcan_protocol_file_ReadResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_ReadResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + _uavcan_protocol_file_Error_encode(buffer, bit_ofs, &msg->error, false); +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint16_t data_len = msg->data.len > 256 ? 256 : msg->data.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 9, &data_len); + *bit_ofs += 9; + } + for (size_t i=0; i < data_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->data.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_file_ReadResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_file_ReadResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_ReadResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + if (_uavcan_protocol_file_Error_decode(transfer, bit_ofs, &msg->error, false)) {return true;} + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 9, false, &msg->data.len); + *bit_ofs += 9; + } else { + msg->data.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->data.len > 256) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->data.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->data.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_ReadResponse sample_uavcan_protocol_file_ReadResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write.h new file mode 100644 index 00000000..348e174c --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_FILE_WRITE_ID 49 +#define UAVCAN_PROTOCOL_FILE_WRITE_SIGNATURE (0x515AA1DC77E58429ULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_file_Write, UAVCAN_PROTOCOL_FILE_WRITE_ID, UAVCAN_PROTOCOL_FILE_WRITE_SIGNATURE, UAVCAN_PROTOCOL_FILE_WRITE_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_FILE_WRITE_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write_req.h new file mode 100644 index 00000000..022a9da8 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write_req.h @@ -0,0 +1,106 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_WRITE_REQUEST_MAX_SIZE 399 +#define UAVCAN_PROTOCOL_FILE_WRITE_REQUEST_SIGNATURE (0x515AA1DC77E58429ULL) +#define UAVCAN_PROTOCOL_FILE_WRITE_REQUEST_ID 49 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_Write_cxx_iface; +#endif + +struct uavcan_protocol_file_WriteRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_Write_cxx_iface; +#endif + uint64_t offset; + struct uavcan_protocol_file_Path path; + struct { uint8_t len; uint8_t data[192]; }data; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_WriteRequest_encode(struct uavcan_protocol_file_WriteRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_WriteRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_WriteRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_WriteRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_WriteRequest* msg, bool tao); +static inline bool _uavcan_protocol_file_WriteRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_WriteRequest* msg, bool tao); +void _uavcan_protocol_file_WriteRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_WriteRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 40, &msg->offset); + *bit_ofs += 40; + _uavcan_protocol_file_Path_encode(buffer, bit_ofs, &msg->path, false); +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t data_len = msg->data.len > 192 ? 192 : msg->data.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 8, &data_len); + *bit_ofs += 8; + } + for (size_t i=0; i < data_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->data.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_file_WriteRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_file_WriteRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_WriteRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 40, false, &msg->offset); + *bit_ofs += 40; + + if (_uavcan_protocol_file_Path_decode(transfer, bit_ofs, &msg->path, false)) {return true;} + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->data.len); + *bit_ofs += 8; + } else { + msg->data.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->data.len > 192) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->data.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->data.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_WriteRequest sample_uavcan_protocol_file_WriteRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write_res.h new file mode 100644 index 00000000..76049df9 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write_res.h @@ -0,0 +1,69 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_FILE_WRITE_RESPONSE_MAX_SIZE 2 +#define UAVCAN_PROTOCOL_FILE_WRITE_RESPONSE_SIGNATURE (0x515AA1DC77E58429ULL) +#define UAVCAN_PROTOCOL_FILE_WRITE_RESPONSE_ID 49 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_file_Write_cxx_iface; +#endif + +struct uavcan_protocol_file_WriteResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_file_Write_cxx_iface; +#endif + struct uavcan_protocol_file_Error error; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_file_WriteResponse_encode(struct uavcan_protocol_file_WriteResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_file_WriteResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_WriteResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_file_WriteResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_WriteResponse* msg, bool tao); +static inline bool _uavcan_protocol_file_WriteResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_WriteResponse* msg, bool tao); +void _uavcan_protocol_file_WriteResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_file_WriteResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + _uavcan_protocol_file_Error_encode(buffer, bit_ofs, &msg->error, tao); +} + +/* + decode uavcan_protocol_file_WriteResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_file_WriteResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_file_WriteResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + if (_uavcan_protocol_file_Error_decode(transfer, bit_ofs, &msg->error, tao)) {return true;} + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_WriteResponse sample_uavcan_protocol_file_WriteResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.Empty.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.Empty.h new file mode 100644 index 00000000..e05acccc --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.Empty.h @@ -0,0 +1,57 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_PARAM_EMPTY_MAX_SIZE 0 +#define UAVCAN_PROTOCOL_PARAM_EMPTY_SIGNATURE (0x6C4D0E8EF37361DFULL) + + +struct uavcan_protocol_param_Empty { +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_param_Empty_encode(struct uavcan_protocol_param_Empty* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_param_Empty_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_Empty* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_param_Empty_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_Empty* msg, bool tao); +static inline bool _uavcan_protocol_param_Empty_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_Empty* msg, bool tao); +void _uavcan_protocol_param_Empty_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_Empty* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + +} + +/* + decode uavcan_protocol_param_Empty, return true on failure, false on success +*/ +bool _uavcan_protocol_param_Empty_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_Empty* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_Empty sample_uavcan_protocol_param_Empty_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode.h new file mode 100644 index 00000000..a15c5af2 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID 10 +#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE (0x3B131AC5EB69D2CDULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_param_ExecuteOpcode, UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID, UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE, UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode_req.h new file mode 100644 index 00000000..d01e3fa1 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode_req.h @@ -0,0 +1,79 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_MAX_SIZE 7 +#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_SIGNATURE (0x3B131AC5EB69D2CDULL) +#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_ID 10 + +#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_SAVE 0 +#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_ERASE 1 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_param_ExecuteOpcode_cxx_iface; +#endif + +struct uavcan_protocol_param_ExecuteOpcodeRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_param_ExecuteOpcode_cxx_iface; +#endif + uint8_t opcode; + int64_t argument; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_param_ExecuteOpcodeRequest_encode(struct uavcan_protocol_param_ExecuteOpcodeRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_param_ExecuteOpcodeRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_ExecuteOpcodeRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_param_ExecuteOpcodeRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_ExecuteOpcodeRequest* msg, bool tao); +static inline bool _uavcan_protocol_param_ExecuteOpcodeRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_ExecuteOpcodeRequest* msg, bool tao); +void _uavcan_protocol_param_ExecuteOpcodeRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_ExecuteOpcodeRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->opcode); + *bit_ofs += 8; + canardEncodeScalar(buffer, *bit_ofs, 48, &msg->argument); + *bit_ofs += 48; +} + +/* + decode uavcan_protocol_param_ExecuteOpcodeRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_param_ExecuteOpcodeRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_ExecuteOpcodeRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->opcode); + *bit_ofs += 8; + + canardDecodeScalar(transfer, *bit_ofs, 48, true, &msg->argument); + *bit_ofs += 48; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_ExecuteOpcodeRequest sample_uavcan_protocol_param_ExecuteOpcodeRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode_res.h new file mode 100644 index 00000000..3b6a85d0 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode_res.h @@ -0,0 +1,76 @@ +#pragma once +#include +#include +#include + + +#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE 7 +#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_SIGNATURE (0x3B131AC5EB69D2CDULL) +#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_ID 10 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_param_ExecuteOpcode_cxx_iface; +#endif + +struct uavcan_protocol_param_ExecuteOpcodeResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_param_ExecuteOpcode_cxx_iface; +#endif + int64_t argument; + bool ok; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_param_ExecuteOpcodeResponse_encode(struct uavcan_protocol_param_ExecuteOpcodeResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_param_ExecuteOpcodeResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_ExecuteOpcodeResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_param_ExecuteOpcodeResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_ExecuteOpcodeResponse* msg, bool tao); +static inline bool _uavcan_protocol_param_ExecuteOpcodeResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_ExecuteOpcodeResponse* msg, bool tao); +void _uavcan_protocol_param_ExecuteOpcodeResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_ExecuteOpcodeResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 48, &msg->argument); + *bit_ofs += 48; + canardEncodeScalar(buffer, *bit_ofs, 1, &msg->ok); + *bit_ofs += 1; +} + +/* + decode uavcan_protocol_param_ExecuteOpcodeResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_param_ExecuteOpcodeResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_ExecuteOpcodeResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 48, true, &msg->argument); + *bit_ofs += 48; + + canardDecodeScalar(transfer, *bit_ofs, 1, false, &msg->ok); + *bit_ofs += 1; + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_ExecuteOpcodeResponse sample_uavcan_protocol_param_ExecuteOpcodeResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet.h new file mode 100644 index 00000000..21ae8cb5 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet.h @@ -0,0 +1,11 @@ +#pragma once +#include +#include + +#define UAVCAN_PROTOCOL_PARAM_GETSET_ID 11 +#define UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE (0xA7B622F939D1A4D5ULL) + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +#include +SERVICE_MESSAGE_CXX_IFACE(uavcan_protocol_param_GetSet, UAVCAN_PROTOCOL_PARAM_GETSET_ID, UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE, UAVCAN_PROTOCOL_PARAM_GETSET_REQUEST_MAX_SIZE, UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE); +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet_req.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet_req.h new file mode 100644 index 00000000..108a4fec --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet_req.h @@ -0,0 +1,106 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_PARAM_GETSET_REQUEST_MAX_SIZE 224 +#define UAVCAN_PROTOCOL_PARAM_GETSET_REQUEST_SIGNATURE (0xA7B622F939D1A4D5ULL) +#define UAVCAN_PROTOCOL_PARAM_GETSET_REQUEST_ID 11 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_param_GetSet_cxx_iface; +#endif + +struct uavcan_protocol_param_GetSetRequest { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_param_GetSet_cxx_iface; +#endif + uint16_t index; + struct uavcan_protocol_param_Value value; + struct { uint8_t len; uint8_t data[92]; }name; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_param_GetSetRequest_encode(struct uavcan_protocol_param_GetSetRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_param_GetSetRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_GetSetRequest* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_param_GetSetRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_GetSetRequest* msg, bool tao); +static inline bool _uavcan_protocol_param_GetSetRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_GetSetRequest* msg, bool tao); +void _uavcan_protocol_param_GetSetRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_GetSetRequest* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 13, &msg->index); + *bit_ofs += 13; + _uavcan_protocol_param_Value_encode(buffer, bit_ofs, &msg->value, false); +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t name_len = msg->name.len > 92 ? 92 : msg->name.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 7, &name_len); + *bit_ofs += 7; + } + for (size_t i=0; i < name_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->name.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_param_GetSetRequest, return true on failure, false on success +*/ +bool _uavcan_protocol_param_GetSetRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_GetSetRequest* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 13, false, &msg->index); + *bit_ofs += 13; + + if (_uavcan_protocol_param_Value_decode(transfer, bit_ofs, &msg->value, false)) {return true;} + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 7, false, &msg->name.len); + *bit_ofs += 7; + } else { + msg->name.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->name.len > 92) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->name.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->name.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_GetSetRequest sample_uavcan_protocol_param_GetSetRequest_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet_res.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet_res.h new file mode 100644 index 00000000..0e29be83 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet_res.h @@ -0,0 +1,125 @@ +#pragma once +#include +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE 371 +#define UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_SIGNATURE (0xA7B622F939D1A4D5ULL) +#define UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_ID 11 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class uavcan_protocol_param_GetSet_cxx_iface; +#endif + +struct uavcan_protocol_param_GetSetResponse { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = uavcan_protocol_param_GetSet_cxx_iface; +#endif + struct uavcan_protocol_param_Value value; + struct uavcan_protocol_param_Value default_value; + struct uavcan_protocol_param_NumericValue max_value; + struct uavcan_protocol_param_NumericValue min_value; + struct { uint8_t len; uint8_t data[92]; }name; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_param_GetSetResponse_encode(struct uavcan_protocol_param_GetSetResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_param_GetSetResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_GetSetResponse* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_param_GetSetResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_GetSetResponse* msg, bool tao); +static inline bool _uavcan_protocol_param_GetSetResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_GetSetResponse* msg, bool tao); +void _uavcan_protocol_param_GetSetResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_GetSetResponse* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + *bit_ofs += 5; + _uavcan_protocol_param_Value_encode(buffer, bit_ofs, &msg->value, false); + *bit_ofs += 5; + _uavcan_protocol_param_Value_encode(buffer, bit_ofs, &msg->default_value, false); + *bit_ofs += 6; + _uavcan_protocol_param_NumericValue_encode(buffer, bit_ofs, &msg->max_value, false); + *bit_ofs += 6; + _uavcan_protocol_param_NumericValue_encode(buffer, bit_ofs, &msg->min_value, false); +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t name_len = msg->name.len > 92 ? 92 : msg->name.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 7, &name_len); + *bit_ofs += 7; + } + for (size_t i=0; i < name_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->name.data[i]); + *bit_ofs += 8; + } +} + +/* + decode uavcan_protocol_param_GetSetResponse, return true on failure, false on success +*/ +bool _uavcan_protocol_param_GetSetResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_GetSetResponse* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + *bit_ofs += 5; + + if (_uavcan_protocol_param_Value_decode(transfer, bit_ofs, &msg->value, false)) {return true;} + + *bit_ofs += 5; + + if (_uavcan_protocol_param_Value_decode(transfer, bit_ofs, &msg->default_value, false)) {return true;} + + *bit_ofs += 6; + + if (_uavcan_protocol_param_NumericValue_decode(transfer, bit_ofs, &msg->max_value, false)) {return true;} + + *bit_ofs += 6; + + if (_uavcan_protocol_param_NumericValue_decode(transfer, bit_ofs, &msg->min_value, false)) {return true;} + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 7, false, &msg->name.len); + *bit_ofs += 7; + } else { + msg->name.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->name.len > 92) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->name.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->name.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_GetSetResponse sample_uavcan_protocol_param_GetSetResponse_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.NumericValue.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.NumericValue.h new file mode 100644 index 00000000..462f1da8 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.NumericValue.h @@ -0,0 +1,120 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_MAX_SIZE 9 +#define UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_SIGNATURE (0xDA6D6FEA22E3587ULL) + +enum uavcan_protocol_param_NumericValue_type_t { + UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_EMPTY, + UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE, + UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_REAL_VALUE, +}; + + +struct uavcan_protocol_param_NumericValue { + enum uavcan_protocol_param_NumericValue_type_t union_tag; + union { + struct uavcan_protocol_param_Empty empty; + int64_t integer_value; + float real_value; + }; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_param_NumericValue_encode(struct uavcan_protocol_param_NumericValue* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_param_NumericValue_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_NumericValue* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_param_NumericValue_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_NumericValue* msg, bool tao); +static inline bool _uavcan_protocol_param_NumericValue_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_NumericValue* msg, bool tao); +void _uavcan_protocol_param_NumericValue_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_NumericValue* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + uint8_t union_tag = msg->union_tag; + canardEncodeScalar(buffer, *bit_ofs, 2, &union_tag); + *bit_ofs += 2; + + switch(msg->union_tag) { + case UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_EMPTY: { + _uavcan_protocol_param_Empty_encode(buffer, bit_ofs, &msg->empty, tao); + break; + } + case UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE: { + canardEncodeScalar(buffer, *bit_ofs, 64, &msg->integer_value); + *bit_ofs += 64; + break; + } + case UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_REAL_VALUE: { + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->real_value); + *bit_ofs += 32; + break; + } + } +} + +/* + decode uavcan_protocol_param_NumericValue, return true on failure, false on success +*/ +bool _uavcan_protocol_param_NumericValue_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_NumericValue* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + uint8_t union_tag; + canardDecodeScalar(transfer, *bit_ofs, 2, false, &union_tag); + *bit_ofs += 2; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (union_tag >= 3) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + msg->union_tag = (enum uavcan_protocol_param_NumericValue_type_t)union_tag; + + switch(msg->union_tag) { + case UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_EMPTY: { + if (_uavcan_protocol_param_Empty_decode(transfer, bit_ofs, &msg->empty, tao)) {return true;} + break; + } + + case UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE: { + canardDecodeScalar(transfer, *bit_ofs, 64, true, &msg->integer_value); + *bit_ofs += 64; + break; + } + + case UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_REAL_VALUE: { + canardDecodeScalar(transfer, *bit_ofs, 32, true, &msg->real_value); + *bit_ofs += 32; + break; + } + + } + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_NumericValue sample_uavcan_protocol_param_NumericValue_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.Value.h b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.Value.h new file mode 100644 index 00000000..a46b3ea0 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/include/uavcan.protocol.param.Value.h @@ -0,0 +1,171 @@ +#pragma once +#include +#include +#include +#include + + +#define UAVCAN_PROTOCOL_PARAM_VALUE_MAX_SIZE 130 +#define UAVCAN_PROTOCOL_PARAM_VALUE_SIGNATURE (0x29F14BF484727267ULL) + +enum uavcan_protocol_param_Value_type_t { + UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY, + UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE, + UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE, + UAVCAN_PROTOCOL_PARAM_VALUE_BOOLEAN_VALUE, + UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE, +}; + + +struct uavcan_protocol_param_Value { + enum uavcan_protocol_param_Value_type_t union_tag; + union { + struct uavcan_protocol_param_Empty empty; + int64_t integer_value; + float real_value; + uint8_t boolean_value; + struct { uint8_t len; uint8_t data[128]; }string_value; + }; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t uavcan_protocol_param_Value_encode(struct uavcan_protocol_param_Value* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool uavcan_protocol_param_Value_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_Value* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _uavcan_protocol_param_Value_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_Value* msg, bool tao); +static inline bool _uavcan_protocol_param_Value_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_Value* msg, bool tao); +void _uavcan_protocol_param_Value_encode(uint8_t* buffer, uint32_t* bit_ofs, struct uavcan_protocol_param_Value* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + uint8_t union_tag = msg->union_tag; + canardEncodeScalar(buffer, *bit_ofs, 3, &union_tag); + *bit_ofs += 3; + + switch(msg->union_tag) { + case UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY: { + _uavcan_protocol_param_Empty_encode(buffer, bit_ofs, &msg->empty, tao); + break; + } + case UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE: { + canardEncodeScalar(buffer, *bit_ofs, 64, &msg->integer_value); + *bit_ofs += 64; + break; + } + case UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE: { + canardEncodeScalar(buffer, *bit_ofs, 32, &msg->real_value); + *bit_ofs += 32; + break; + } + case UAVCAN_PROTOCOL_PARAM_VALUE_BOOLEAN_VALUE: { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->boolean_value); + *bit_ofs += 8; + break; + } + case UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE: { +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t string_value_len = msg->string_value.len > 128 ? 128 : msg->string_value.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 8, &string_value_len); + *bit_ofs += 8; + } + for (size_t i=0; i < string_value_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->string_value.data[i]); + *bit_ofs += 8; + } + break; + } + } +} + +/* + decode uavcan_protocol_param_Value, return true on failure, false on success +*/ +bool _uavcan_protocol_param_Value_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct uavcan_protocol_param_Value* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + uint8_t union_tag; + canardDecodeScalar(transfer, *bit_ofs, 3, false, &union_tag); + *bit_ofs += 3; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (union_tag >= 5) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + msg->union_tag = (enum uavcan_protocol_param_Value_type_t)union_tag; + + switch(msg->union_tag) { + case UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY: { + if (_uavcan_protocol_param_Empty_decode(transfer, bit_ofs, &msg->empty, tao)) {return true;} + break; + } + + case UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE: { + canardDecodeScalar(transfer, *bit_ofs, 64, true, &msg->integer_value); + *bit_ofs += 64; + break; + } + + case UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE: { + canardDecodeScalar(transfer, *bit_ofs, 32, true, &msg->real_value); + *bit_ofs += 32; + break; + } + + case UAVCAN_PROTOCOL_PARAM_VALUE_BOOLEAN_VALUE: { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->boolean_value); + *bit_ofs += 8; + break; + } + + case UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE: { + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->string_value.len); + *bit_ofs += 8; + } else { + msg->string_value.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->string_value.len > 128) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->string_value.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->string_value.data[i]); + *bit_ofs += 8; + } + break; + } + + } + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_Value sample_uavcan_protocol_param_Value_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +#endif +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.RPMCommand.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.RPMCommand.c new file mode 100644 index 00000000..c6c12491 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.RPMCommand.c @@ -0,0 +1,67 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_equipment_esc_RPMCommand_encode(struct uavcan_equipment_esc_RPMCommand* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_EQUIPMENT_ESC_RPMCOMMAND_MAX_SIZE); + _uavcan_equipment_esc_RPMCommand_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_equipment_esc_RPMCommand_decode(const CanardRxTransfer* transfer, struct uavcan_equipment_esc_RPMCommand* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_EQUIPMENT_ESC_RPMCOMMAND_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_equipment_esc_RPMCommand_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_equipment_esc_RPMCommand sample_uavcan_equipment_esc_RPMCommand_msg(void) { + struct uavcan_equipment_esc_RPMCommand msg; + + msg.rpm.len = (uint8_t)random_range_unsigned_val(0, 20); + for (size_t i=0; i < msg.rpm.len; i++) { + msg.rpm.data[i] = (int32_t)random_bitlen_signed_val(18); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.RawCommand.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.RawCommand.c new file mode 100644 index 00000000..40e6e1ff --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.RawCommand.c @@ -0,0 +1,67 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_equipment_esc_RawCommand_encode(struct uavcan_equipment_esc_RawCommand* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_MAX_SIZE); + _uavcan_equipment_esc_RawCommand_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_equipment_esc_RawCommand_decode(const CanardRxTransfer* transfer, struct uavcan_equipment_esc_RawCommand* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_equipment_esc_RawCommand_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_equipment_esc_RawCommand sample_uavcan_equipment_esc_RawCommand_msg(void) { + struct uavcan_equipment_esc_RawCommand msg; + + msg.cmd.len = (uint8_t)random_range_unsigned_val(0, 20); + for (size_t i=0; i < msg.cmd.len; i++) { + msg.cmd.data[i] = (int16_t)random_bitlen_signed_val(14); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.Status.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.Status.c new file mode 100644 index 00000000..3a7d8530 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.Status.c @@ -0,0 +1,70 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_equipment_esc_Status_encode(struct uavcan_equipment_esc_Status* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE); + _uavcan_equipment_esc_Status_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_equipment_esc_Status_decode(const CanardRxTransfer* transfer, struct uavcan_equipment_esc_Status* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_equipment_esc_Status_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_equipment_esc_Status sample_uavcan_equipment_esc_Status_msg(void) { + struct uavcan_equipment_esc_Status msg; + + msg.error_count = (uint32_t)random_bitlen_unsigned_val(32); + msg.voltage = random_float16_val(); + msg.current = random_float16_val(); + msg.temperature = random_float16_val(); + msg.rpm = (int32_t)random_bitlen_signed_val(18); + msg.power_rating_pct = (uint8_t)random_bitlen_unsigned_val(7); + msg.esc_index = (uint8_t)random_bitlen_unsigned_val(5); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.StatusExtended.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.StatusExtended.c new file mode 100644 index 00000000..46dbac5b --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.StatusExtended.c @@ -0,0 +1,69 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_equipment_esc_StatusExtended_encode(struct uavcan_equipment_esc_StatusExtended* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_MAX_SIZE); + _uavcan_equipment_esc_StatusExtended_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_equipment_esc_StatusExtended_decode(const CanardRxTransfer* transfer, struct uavcan_equipment_esc_StatusExtended* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_equipment_esc_StatusExtended_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_equipment_esc_StatusExtended sample_uavcan_equipment_esc_StatusExtended_msg(void) { + struct uavcan_equipment_esc_StatusExtended msg; + + msg.input_pct = (uint8_t)random_bitlen_unsigned_val(7); + msg.output_pct = (uint8_t)random_bitlen_unsigned_val(7); + msg.motor_temperature_degC = (int16_t)random_bitlen_signed_val(9); + msg.motor_angle = (uint16_t)random_bitlen_unsigned_val(9); + msg.status_flags = (uint32_t)random_bitlen_unsigned_val(19); + msg.esc_index = (uint8_t)random_bitlen_unsigned_val(5); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.safety.ArmingStatus.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.safety.ArmingStatus.c new file mode 100644 index 00000000..e5f4b6be --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.equipment.safety.ArmingStatus.c @@ -0,0 +1,64 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_equipment_safety_ArmingStatus_encode(struct uavcan_equipment_safety_ArmingStatus* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_MAX_SIZE); + _uavcan_equipment_safety_ArmingStatus_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_equipment_safety_ArmingStatus_decode(const CanardRxTransfer* transfer, struct uavcan_equipment_safety_ArmingStatus* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_equipment_safety_ArmingStatus_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_equipment_safety_ArmingStatus sample_uavcan_equipment_safety_ArmingStatus_msg(void) { + struct uavcan_equipment_safety_ArmingStatus msg; + + msg.status = (uint8_t)random_bitlen_unsigned_val(8); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.GetNodeInfo_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.GetNodeInfo_req.c new file mode 100644 index 00000000..f10b60bb --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.GetNodeInfo_req.c @@ -0,0 +1,64 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_GetNodeInfoRequest_encode(struct uavcan_protocol_GetNodeInfoRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_GETNODEINFO_REQUEST_MAX_SIZE); + _uavcan_protocol_GetNodeInfoRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_GetNodeInfoRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_GetNodeInfoRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_GETNODEINFO_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_GetNodeInfoRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_GetNodeInfoRequest sample_uavcan_protocol_GetNodeInfoRequest_msg(void) { + struct uavcan_protocol_GetNodeInfoRequest msg; + + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.GetNodeInfo_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.GetNodeInfo_res.c new file mode 100644 index 00000000..bdfd1af3 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.GetNodeInfo_res.c @@ -0,0 +1,70 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_GetNodeInfoResponse_encode(struct uavcan_protocol_GetNodeInfoResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE); + _uavcan_protocol_GetNodeInfoResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_GetNodeInfoResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_GetNodeInfoResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_GetNodeInfoResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_GetNodeInfoResponse sample_uavcan_protocol_GetNodeInfoResponse_msg(void) { + struct uavcan_protocol_GetNodeInfoResponse msg; + + msg.status = sample_uavcan_protocol_NodeStatus_msg(); + msg.software_version = sample_uavcan_protocol_SoftwareVersion_msg(); + msg.hardware_version = sample_uavcan_protocol_HardwareVersion_msg(); + msg.name.len = (uint8_t)random_range_unsigned_val(0, 80); + for (size_t i=0; i < msg.name.len; i++) { + msg.name.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.HardwareVersion.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.HardwareVersion.c new file mode 100644 index 00000000..ead23919 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.HardwareVersion.c @@ -0,0 +1,72 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_HardwareVersion_encode(struct uavcan_protocol_HardwareVersion* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_HARDWAREVERSION_MAX_SIZE); + _uavcan_protocol_HardwareVersion_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_HardwareVersion_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_HardwareVersion* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_HARDWAREVERSION_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_HardwareVersion_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_HardwareVersion sample_uavcan_protocol_HardwareVersion_msg(void) { + struct uavcan_protocol_HardwareVersion msg; + + msg.major = (uint8_t)random_bitlen_unsigned_val(8); + msg.minor = (uint8_t)random_bitlen_unsigned_val(8); + for (size_t i=0; i < 16; i++) { + msg.unique_id[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + msg.certificate_of_authenticity.len = (uint8_t)random_range_unsigned_val(0, 255); + for (size_t i=0; i < msg.certificate_of_authenticity.len; i++) { + msg.certificate_of_authenticity.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.NodeStatus.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.NodeStatus.c new file mode 100644 index 00000000..6d5ece0d --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.NodeStatus.c @@ -0,0 +1,68 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_NodeStatus_encode(struct uavcan_protocol_NodeStatus* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE); + _uavcan_protocol_NodeStatus_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_NodeStatus_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_NodeStatus* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_NodeStatus_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_NodeStatus sample_uavcan_protocol_NodeStatus_msg(void) { + struct uavcan_protocol_NodeStatus msg; + + msg.uptime_sec = (uint32_t)random_bitlen_unsigned_val(32); + msg.health = (uint8_t)random_bitlen_unsigned_val(2); + msg.mode = (uint8_t)random_bitlen_unsigned_val(3); + msg.sub_mode = (uint8_t)random_bitlen_unsigned_val(3); + msg.vendor_specific_status_code = (uint16_t)random_bitlen_unsigned_val(16); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.RestartNode_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.RestartNode_req.c new file mode 100644 index 00000000..19b13a4a --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.RestartNode_req.c @@ -0,0 +1,65 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_RestartNodeRequest_encode(struct uavcan_protocol_RestartNodeRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_MAX_SIZE); + _uavcan_protocol_RestartNodeRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_RestartNodeRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_RestartNodeRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_RestartNodeRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_RestartNodeRequest sample_uavcan_protocol_RestartNodeRequest_msg(void) { + struct uavcan_protocol_RestartNodeRequest msg; + + msg.magic_number = (uint64_t)random_bitlen_unsigned_val(40); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.RestartNode_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.RestartNode_res.c new file mode 100644 index 00000000..42d5105a --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.RestartNode_res.c @@ -0,0 +1,64 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_RestartNodeResponse_encode(struct uavcan_protocol_RestartNodeResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_MAX_SIZE); + _uavcan_protocol_RestartNodeResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_RestartNodeResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_RestartNodeResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_RestartNodeResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_RestartNodeResponse sample_uavcan_protocol_RestartNodeResponse_msg(void) { + struct uavcan_protocol_RestartNodeResponse msg; + + msg.ok = (bool)random_bitlen_unsigned_val(1); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.SoftwareVersion.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.SoftwareVersion.c new file mode 100644 index 00000000..6fe34196 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.SoftwareVersion.c @@ -0,0 +1,68 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_SoftwareVersion_encode(struct uavcan_protocol_SoftwareVersion* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_SOFTWAREVERSION_MAX_SIZE); + _uavcan_protocol_SoftwareVersion_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_SoftwareVersion_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_SoftwareVersion* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_SOFTWAREVERSION_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_SoftwareVersion_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_SoftwareVersion sample_uavcan_protocol_SoftwareVersion_msg(void) { + struct uavcan_protocol_SoftwareVersion msg; + + msg.major = (uint8_t)random_bitlen_unsigned_val(8); + msg.minor = (uint8_t)random_bitlen_unsigned_val(8); + msg.optional_field_flags = (uint8_t)random_bitlen_unsigned_val(8); + msg.vcs_commit = (uint32_t)random_bitlen_unsigned_val(32); + msg.image_crc = (uint64_t)random_bitlen_unsigned_val(64); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.KeyValue.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.KeyValue.c new file mode 100644 index 00000000..006796d5 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.KeyValue.c @@ -0,0 +1,68 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_debug_KeyValue_encode(struct uavcan_protocol_debug_KeyValue* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_DEBUG_KEYVALUE_MAX_SIZE); + _uavcan_protocol_debug_KeyValue_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_debug_KeyValue_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_debug_KeyValue* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_DEBUG_KEYVALUE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_debug_KeyValue_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_debug_KeyValue sample_uavcan_protocol_debug_KeyValue_msg(void) { + struct uavcan_protocol_debug_KeyValue msg; + + msg.value = random_float_val(); + msg.key.len = (uint8_t)random_range_unsigned_val(0, 58); + for (size_t i=0; i < msg.key.len; i++) { + msg.key.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.LogLevel.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.LogLevel.c new file mode 100644 index 00000000..9259de44 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.LogLevel.c @@ -0,0 +1,64 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_debug_LogLevel_encode(struct uavcan_protocol_debug_LogLevel* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_MAX_SIZE); + _uavcan_protocol_debug_LogLevel_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_debug_LogLevel_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_debug_LogLevel* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_debug_LogLevel_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_debug_LogLevel sample_uavcan_protocol_debug_LogLevel_msg(void) { + struct uavcan_protocol_debug_LogLevel msg; + + msg.value = (uint8_t)random_bitlen_unsigned_val(3); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.LogMessage.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.LogMessage.c new file mode 100644 index 00000000..85e2cd58 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.LogMessage.c @@ -0,0 +1,72 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_debug_LogMessage_encode(struct uavcan_protocol_debug_LogMessage* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE); + _uavcan_protocol_debug_LogMessage_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_debug_LogMessage_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_debug_LogMessage* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_debug_LogMessage_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_debug_LogMessage sample_uavcan_protocol_debug_LogMessage_msg(void) { + struct uavcan_protocol_debug_LogMessage msg; + + msg.level = sample_uavcan_protocol_debug_LogLevel_msg(); + msg.source.len = (uint8_t)random_range_unsigned_val(0, 31); + for (size_t i=0; i < msg.source.len; i++) { + msg.source.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + msg.text.len = (uint8_t)random_range_unsigned_val(0, 90); + for (size_t i=0; i < msg.text.len; i++) { + msg.text.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.Allocation.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.Allocation.c new file mode 100644 index 00000000..7029c2cf --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.Allocation.c @@ -0,0 +1,69 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_dynamic_node_id_Allocation_encode(struct uavcan_protocol_dynamic_node_id_Allocation* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_SIZE); + _uavcan_protocol_dynamic_node_id_Allocation_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_dynamic_node_id_Allocation_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_Allocation* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_dynamic_node_id_Allocation_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_Allocation sample_uavcan_protocol_dynamic_node_id_Allocation_msg(void) { + struct uavcan_protocol_dynamic_node_id_Allocation msg; + + msg.node_id = (uint8_t)random_bitlen_unsigned_val(7); + msg.first_part_of_unique_id = (bool)random_bitlen_unsigned_val(1); + msg.unique_id.len = (uint8_t)random_range_unsigned_val(0, 16); + for (size_t i=0; i < msg.unique_id.len; i++) { + msg.unique_id.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.c new file mode 100644 index 00000000..1a88f2a8 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.c @@ -0,0 +1,72 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_encode(struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_REQUEST_MAX_SIZE); + _uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest sample_uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest_msg(void) { + struct uavcan_protocol_dynamic_node_id_server_AppendEntriesRequest msg; + + msg.term = (uint32_t)random_bitlen_unsigned_val(32); + msg.prev_log_term = (uint32_t)random_bitlen_unsigned_val(32); + msg.prev_log_index = (uint8_t)random_bitlen_unsigned_val(8); + msg.leader_commit = (uint8_t)random_bitlen_unsigned_val(8); + msg.entries.len = (uint8_t)random_range_unsigned_val(0, 1); + for (size_t i=0; i < msg.entries.len; i++) { + msg.entries.data[i] = sample_uavcan_protocol_dynamic_node_id_server_Entry_msg(); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.c new file mode 100644 index 00000000..ffb13308 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.c @@ -0,0 +1,65 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_encode(struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_RESPONSE_MAX_SIZE); + _uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_APPENDENTRIES_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse sample_uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse_msg(void) { + struct uavcan_protocol_dynamic_node_id_server_AppendEntriesResponse msg; + + msg.term = (uint32_t)random_bitlen_unsigned_val(32); + msg.success = (bool)random_bitlen_unsigned_val(1); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.Discovery.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.Discovery.c new file mode 100644 index 00000000..c5a53997 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.Discovery.c @@ -0,0 +1,68 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_Discovery_encode(struct uavcan_protocol_dynamic_node_id_server_Discovery* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_DISCOVERY_MAX_SIZE); + _uavcan_protocol_dynamic_node_id_server_Discovery_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_dynamic_node_id_server_Discovery_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_Discovery* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_DISCOVERY_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_dynamic_node_id_server_Discovery_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_Discovery sample_uavcan_protocol_dynamic_node_id_server_Discovery_msg(void) { + struct uavcan_protocol_dynamic_node_id_server_Discovery msg; + + msg.configured_cluster_size = (uint8_t)random_bitlen_unsigned_val(8); + msg.known_nodes.len = (uint8_t)random_range_unsigned_val(0, 5); + for (size_t i=0; i < msg.known_nodes.len; i++) { + msg.known_nodes.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.Entry.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.Entry.c new file mode 100644 index 00000000..9766f42f --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.Entry.c @@ -0,0 +1,68 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_Entry_encode(struct uavcan_protocol_dynamic_node_id_server_Entry* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_ENTRY_MAX_SIZE); + _uavcan_protocol_dynamic_node_id_server_Entry_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_dynamic_node_id_server_Entry_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_Entry* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_ENTRY_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_dynamic_node_id_server_Entry_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_Entry sample_uavcan_protocol_dynamic_node_id_server_Entry_msg(void) { + struct uavcan_protocol_dynamic_node_id_server_Entry msg; + + msg.term = (uint32_t)random_bitlen_unsigned_val(32); + for (size_t i=0; i < 16; i++) { + msg.unique_id[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + msg.node_id = (uint8_t)random_bitlen_unsigned_val(7); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.RequestVote_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.RequestVote_req.c new file mode 100644 index 00000000..5bf5c2b1 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.RequestVote_req.c @@ -0,0 +1,67 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_encode(struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_REQUEST_MAX_SIZE); + _uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest sample_uavcan_protocol_dynamic_node_id_server_RequestVoteRequest_msg(void) { + struct uavcan_protocol_dynamic_node_id_server_RequestVoteRequest msg; + + msg.term = (uint32_t)random_bitlen_unsigned_val(32); + msg.last_log_term = (uint32_t)random_bitlen_unsigned_val(32); + msg.last_log_index = (uint8_t)random_bitlen_unsigned_val(8); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.RequestVote_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.RequestVote_res.c new file mode 100644 index 00000000..f4e35e74 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.RequestVote_res.c @@ -0,0 +1,65 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_encode(struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_RESPONSE_MAX_SIZE); + _uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_SERVER_REQUESTVOTE_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse sample_uavcan_protocol_dynamic_node_id_server_RequestVoteResponse_msg(void) { + struct uavcan_protocol_dynamic_node_id_server_RequestVoteResponse msg; + + msg.term = (uint32_t)random_bitlen_unsigned_val(32); + msg.vote_granted = (bool)random_bitlen_unsigned_val(1); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.BeginFirmwareUpdate_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.BeginFirmwareUpdate_req.c new file mode 100644 index 00000000..fa7f4b86 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.BeginFirmwareUpdate_req.c @@ -0,0 +1,66 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_BeginFirmwareUpdateRequest_encode(struct uavcan_protocol_file_BeginFirmwareUpdateRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_REQUEST_MAX_SIZE); + _uavcan_protocol_file_BeginFirmwareUpdateRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_BeginFirmwareUpdateRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_BeginFirmwareUpdateRequest sample_uavcan_protocol_file_BeginFirmwareUpdateRequest_msg(void) { + struct uavcan_protocol_file_BeginFirmwareUpdateRequest msg; + + msg.source_node_id = (uint8_t)random_bitlen_unsigned_val(8); + msg.image_file_remote_path = sample_uavcan_protocol_file_Path_msg(); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.BeginFirmwareUpdate_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.BeginFirmwareUpdate_res.c new file mode 100644 index 00000000..898feaf5 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.BeginFirmwareUpdate_res.c @@ -0,0 +1,68 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(struct uavcan_protocol_file_BeginFirmwareUpdateResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE); + _uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_BeginFirmwareUpdateResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_BeginFirmwareUpdateResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_BeginFirmwareUpdateResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_BeginFirmwareUpdateResponse sample_uavcan_protocol_file_BeginFirmwareUpdateResponse_msg(void) { + struct uavcan_protocol_file_BeginFirmwareUpdateResponse msg; + + msg.error = (uint8_t)random_bitlen_unsigned_val(8); + msg.optional_error_message.len = (uint8_t)random_range_unsigned_val(0, 127); + for (size_t i=0; i < msg.optional_error_message.len; i++) { + msg.optional_error_message.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Delete_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Delete_req.c new file mode 100644 index 00000000..43f9414d --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Delete_req.c @@ -0,0 +1,65 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_DeleteRequest_encode(struct uavcan_protocol_file_DeleteRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_DELETE_REQUEST_MAX_SIZE); + _uavcan_protocol_file_DeleteRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_DeleteRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_DeleteRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_DELETE_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_DeleteRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_DeleteRequest sample_uavcan_protocol_file_DeleteRequest_msg(void) { + struct uavcan_protocol_file_DeleteRequest msg; + + msg.path = sample_uavcan_protocol_file_Path_msg(); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Delete_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Delete_res.c new file mode 100644 index 00000000..37508d2d --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Delete_res.c @@ -0,0 +1,64 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_DeleteResponse_encode(struct uavcan_protocol_file_DeleteResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_DELETE_RESPONSE_MAX_SIZE); + _uavcan_protocol_file_DeleteResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_DeleteResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_DeleteResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_DELETE_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_DeleteResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_DeleteResponse sample_uavcan_protocol_file_DeleteResponse_msg(void) { + struct uavcan_protocol_file_DeleteResponse msg; + + msg.error = sample_uavcan_protocol_file_Error_msg(); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.EntryType.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.EntryType.c new file mode 100644 index 00000000..971bc078 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.EntryType.c @@ -0,0 +1,64 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_EntryType_encode(struct uavcan_protocol_file_EntryType* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_ENTRYTYPE_MAX_SIZE); + _uavcan_protocol_file_EntryType_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_EntryType_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_EntryType* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_ENTRYTYPE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_EntryType_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_EntryType sample_uavcan_protocol_file_EntryType_msg(void) { + struct uavcan_protocol_file_EntryType msg; + + msg.flags = (uint8_t)random_bitlen_unsigned_val(8); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Error.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Error.c new file mode 100644 index 00000000..c3c2a2b2 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Error.c @@ -0,0 +1,64 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_Error_encode(struct uavcan_protocol_file_Error* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_ERROR_MAX_SIZE); + _uavcan_protocol_file_Error_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_Error_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_Error* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_ERROR_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_Error_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_Error sample_uavcan_protocol_file_Error_msg(void) { + struct uavcan_protocol_file_Error msg; + + msg.value = (int16_t)random_bitlen_signed_val(16); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetDirectoryEntryInfo_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetDirectoryEntryInfo_req.c new file mode 100644 index 00000000..deeb8f17 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetDirectoryEntryInfo_req.c @@ -0,0 +1,66 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode(struct uavcan_protocol_file_GetDirectoryEntryInfoRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_REQUEST_MAX_SIZE); + _uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_GetDirectoryEntryInfoRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_GetDirectoryEntryInfoRequest sample_uavcan_protocol_file_GetDirectoryEntryInfoRequest_msg(void) { + struct uavcan_protocol_file_GetDirectoryEntryInfoRequest msg; + + msg.entry_index = (uint32_t)random_bitlen_unsigned_val(32); + msg.directory_path = sample_uavcan_protocol_file_Path_msg(); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetDirectoryEntryInfo_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetDirectoryEntryInfo_res.c new file mode 100644 index 00000000..67c41158 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetDirectoryEntryInfo_res.c @@ -0,0 +1,66 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode(struct uavcan_protocol_file_GetDirectoryEntryInfoResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_RESPONSE_MAX_SIZE); + _uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_GetDirectoryEntryInfoResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_GetDirectoryEntryInfoResponse sample_uavcan_protocol_file_GetDirectoryEntryInfoResponse_msg(void) { + struct uavcan_protocol_file_GetDirectoryEntryInfoResponse msg; + + msg.error = sample_uavcan_protocol_file_Error_msg(); + msg.entry_type = sample_uavcan_protocol_file_EntryType_msg(); + msg.entry_full_path = sample_uavcan_protocol_file_Path_msg(); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetInfo_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetInfo_req.c new file mode 100644 index 00000000..161917fb --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetInfo_req.c @@ -0,0 +1,65 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_GetInfoRequest_encode(struct uavcan_protocol_file_GetInfoRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_GETINFO_REQUEST_MAX_SIZE); + _uavcan_protocol_file_GetInfoRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_GetInfoRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_GetInfoRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_GETINFO_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_GetInfoRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_GetInfoRequest sample_uavcan_protocol_file_GetInfoRequest_msg(void) { + struct uavcan_protocol_file_GetInfoRequest msg; + + msg.path = sample_uavcan_protocol_file_Path_msg(); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetInfo_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetInfo_res.c new file mode 100644 index 00000000..c250739f --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetInfo_res.c @@ -0,0 +1,66 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_GetInfoResponse_encode(struct uavcan_protocol_file_GetInfoResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_GETINFO_RESPONSE_MAX_SIZE); + _uavcan_protocol_file_GetInfoResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_GetInfoResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_GetInfoResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_GETINFO_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_GetInfoResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_GetInfoResponse sample_uavcan_protocol_file_GetInfoResponse_msg(void) { + struct uavcan_protocol_file_GetInfoResponse msg; + + msg.size = (uint64_t)random_bitlen_unsigned_val(40); + msg.error = sample_uavcan_protocol_file_Error_msg(); + msg.entry_type = sample_uavcan_protocol_file_EntryType_msg(); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Path.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Path.c new file mode 100644 index 00000000..a6857f94 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Path.c @@ -0,0 +1,67 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_Path_encode(struct uavcan_protocol_file_Path* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_PATH_MAX_SIZE); + _uavcan_protocol_file_Path_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_Path_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_Path* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_PATH_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_Path_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_Path sample_uavcan_protocol_file_Path_msg(void) { + struct uavcan_protocol_file_Path msg; + + msg.path.len = (uint8_t)random_range_unsigned_val(0, 200); + for (size_t i=0; i < msg.path.len; i++) { + msg.path.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Read_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Read_req.c new file mode 100644 index 00000000..f57e4360 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Read_req.c @@ -0,0 +1,66 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_ReadRequest_encode(struct uavcan_protocol_file_ReadRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_READ_REQUEST_MAX_SIZE); + _uavcan_protocol_file_ReadRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_ReadRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_ReadRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_READ_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_ReadRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_ReadRequest sample_uavcan_protocol_file_ReadRequest_msg(void) { + struct uavcan_protocol_file_ReadRequest msg; + + msg.offset = (uint64_t)random_bitlen_unsigned_val(40); + msg.path = sample_uavcan_protocol_file_Path_msg(); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Read_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Read_res.c new file mode 100644 index 00000000..b7cdf92d --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Read_res.c @@ -0,0 +1,68 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_ReadResponse_encode(struct uavcan_protocol_file_ReadResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_READ_RESPONSE_MAX_SIZE); + _uavcan_protocol_file_ReadResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_ReadResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_ReadResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_READ_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_ReadResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_ReadResponse sample_uavcan_protocol_file_ReadResponse_msg(void) { + struct uavcan_protocol_file_ReadResponse msg; + + msg.error = sample_uavcan_protocol_file_Error_msg(); + msg.data.len = (uint16_t)random_range_unsigned_val(0, 256); + for (size_t i=0; i < msg.data.len; i++) { + msg.data.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Write_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Write_req.c new file mode 100644 index 00000000..78ead570 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Write_req.c @@ -0,0 +1,70 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_WriteRequest_encode(struct uavcan_protocol_file_WriteRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_WRITE_REQUEST_MAX_SIZE); + _uavcan_protocol_file_WriteRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_WriteRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_WriteRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_WRITE_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_WriteRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_WriteRequest sample_uavcan_protocol_file_WriteRequest_msg(void) { + struct uavcan_protocol_file_WriteRequest msg; + + msg.offset = (uint64_t)random_bitlen_unsigned_val(40); + msg.path = sample_uavcan_protocol_file_Path_msg(); + msg.data.len = (uint8_t)random_range_unsigned_val(0, 192); + for (size_t i=0; i < msg.data.len; i++) { + msg.data.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Write_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Write_res.c new file mode 100644 index 00000000..2b434abf --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Write_res.c @@ -0,0 +1,64 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_file_WriteResponse_encode(struct uavcan_protocol_file_WriteResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_FILE_WRITE_RESPONSE_MAX_SIZE); + _uavcan_protocol_file_WriteResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_file_WriteResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_file_WriteResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_FILE_WRITE_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_file_WriteResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_file_WriteResponse sample_uavcan_protocol_file_WriteResponse_msg(void) { + struct uavcan_protocol_file_WriteResponse msg; + + msg.error = sample_uavcan_protocol_file_Error_msg(); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.Empty.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.Empty.c new file mode 100644 index 00000000..245e7aa7 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.Empty.c @@ -0,0 +1,63 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_param_Empty_encode(struct uavcan_protocol_param_Empty* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_PARAM_EMPTY_MAX_SIZE); + _uavcan_protocol_param_Empty_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_param_Empty_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_Empty* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_PARAM_EMPTY_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_param_Empty_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_Empty sample_uavcan_protocol_param_Empty_msg(void) { + struct uavcan_protocol_param_Empty msg; + + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.ExecuteOpcode_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.ExecuteOpcode_req.c new file mode 100644 index 00000000..173bba3c --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.ExecuteOpcode_req.c @@ -0,0 +1,66 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_param_ExecuteOpcodeRequest_encode(struct uavcan_protocol_param_ExecuteOpcodeRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_MAX_SIZE); + _uavcan_protocol_param_ExecuteOpcodeRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_param_ExecuteOpcodeRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_ExecuteOpcodeRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_param_ExecuteOpcodeRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_ExecuteOpcodeRequest sample_uavcan_protocol_param_ExecuteOpcodeRequest_msg(void) { + struct uavcan_protocol_param_ExecuteOpcodeRequest msg; + + msg.opcode = (uint8_t)random_bitlen_unsigned_val(8); + msg.argument = (int64_t)random_bitlen_signed_val(48); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.ExecuteOpcode_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.ExecuteOpcode_res.c new file mode 100644 index 00000000..bed38ecd --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.ExecuteOpcode_res.c @@ -0,0 +1,65 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_param_ExecuteOpcodeResponse_encode(struct uavcan_protocol_param_ExecuteOpcodeResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE); + _uavcan_protocol_param_ExecuteOpcodeResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_param_ExecuteOpcodeResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_ExecuteOpcodeResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_param_ExecuteOpcodeResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_ExecuteOpcodeResponse sample_uavcan_protocol_param_ExecuteOpcodeResponse_msg(void) { + struct uavcan_protocol_param_ExecuteOpcodeResponse msg; + + msg.argument = (int64_t)random_bitlen_signed_val(48); + msg.ok = (bool)random_bitlen_unsigned_val(1); + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.GetSet_req.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.GetSet_req.c new file mode 100644 index 00000000..dbbb2d5b --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.GetSet_req.c @@ -0,0 +1,70 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_param_GetSetRequest_encode(struct uavcan_protocol_param_GetSetRequest* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_PARAM_GETSET_REQUEST_MAX_SIZE); + _uavcan_protocol_param_GetSetRequest_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_param_GetSetRequest_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_GetSetRequest* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_PARAM_GETSET_REQUEST_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_param_GetSetRequest_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_GetSetRequest sample_uavcan_protocol_param_GetSetRequest_msg(void) { + struct uavcan_protocol_param_GetSetRequest msg; + + msg.index = (uint16_t)random_bitlen_unsigned_val(13); + msg.value = sample_uavcan_protocol_param_Value_msg(); + msg.name.len = (uint8_t)random_range_unsigned_val(0, 92); + for (size_t i=0; i < msg.name.len; i++) { + msg.name.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.GetSet_res.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.GetSet_res.c new file mode 100644 index 00000000..ca0676f4 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.GetSet_res.c @@ -0,0 +1,71 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_param_GetSetResponse_encode(struct uavcan_protocol_param_GetSetResponse* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE); + _uavcan_protocol_param_GetSetResponse_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_param_GetSetResponse_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_GetSetResponse* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_param_GetSetResponse_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_GetSetResponse sample_uavcan_protocol_param_GetSetResponse_msg(void) { + struct uavcan_protocol_param_GetSetResponse msg; + + msg.value = sample_uavcan_protocol_param_Value_msg(); + msg.default_value = sample_uavcan_protocol_param_Value_msg(); + msg.max_value = sample_uavcan_protocol_param_NumericValue_msg(); + msg.min_value = sample_uavcan_protocol_param_NumericValue_msg(); + msg.name.len = (uint8_t)random_range_unsigned_val(0, 92); + for (size_t i=0; i < msg.name.len; i++) { + msg.name.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.NumericValue.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.NumericValue.c new file mode 100644 index 00000000..439d816f --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.NumericValue.c @@ -0,0 +1,79 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_param_NumericValue_encode(struct uavcan_protocol_param_NumericValue* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_MAX_SIZE); + _uavcan_protocol_param_NumericValue_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_param_NumericValue_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_NumericValue* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_param_NumericValue_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_NumericValue sample_uavcan_protocol_param_NumericValue_msg(void) { + struct uavcan_protocol_param_NumericValue msg; + + msg.union_tag = random_range_unsigned_val(0, 2); + + switch(msg.union_tag) { + case UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_EMPTY: { + msg.empty = sample_uavcan_protocol_param_Empty_msg(); + break; + } + case UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE: { + msg.integer_value = (int64_t)random_bitlen_signed_val(64); + break; + } + case UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_REAL_VALUE: { + msg.real_value = random_float_val(); + break; + } + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.Value.c b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.Value.c new file mode 100644 index 00000000..b8ad2646 --- /dev/null +++ b/bootloader/DroneCAN/dsdl_generated/src/uavcan.protocol.param.Value.c @@ -0,0 +1,90 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t uavcan_protocol_param_Value_encode(struct uavcan_protocol_param_Value* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, UAVCAN_PROTOCOL_PARAM_VALUE_MAX_SIZE); + _uavcan_protocol_param_Value_encode(buffer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + tao +#else + true +#endif + ); + return ((bit_ofs+7)/8); +} + +/* + return true if the decode is invalid + */ +bool uavcan_protocol_param_Value_decode(const CanardRxTransfer* transfer, struct uavcan_protocol_param_Value* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > UAVCAN_PROTOCOL_PARAM_VALUE_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_uavcan_protocol_param_Value_decode(transfer, &bit_ofs, msg, +#if CANARD_ENABLE_TAO_OPTION + transfer->tao +#else + true +#endif + )) { + return true; /* invalid payload */ + } + + const uint32_t byte_len = (bit_ofs+7U)/8U; +#if CANARD_ENABLE_TAO_OPTION + // if this could be CANFD then the dlc could indicating more bytes than + // we actually have + if (!transfer->tao) { + return byte_len > transfer->payload_len; + } +#endif + return byte_len != transfer->payload_len; +} + +#ifdef CANARD_DSDLC_TEST_BUILD +struct uavcan_protocol_param_Value sample_uavcan_protocol_param_Value_msg(void) { + struct uavcan_protocol_param_Value msg; + + msg.union_tag = random_range_unsigned_val(0, 4); + + switch(msg.union_tag) { + case UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY: { + msg.empty = sample_uavcan_protocol_param_Empty_msg(); + break; + } + case UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE: { + msg.integer_value = (int64_t)random_bitlen_signed_val(64); + break; + } + case UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE: { + msg.real_value = random_float_val(); + break; + } + case UAVCAN_PROTOCOL_PARAM_VALUE_BOOLEAN_VALUE: { + msg.boolean_value = (uint8_t)random_bitlen_unsigned_val(8); + break; + } + case UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE: { + msg.string_value.len = (uint8_t)random_range_unsigned_val(0, 128); + for (size_t i=0; i < msg.string_value.len; i++) { + msg.string_value.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + break; + } + } + return msg; +} +#endif diff --git a/bootloader/DroneCAN/libcanard/LICENSE b/bootloader/DroneCAN/libcanard/LICENSE new file mode 100644 index 00000000..9c6ac2ed --- /dev/null +++ b/bootloader/DroneCAN/libcanard/LICENSE @@ -0,0 +1,22 @@ +The MIT License (MIT) + +Copyright (c) 2015 UAVCAN + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + diff --git a/bootloader/DroneCAN/libcanard/README.md b/bootloader/DroneCAN/libcanard/README.md new file mode 100644 index 00000000..49120253 --- /dev/null +++ b/bootloader/DroneCAN/libcanard/README.md @@ -0,0 +1,4 @@ +# Libcanard + +This is a subset of +https://github.com/dronecan/libcanard diff --git a/bootloader/DroneCAN/libcanard/canard.c b/bootloader/DroneCAN/libcanard/canard.c new file mode 100644 index 00000000..5a27deea --- /dev/null +++ b/bootloader/DroneCAN/libcanard/canard.c @@ -0,0 +1,1938 @@ +/* + * Copyright (c) 2016-2019 UAVCAN Team + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + * + * Contributors: https://github.com/UAVCAN/libcanard/contributors + * + * Documentation: http://uavcan.org/Implementations/Libcanard + */ + +#include "canard_internals.h" +#include + + +#undef MIN +#undef MAX +#define MIN(a, b) (((a) < (b)) ? (a) : (b)) +#define MAX(a, b) (((a) > (b)) ? (a) : (b)) + + +#define TRANSFER_TIMEOUT_USEC 2000000U +#define IFACE_SWITCH_DELAY_USEC 1000000U + +#define TRANSFER_ID_BIT_LEN 5U +#define ANON_MSG_DATA_TYPE_ID_BIT_LEN 2U + +#define SOURCE_ID_FROM_ID(x) ((uint8_t) (((x) >> 0U) & 0x7FU)) +#define SERVICE_NOT_MSG_FROM_ID(x) ((bool) (((x) >> 7U) & 0x1U)) +#define REQUEST_NOT_RESPONSE_FROM_ID(x) ((bool) (((x) >> 15U) & 0x1U)) +#define DEST_ID_FROM_ID(x) ((uint8_t) (((x) >> 8U) & 0x7FU)) +#define PRIORITY_FROM_ID(x) ((uint8_t) (((x) >> 24U) & 0x1FU)) +#define MSG_TYPE_FROM_ID(x) ((uint16_t)(((x) >> 8U) & 0xFFFFU)) +#define SRV_TYPE_FROM_ID(x) ((uint8_t) (((x) >> 16U) & 0xFFU)) + +#define MAKE_TRANSFER_DESCRIPTOR(data_type_id, transfer_type, src_node_id, dst_node_id) \ + (((uint32_t)(data_type_id)) | (((uint32_t)(transfer_type)) << 16U) | \ + (((uint32_t)(src_node_id)) << 18U) | (((uint32_t)(dst_node_id)) << 25U)) + +#define TRANSFER_ID_FROM_TAIL_BYTE(x) ((uint8_t)((x) & 0x1FU)) + +// The extra cast to unsigned is needed to squelch warnings from clang-tidy +#define IS_START_OF_TRANSFER(x) ((bool)(((uint32_t)(x) >> 7U) & 0x1U)) +#define IS_END_OF_TRANSFER(x) ((bool)(((uint32_t)(x) >> 6U) & 0x1U)) +#define TOGGLE_BIT(x) ((bool)(((uint32_t)(x) >> 5U) & 0x1U)) + + + +/* + * API functions + */ +void canardInit(CanardInstance* out_ins, + void* mem_arena, + size_t mem_arena_size, + CanardOnTransferReception on_reception, + CanardShouldAcceptTransfer should_accept, + void* user_reference) +{ + CANARD_ASSERT(out_ins != NULL); + + /* + * Checking memory layout. + * This condition is supposed to be true for all 32-bit and smaller platforms. + * If your application fails here, make sure it's not built in 64-bit mode. + * Refer to the design documentation for more info. + */ + CANARD_ASSERT(CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE >= 5); + + memset(out_ins, 0, sizeof(*out_ins)); + + out_ins->node_id = CANARD_BROADCAST_NODE_ID; + out_ins->on_reception = on_reception; + out_ins->should_accept = should_accept; + out_ins->rx_states = NULL; + out_ins->tx_queue = NULL; + out_ins->user_reference = user_reference; +#if CANARD_ENABLE_TAO_OPTION + out_ins->tao_disabled = false; +#endif + size_t pool_capacity = mem_arena_size / CANARD_MEM_BLOCK_SIZE; + if (pool_capacity > 0xFFFFU) + { + pool_capacity = 0xFFFFU; + } + + initPoolAllocator(&out_ins->allocator, mem_arena, (uint16_t)pool_capacity); +} + +void* canardGetUserReference(const CanardInstance* ins) +{ + CANARD_ASSERT(ins != NULL); + return ins->user_reference; +} + +void canardSetLocalNodeID(CanardInstance* ins, uint8_t self_node_id) +{ + CANARD_ASSERT(ins != NULL); + + if ((ins->node_id == CANARD_BROADCAST_NODE_ID) && + (self_node_id >= CANARD_MIN_NODE_ID) && + (self_node_id <= CANARD_MAX_NODE_ID)) + { + ins->node_id = self_node_id; + } + else + { + CANARD_ASSERT(false); + } +} + +uint8_t canardGetLocalNodeID(const CanardInstance* ins) +{ + return ins->node_id; +} + +void canardForgetLocalNodeID(CanardInstance* ins) { + ins->node_id = CANARD_BROADCAST_NODE_ID; +} + +void canardInitTxTransfer(CanardTxTransfer* transfer) +{ + CANARD_ASSERT(transfer != NULL); + memset(transfer, 0, sizeof(*transfer)); +} + + +int16_t canardBroadcast(CanardInstance* ins, + uint64_t data_type_signature, + uint16_t data_type_id, + uint8_t* inout_transfer_id, + uint8_t priority, + const void* payload, + uint16_t payload_len +#if CANARD_ENABLE_DEADLINE + ,uint64_t tx_deadline +#endif +#if CANARD_MULTI_IFACE + ,uint8_t iface_mask +#endif +#if CANARD_ENABLE_CANFD + ,bool canfd +#endif +) +{ + // create transfer object + CanardTxTransfer transfer_object = { + .data_type_signature = data_type_signature, + .data_type_id = data_type_id, + .inout_transfer_id = inout_transfer_id, + .priority = priority, + .payload = (uint8_t*)payload, + .payload_len = payload_len, +#if CANARD_ENABLE_DEADLINE + .deadline_usec = tx_deadline, +#endif +#if CANARD_MULTI_IFACE + .iface_mask = iface_mask, +#endif +#if CANARD_ENABLE_CANFD + .canfd = canfd, +#endif + }; + + return canardBroadcastObj(ins, &transfer_object); +} + +int16_t canardBroadcastObj(CanardInstance* ins, CanardTxTransfer* transfer_object) +{ + if (transfer_object->payload == NULL && transfer_object->payload_len > 0) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + if (transfer_object->priority > CANARD_TRANSFER_PRIORITY_LOWEST) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + uint32_t can_id = 0; + uint16_t crc = 0xFFFFU; + + if (canardGetLocalNodeID(ins) == 0) + { + if (transfer_object->payload_len > 7) + { + return -CANARD_ERROR_NODE_ID_NOT_SET; + } + + static const uint16_t DTIDMask = (1U << ANON_MSG_DATA_TYPE_ID_BIT_LEN) - 1U; + + if ((transfer_object->data_type_id & DTIDMask) != transfer_object->data_type_id) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + // anonymous transfer, random discriminator + const uint16_t discriminator = (uint16_t)((crcAdd(0xFFFFU, transfer_object->payload, transfer_object->payload_len)) & 0x7FFEU); + can_id = ((uint32_t) transfer_object->priority << 24U) | ((uint32_t) discriminator << 9U) | + ((uint32_t) (transfer_object->data_type_id & DTIDMask) << 8U) | (uint32_t) canardGetLocalNodeID(ins); + } + else + { + can_id = ((uint32_t) transfer_object->priority << 24U) | ((uint32_t) transfer_object->data_type_id << 8U) | (uint32_t) canardGetLocalNodeID(ins); + crc = calculateCRC(transfer_object); + } + + const int16_t result = enqueueTxFrames(ins, can_id, crc, transfer_object); + + if (result > 0) { + incrementTransferID(transfer_object->inout_transfer_id); + } + + return result; +} + +/* + the following FromIdx and ToIdx functions allow for the + CanardBufferBlock and CanartRxState structures to have the same size + on 32 bit and 64 bit platforms, which allows for easier testing in + simulator environments + */ +CANARD_INTERNAL CanardBufferBlock *canardBufferFromIdx(CanardPoolAllocator* allocator, canard_buffer_idx_t idx) +{ +#if CANARD_64_BIT + if (idx == CANARD_BUFFER_IDX_NONE) { + return NULL; + } + return (CanardBufferBlock *)(uintptr_t)&((uint8_t *)allocator->arena)[idx-1]; +#else + (void)allocator; + return (CanardBufferBlock *)idx; +#endif +} + +CANARD_INTERNAL canard_buffer_idx_t canardBufferToIdx(CanardPoolAllocator* allocator, const CanardBufferBlock *buf) +{ +#if CANARD_64_BIT + if (buf == NULL) { + return CANARD_BUFFER_IDX_NONE; + } + return 1U+((canard_buffer_idx_t)((uint8_t *)buf - (uint8_t *)allocator->arena)); +#else + (void)allocator; + return (canard_buffer_idx_t)buf; +#endif +} + +CANARD_INTERNAL CanardRxState *canardRxFromIdx(CanardPoolAllocator* allocator, canard_buffer_idx_t idx) +{ +#if CANARD_64_BIT + if (idx == CANARD_BUFFER_IDX_NONE) { + return NULL; + } + return (CanardRxState *)(uintptr_t)&((uint8_t *)allocator->arena)[idx-1]; +#else + (void)allocator; + return (CanardRxState *)idx; +#endif +} + +CANARD_INTERNAL canard_buffer_idx_t canardRxToIdx(CanardPoolAllocator* allocator, const CanardRxState *rx) +{ +#if CANARD_64_BIT + if (rx == NULL) { + return CANARD_BUFFER_IDX_NONE; + } + return 1U+((canard_buffer_idx_t)((uint8_t *)rx - (uint8_t *)allocator->arena)); +#else + (void)allocator; + return (canard_buffer_idx_t)rx; +#endif +} + +CANARD_INTERNAL uint16_t calculateCRC(const CanardTxTransfer* transfer_object) +{ + uint16_t crc = 0xFFFFU; +#if CANARD_ENABLE_CANFD + if ((transfer_object->payload_len > 7 && !transfer_object->canfd) || + (transfer_object->payload_len > 63 && transfer_object->canfd)) +#else + if (transfer_object->payload_len > 7) +#endif + { + crc = crcAddSignature(crc, transfer_object->data_type_signature); + crc = crcAdd(crc, transfer_object->payload, transfer_object->payload_len); +#if CANARD_ENABLE_CANFD + if (transfer_object->payload_len > 63 && transfer_object->canfd) { + uint8_t empty = 0; + uint8_t padding = (uint8_t)dlcToDataLength(dataLengthToDlc((uint16_t)((transfer_object->payload_len+2) % 63)+1))-1; + padding -= (uint8_t)((transfer_object->payload_len+2) % 63); + for (uint8_t i=0; ipayload == NULL && transfer_object->payload_len > 0) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + if (transfer_object->priority > CANARD_TRANSFER_PRIORITY_LOWEST) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + if (canardGetLocalNodeID(ins) == 0) + { + return -CANARD_ERROR_NODE_ID_NOT_SET; + } + + const uint32_t can_id = ((uint32_t) transfer_object->priority << 24U) | ((uint32_t) transfer_object->data_type_id << 16U) | + ((uint32_t) transfer_object->transfer_type << 15U) | ((uint32_t) destination_node_id << 8U) | + (1U << 7U) | (uint32_t) canardGetLocalNodeID(ins); + + uint16_t crc = calculateCRC(transfer_object); + + + const int16_t result = enqueueTxFrames(ins, can_id, crc, transfer_object); + + if (result > 0 && transfer_object->transfer_type == CanardTransferTypeRequest) // Response Transfer ID must not be altered + { + incrementTransferID(transfer_object->inout_transfer_id); + } + + return result; +} + +CanardCANFrame* canardPeekTxQueue(const CanardInstance* ins) +{ + if (ins->tx_queue == NULL) + { + return NULL; + } + return &ins->tx_queue->frame; +} + +void canardPopTxQueue(CanardInstance* ins) +{ + CanardTxQueueItem* item = ins->tx_queue; + ins->tx_queue = item->next; + freeBlock(&ins->allocator, item); +} + +int16_t canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint64_t timestamp_usec) +{ + const CanardTransferType transfer_type = extractTransferType(frame->id); + const uint8_t destination_node_id = (transfer_type == CanardTransferTypeBroadcast) ? + (uint8_t)CANARD_BROADCAST_NODE_ID : + DEST_ID_FROM_ID(frame->id); + + // TODO: This function should maintain statistics of transfer errors and such. + + if ((frame->id & CANARD_CAN_FRAME_EFF) == 0 || + (frame->id & CANARD_CAN_FRAME_RTR) != 0 || + (frame->id & CANARD_CAN_FRAME_ERR) != 0 || + (frame->data_len < 1)) + { + return -CANARD_ERROR_RX_INCOMPATIBLE_PACKET; + } + + if (transfer_type != CanardTransferTypeBroadcast && + destination_node_id != canardGetLocalNodeID(ins)) + { + return -CANARD_ERROR_RX_WRONG_ADDRESS; + } + + const uint8_t priority = PRIORITY_FROM_ID(frame->id); + const uint8_t source_node_id = SOURCE_ID_FROM_ID(frame->id); + const uint16_t data_type_id = extractDataType(frame->id); + const uint32_t transfer_descriptor = + MAKE_TRANSFER_DESCRIPTOR(data_type_id, transfer_type, source_node_id, destination_node_id); + + const uint8_t tail_byte = frame->data[frame->data_len - 1]; + + uint64_t data_type_signature = 0; + CanardRxState* rx_state = NULL; + + if (IS_START_OF_TRANSFER(tail_byte)) + { + + if (ins->should_accept(ins, &data_type_signature, data_type_id, transfer_type, source_node_id)) + { + rx_state = traverseRxStates(ins, transfer_descriptor); + + if(rx_state == NULL) + { + return -CANARD_ERROR_OUT_OF_MEMORY; + } + } + else + { + return -CANARD_ERROR_RX_NOT_WANTED; + } + } + else + { + rx_state = findRxState(ins, transfer_descriptor); + + if (rx_state == NULL) + { + return -CANARD_ERROR_RX_MISSED_START; + } + } + + CANARD_ASSERT(rx_state != NULL); // All paths that lead to NULL should be terminated with return above + + // Resolving the state flags: + const bool not_initialized = rx_state->timestamp_usec == 0; + const bool tid_timed_out = (timestamp_usec - rx_state->timestamp_usec) > TRANSFER_TIMEOUT_USEC; + const bool same_iface = frame->iface_id == rx_state->iface_id; + const bool first_frame = IS_START_OF_TRANSFER(tail_byte); + const bool not_previous_tid = + computeTransferIDForwardDistance((uint8_t) rx_state->transfer_id, TRANSFER_ID_FROM_TAIL_BYTE(tail_byte)) > 1; + const bool iface_switch_allowed = (timestamp_usec - rx_state->timestamp_usec) > IFACE_SWITCH_DELAY_USEC; + const bool non_wrapped_tid = computeTransferIDForwardDistance(TRANSFER_ID_FROM_TAIL_BYTE(tail_byte), (uint8_t) rx_state->transfer_id) < (1 << (TRANSFER_ID_BIT_LEN-1)); + const bool incomplete_frame = rx_state->buffer_blocks != CANARD_BUFFER_IDX_NONE; + + const bool need_restart = + (not_initialized) || + (tid_timed_out) || + (same_iface && first_frame && (not_previous_tid || incomplete_frame)) || + (iface_switch_allowed && first_frame && non_wrapped_tid); + + if (need_restart) + { + rx_state->transfer_id = TRANSFER_ID_FROM_TAIL_BYTE(tail_byte); + rx_state->next_toggle = 0; + releaseStatePayload(ins, rx_state); + rx_state->iface_id = frame->iface_id; + if (!IS_START_OF_TRANSFER(tail_byte)) + { + rx_state->transfer_id++; + return -CANARD_ERROR_RX_MISSED_START; + } + } + + if (frame->iface_id != rx_state->iface_id) + { + // drop frame if coming from unexpected interface + return CANARD_OK; + } + + if (IS_START_OF_TRANSFER(tail_byte) && IS_END_OF_TRANSFER(tail_byte)) // single frame transfer + { + rx_state->timestamp_usec = timestamp_usec; + CanardRxTransfer rx_transfer = { + .timestamp_usec = timestamp_usec, + .payload_head = frame->data, + .payload_len = (uint8_t)(frame->data_len - 1U), + .data_type_id = data_type_id, + .transfer_type = (uint8_t)transfer_type, + .transfer_id = TRANSFER_ID_FROM_TAIL_BYTE(tail_byte), + .priority = priority, + .source_node_id = source_node_id, +#if CANARD_ENABLE_CANFD + .canfd = frame->canfd, + .tao = !(frame->canfd || ins->tao_disabled) +#elif CANARD_ENABLE_TAO_OPTION + .tao = !ins->tao_disabled +#endif + }; + + ins->on_reception(ins, &rx_transfer); + + prepareForNextTransfer(rx_state); + return CANARD_OK; + } + + if (TOGGLE_BIT(tail_byte) != rx_state->next_toggle) + { + return -CANARD_ERROR_RX_WRONG_TOGGLE; + } + + if (TRANSFER_ID_FROM_TAIL_BYTE(tail_byte) != rx_state->transfer_id) + { + return -CANARD_ERROR_RX_UNEXPECTED_TID; + } + + if (IS_START_OF_TRANSFER(tail_byte) && !IS_END_OF_TRANSFER(tail_byte)) // Beginning of multi frame transfer + { + if (frame->data_len <= 3) + { + return -CANARD_ERROR_RX_SHORT_FRAME; + } + + // take off the crc and store the payload + rx_state->timestamp_usec = timestamp_usec; + rx_state->payload_len = 0; + const int16_t ret = bufferBlockPushBytes(&ins->allocator, rx_state, frame->data + 2, + (uint8_t) (frame->data_len - 3)); + if (ret < 0) + { + releaseStatePayload(ins, rx_state); + prepareForNextTransfer(rx_state); + return -CANARD_ERROR_OUT_OF_MEMORY; + } + rx_state->payload_crc = (uint16_t)(((uint16_t) frame->data[0]) | (uint16_t)((uint16_t) frame->data[1] << 8U)); + rx_state->calculated_crc = crcAddSignature(0xFFFFU, data_type_signature); + rx_state->calculated_crc = crcAdd((uint16_t)rx_state->calculated_crc, + frame->data + 2, (uint8_t)(frame->data_len - 3)); + } + else if (!IS_START_OF_TRANSFER(tail_byte) && !IS_END_OF_TRANSFER(tail_byte)) // Middle of a multi-frame transfer + { + const int16_t ret = bufferBlockPushBytes(&ins->allocator, rx_state, frame->data, + (uint8_t) (frame->data_len - 1)); + if (ret < 0) + { + releaseStatePayload(ins, rx_state); + prepareForNextTransfer(rx_state); + return -CANARD_ERROR_OUT_OF_MEMORY; + } + rx_state->calculated_crc = crcAdd((uint16_t)rx_state->calculated_crc, + frame->data, (uint8_t)(frame->data_len - 1)); + } + else // End of a multi-frame transfer + { + const uint8_t frame_payload_size = (uint8_t)(frame->data_len - 1); + + uint8_t tail_offset = 0; + + if (rx_state->payload_len < CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) + { + // Copy the beginning of the frame into the head, point the tail pointer to the remainder + for (size_t i = rx_state->payload_len; + (i < CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) && (tail_offset < frame_payload_size); + i++, tail_offset++) + { + rx_state->buffer_head[i] = frame->data[tail_offset]; + } + } + else + { + // Like above, except that the beginning goes into the last block of the storage + CanardBufferBlock* block = canardBufferFromIdx(&ins->allocator, rx_state->buffer_blocks); + if (block != NULL) + { + size_t offset = CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE; // Payload offset of the first block + while (block->next != NULL) + { + block = block->next; + offset += CANARD_BUFFER_BLOCK_DATA_SIZE; + } + CANARD_ASSERT(block != NULL); + + const size_t offset_within_block = rx_state->payload_len - offset; + CANARD_ASSERT(offset_within_block <= CANARD_BUFFER_BLOCK_DATA_SIZE); + + for (size_t i = offset_within_block; + (i < CANARD_BUFFER_BLOCK_DATA_SIZE) && (tail_offset < frame_payload_size); + i++, tail_offset++) + { + block->data[i] = frame->data[tail_offset]; + } + } + } + + CanardRxTransfer rx_transfer = { + .timestamp_usec = timestamp_usec, + .payload_head = rx_state->buffer_head, + .payload_middle = canardBufferFromIdx(&ins->allocator, rx_state->buffer_blocks), + .payload_tail = (tail_offset >= frame_payload_size) ? NULL : (&frame->data[tail_offset]), + .payload_len = (uint16_t)(rx_state->payload_len + frame_payload_size), + .data_type_id = data_type_id, + .transfer_type = (uint8_t)transfer_type, + .transfer_id = TRANSFER_ID_FROM_TAIL_BYTE(tail_byte), + .priority = priority, + .source_node_id = source_node_id, + +#if CANARD_ENABLE_CANFD + .canfd = frame->canfd, + .tao = !(frame->canfd || ins->tao_disabled) +#elif CANARD_ENABLE_TAO_OPTION + .tao = !ins->tao_disabled +#endif + }; + + rx_state->buffer_blocks = CANARD_BUFFER_IDX_NONE; // Block list ownership has been transferred to rx_transfer! + + // CRC validation + rx_state->calculated_crc = crcAdd((uint16_t)rx_state->calculated_crc, frame->data, frame->data_len - 1U); + if (rx_state->calculated_crc == rx_state->payload_crc) + { + ins->on_reception(ins, &rx_transfer); + } + + // Making sure the payload is released even if the application didn't bother with it + canardReleaseRxTransferPayload(ins, &rx_transfer); + prepareForNextTransfer(rx_state); + + if (rx_state->calculated_crc == rx_state->payload_crc) + { + return CANARD_OK; + } + else + { + return -CANARD_ERROR_RX_BAD_CRC; + } + } + + rx_state->next_toggle = rx_state->next_toggle ? 0 : 1; + return CANARD_OK; +} + +void canardCleanupStaleTransfers(CanardInstance* ins, uint64_t current_time_usec) +{ + CanardRxState* prev = ins->rx_states, * state = ins->rx_states; + + while (state != NULL) + { + if ((current_time_usec - state->timestamp_usec) > TRANSFER_TIMEOUT_USEC) + { + if (state == ins->rx_states) + { + releaseStatePayload(ins, state); + ins->rx_states = canardRxFromIdx(&ins->allocator, ins->rx_states->next); + freeBlock(&ins->allocator, state); + state = ins->rx_states; + prev = state; + } + else + { + releaseStatePayload(ins, state); + prev->next = state->next; + freeBlock(&ins->allocator, state); + state = canardRxFromIdx(&ins->allocator, prev->next); + } + } + else + { + prev = state; + state = canardRxFromIdx(&ins->allocator, state->next); + } + } + +#if CANARD_MULTI_IFACE || CANARD_ENABLE_DEADLINE + // remove stale TX transfers + CanardTxQueueItem* prev_item = ins->tx_queue, * item = ins->tx_queue; + while (item != NULL) + { +#if CANARD_MULTI_IFACE && CANARD_ENABLE_DEADLINE + if ((current_time_usec > item->frame.deadline_usec) || item->frame.iface_mask == 0) +#elif CANARD_MULTI_IFACE + if (item->frame.iface_mask == 0) +#else + if (current_time_usec > item->frame.deadline_usec) +#endif + { + if (item == ins->tx_queue) + { + ins->tx_queue = ins->tx_queue->next; + freeBlock(&ins->allocator, item); + item = ins->tx_queue; + prev_item = item; + } + else + { + prev_item->next = item->next; + freeBlock(&ins->allocator, item); + item = prev_item->next; + } + } + else + { + prev_item = item; + item = item->next; + } + } +#endif +} + +int16_t canardDecodeScalar(const CanardRxTransfer* transfer, + uint32_t bit_offset, + uint8_t bit_length, + bool value_is_signed, + void* out_value) +{ + if (transfer == NULL || out_value == NULL) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + if (bit_length < 1 || bit_length > 64) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + if (bit_length == 1 && value_is_signed) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + /* + * Reading raw bytes into the temporary storage. + * Luckily, C guarantees that every element is aligned at the beginning (lower address) of the union. + */ + union + { + bool boolean; ///< sizeof(bool) is implementation-defined, so it has to be handled separately + uint8_t u8; ///< Also char + int8_t s8; + uint16_t u16; + int16_t s16; + uint32_t u32; + int32_t s32; ///< Also float, possibly double, possibly long double (depends on implementation) + uint64_t u64; + int64_t s64; ///< Also double, possibly float, possibly long double (depends on implementation) + uint8_t bytes[8]; + } storage; + + memset(&storage, 0, sizeof(storage)); // This is important + + const int16_t result = descatterTransferPayload(transfer, bit_offset, bit_length, &storage.bytes[0]); + if (result <= 0) + { + return result; + } + + CANARD_ASSERT((result > 0) && (result <= 64) && (result <= bit_length)); + + /* + * The bit copy algorithm assumes that more significant bits have lower index, so we need to shift some. + * Extra most significant bits will be filled with zeroes, which is fine. + * Coverity Scan mistakenly believes that the array may be overrun if bit_length == 64; however, this branch will + * not be taken if bit_length == 64, because 64 % 8 == 0. + */ + if ((bit_length % 8) != 0) + { + // coverity[overrun-local] + storage.bytes[bit_length / 8U] = (uint8_t)(storage.bytes[bit_length / 8U] >> ((8U - (bit_length % 8U)) & 7U)); + } + + /* + * Determining the closest standard byte length - this will be needed for byte reordering and sign bit extension. + */ + uint8_t std_byte_length = 0; + if (bit_length == 1) { std_byte_length = sizeof(bool); } + else if (bit_length <= 8) { std_byte_length = 1; } + else if (bit_length <= 16) { std_byte_length = 2; } + else if (bit_length <= 32) { std_byte_length = 4; } + else if (bit_length <= 64) { std_byte_length = 8; } + else + { + CANARD_ASSERT(false); + return -CANARD_ERROR_INTERNAL; + } + + CANARD_ASSERT((std_byte_length > 0) && (std_byte_length <= 8)); + + /* + * Flipping the byte order if needed. + */ + if (isBigEndian()) + { + swapByteOrder(&storage.bytes[0], std_byte_length); + } + +#if WORD_ADDRESSING_IS_16BITS + /* + * Copying 8-bit array to 64-bit storage + */ + { + uint64_t temp = 0; + for(uint16_t i=0; i 0); + return result; +} + +void canardEncodeScalar(void* destination, + uint32_t bit_offset, + uint8_t bit_length, + const void* value) +{ + /* + * This function can only fail due to invalid arguments, so it was decided to make it return void, + * and in the case of bad arguments try the best effort or just trigger an CANARD_ASSERTion failure. + * Maybe not the best solution, but it simplifies the API. + */ + CANARD_ASSERT(destination != NULL); + CANARD_ASSERT(value != NULL); + + if (bit_length > 64) + { + CANARD_ASSERT(false); + bit_length = 64; + } + + if (bit_length < 1) + { + CANARD_ASSERT(false); + bit_length = 1; + } + + /* + * Preparing the data in the temporary storage. + */ + union + { + bool boolean; + uint8_t u8; + uint16_t u16; + uint32_t u32; + uint64_t u64; + uint8_t bytes[8]; + } storage; + + memset(&storage, 0, sizeof(storage)); + + uint8_t std_byte_length = 0; + + // Extra most significant bits can be safely ignored here. + if (bit_length == 1) { std_byte_length = sizeof(bool); storage.boolean = (*((bool*) value) != 0); } + else if (bit_length <= 8) { std_byte_length = 1; storage.u8 = *((uint8_t*) value); } + else if (bit_length <= 16) { std_byte_length = 2; storage.u16 = *((uint16_t*) value); } + else if (bit_length <= 32) { std_byte_length = 4; storage.u32 = *((uint32_t*) value); } + else if (bit_length <= 64) { std_byte_length = 8; storage.u64 = *((uint64_t*) value); } + else + { + CANARD_ASSERT(false); + } + + CANARD_ASSERT(std_byte_length > 0); + +#if WORD_ADDRESSING_IS_16BITS + /* + * Copying 64-bit storage to 8-bit array + */ + { + uint64_t temp = storage.u64; + for(uint16_t i=0; i> (8*i)) & 0xFFU; + } + } +#endif + + if (isBigEndian()) + { + swapByteOrder(&storage.bytes[0], std_byte_length); + } + + /* + * The bit copy algorithm assumes that more significant bits have lower index, so we need to shift some. + * Extra least significant bits will be filled with zeroes, which is fine. + * Extra most significant bits will be discarded here. + * Coverity Scan mistakenly believes that the array may be overrun if bit_length == 64; however, this branch will + * not be taken if bit_length == 64, because 64 % 8 == 0. + */ + if ((bit_length % 8) != 0) + { + // coverity[overrun-local] + storage.bytes[bit_length / 8U] = (uint8_t)(storage.bytes[bit_length / 8U] << ((8U - (bit_length % 8U)) & 7U)); + } + + /* + * Now, the storage contains properly serialized scalar. Copying it out. + */ + copyBitArray(&storage.bytes[0], 0, bit_length, (uint8_t*) destination, bit_offset); +} + +void canardReleaseRxTransferPayload(CanardInstance* ins, CanardRxTransfer* transfer) +{ + while (transfer->payload_middle != NULL) + { + CanardBufferBlock* const temp = transfer->payload_middle->next; + freeBlock(&ins->allocator, transfer->payload_middle); + transfer->payload_middle = temp; + } + + transfer->payload_middle = NULL; + transfer->payload_head = NULL; + transfer->payload_tail = NULL; + transfer->payload_len = 0; +} + +CanardPoolAllocatorStatistics canardGetPoolAllocatorStatistics(CanardInstance* ins) +{ + return ins->allocator.statistics; +} + +uint16_t canardConvertNativeFloatToFloat16(float value) +{ + CANARD_ASSERT(sizeof(float) == CANARD_SIZEOF_FLOAT); + + union FP32 + { + uint32_t u; + float f; + }; + + const union FP32 f32inf = { 255UL << 23U }; + const union FP32 f16inf = { 31UL << 23U }; + const union FP32 magic = { 15UL << 23U }; + const uint32_t sign_mask = 0x80000000UL; + const uint32_t round_mask = 0xFFFFF000UL; + + union FP32 in; + in.f = value; + uint32_t sign = in.u & sign_mask; + in.u ^= sign; + + uint16_t out = 0; + + if (in.u >= f32inf.u) + { + out = (in.u > f32inf.u) ? (uint16_t)0x7FFFU : (uint16_t)0x7C00U; + } + else + { + in.u &= round_mask; + in.f *= magic.f; + in.u -= round_mask; + if (in.u > f16inf.u) + { + in.u = f16inf.u; + } + out = (uint16_t)(in.u >> 13U); + } + + out |= (uint16_t)(sign >> 16U); + + return out; +} + +float canardConvertFloat16ToNativeFloat(uint16_t value) +{ + CANARD_ASSERT(sizeof(float) == CANARD_SIZEOF_FLOAT); + + union FP32 + { + uint32_t u; + float f; + }; + + const union FP32 magic = { (254UL - 15UL) << 23U }; + const union FP32 was_inf_nan = { (127UL + 16UL) << 23U }; + union FP32 out; + + out.u = (value & 0x7FFFU) << 13U; + out.f *= magic.f; + if (out.f >= was_inf_nan.f) + { + out.u |= 255UL << 23U; + } + out.u |= (value & 0x8000UL) << 16U; + + return out.f; +} + +/* + * Internal (static functions) + */ +CANARD_INTERNAL int16_t computeTransferIDForwardDistance(uint8_t a, uint8_t b) +{ + int16_t d = (int16_t)(a - b); + if (d < 0) + { + d = (int16_t)(d + (int16_t)(1U << TRANSFER_ID_BIT_LEN)); + } + return d; +} + +CANARD_INTERNAL void incrementTransferID(uint8_t* transfer_id) +{ + CANARD_ASSERT(transfer_id != NULL); + + (*transfer_id)++; + if (*transfer_id >= 32) + { + *transfer_id = 0; + } +} + +CANARD_INTERNAL uint16_t dlcToDataLength(uint16_t dlc) { + /* + Data Length Code 9 10 11 12 13 14 15 + Number of data bytes 12 16 20 24 32 48 64 + */ + if (dlc <= 8) { + return dlc; + } else if (dlc == 9) { + return 12; + } else if (dlc == 10) { + return 16; + } else if (dlc == 11) { + return 20; + } else if (dlc == 12) { + return 24; + } else if (dlc == 13) { + return 32; + } else if (dlc == 14) { + return 48; + } + return 64; +} + +CANARD_INTERNAL uint16_t dataLengthToDlc(uint16_t data_length) { + if (data_length <= 8) { + return data_length; + } else if (data_length <= 12) { + return 9; + } else if (data_length <= 16) { + return 10; + } else if (data_length <= 20) { + return 11; + } else if (data_length <= 24) { + return 12; + } else if (data_length <= 32) { + return 13; + } else if (data_length <= 48) { + return 14; + } + return 15; +} + +CANARD_INTERNAL int16_t enqueueTxFrames(CanardInstance* ins, + uint32_t can_id, + uint16_t crc, + CanardTxTransfer* transfer +) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT((can_id & CANARD_CAN_EXT_ID_MASK) == can_id); // Flags must be cleared + + if (transfer->inout_transfer_id == NULL) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + if ((transfer->payload_len > 0) && (transfer->payload == NULL)) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + int16_t result = 0; +#if CANARD_ENABLE_CANFD + uint8_t frame_max_data_len = transfer->canfd ? CANARD_CANFD_FRAME_MAX_DATA_LEN:CANARD_CAN_FRAME_MAX_DATA_LEN; +#else + uint8_t frame_max_data_len = CANARD_CAN_FRAME_MAX_DATA_LEN; +#endif + if (transfer->payload_len < frame_max_data_len) // Single frame transfer + { + CanardTxQueueItem* queue_item = createTxItem(&ins->allocator); + if (queue_item == NULL) + { + return -CANARD_ERROR_OUT_OF_MEMORY; + } + + memcpy(queue_item->frame.data, transfer->payload, transfer->payload_len); + + transfer->payload_len = dlcToDataLength(dataLengthToDlc(transfer->payload_len+1))-1; + queue_item->frame.data_len = (uint8_t)(transfer->payload_len + 1); + queue_item->frame.data[transfer->payload_len] = (uint8_t)(0xC0U | (*transfer->inout_transfer_id & 31U)); + queue_item->frame.id = can_id | CANARD_CAN_FRAME_EFF; +#if CANARD_ENABLE_DEADLINE + queue_item->frame.deadline_usec = transfer->deadline_usec; +#endif +#if CANARD_MULTI_IFACE + queue_item->frame.iface_mask = transfer->iface_mask; +#endif +#if CANARD_ENABLE_CANFD + queue_item->frame.canfd = transfer->canfd; +#endif + pushTxQueue(ins, queue_item); + result++; + } + else // Multi frame transfer + { + uint16_t data_index = 0; + uint8_t toggle = 0; + uint8_t sot_eot = 0x80; + + CanardTxQueueItem* queue_item = NULL; + + while (transfer->payload_len - data_index != 0) + { + queue_item = createTxItem(&ins->allocator); + if (queue_item == NULL) + { + CANARD_ASSERT(false); + return -CANARD_ERROR_OUT_OF_MEMORY; // TODO: Purge all frames enqueued so far + } + + uint16_t i = 0; + if (data_index == 0) + { + // add crc + queue_item->frame.data[0] = (uint8_t) (crc); + queue_item->frame.data[1] = (uint8_t) (crc >> 8U); + i = 2; + } + else + { + i = 0; + } + + for (; i < (frame_max_data_len - 1) && data_index < transfer->payload_len; i++, data_index++) + { + queue_item->frame.data[i] = transfer->payload[data_index]; + } + // tail byte + sot_eot = (data_index == transfer->payload_len) ? (uint8_t)0x40 : sot_eot; + + i = dlcToDataLength(dataLengthToDlc(i+1))-1; + queue_item->frame.data[i] = (uint8_t)(sot_eot | ((uint32_t)toggle << 5U) | ((uint32_t)*transfer->inout_transfer_id & 31U)); + queue_item->frame.id = can_id | CANARD_CAN_FRAME_EFF; + queue_item->frame.data_len = (uint8_t)(i + 1); +#if CANARD_ENABLE_DEADLINE + queue_item->frame.deadline_usec = transfer->deadline_usec; +#endif +#if CANARD_MULTI_IFACE + queue_item->frame.iface_mask = transfer->iface_mask; +#endif +#if CANARD_ENABLE_CANFD + queue_item->frame.canfd = transfer->canfd; +#endif + pushTxQueue(ins, queue_item); + + result++; + toggle ^= 1; + sot_eot = 0; + } + } + + return result; +} + +/** + * Puts frame on on the TX queue. Higher priority placed first + */ +CANARD_INTERNAL void pushTxQueue(CanardInstance* ins, CanardTxQueueItem* item) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(item->frame.data_len > 0); // UAVCAN doesn't allow zero-payload frames + + if (ins->tx_queue == NULL) + { + ins->tx_queue = item; + return; + } + + CanardTxQueueItem* queue = ins->tx_queue; + CanardTxQueueItem* previous = ins->tx_queue; + + while (queue != NULL) + { + if (isPriorityHigher(queue->frame.id, item->frame.id)) // lower number wins + { + if (queue == ins->tx_queue) + { + item->next = queue; + ins->tx_queue = item; + } + else + { + previous->next = item; + item->next = queue; + } + return; + } + else + { + if (queue->next == NULL) + { + queue->next = item; + return; + } + else + { + previous = queue; + queue = queue->next; + } + } + } +} + +/** + * Creates new tx queue item from allocator + */ +CANARD_INTERNAL CanardTxQueueItem* createTxItem(CanardPoolAllocator* allocator) +{ + CanardTxQueueItem* item = (CanardTxQueueItem*) allocateBlock(allocator); + if (item == NULL) + { + return NULL; + } + memset(item, 0, sizeof(*item)); + return item; +} + +/** + * Returns true if priority of rhs is higher than id + */ +CANARD_INTERNAL bool isPriorityHigher(uint32_t rhs, uint32_t id) +{ + const uint32_t clean_id = id & CANARD_CAN_EXT_ID_MASK; + const uint32_t rhs_clean_id = rhs & CANARD_CAN_EXT_ID_MASK; + + /* + * STD vs EXT - if 11 most significant bits are the same, EXT loses. + */ + const bool ext = (id & CANARD_CAN_FRAME_EFF) != 0; + const bool rhs_ext = (rhs & CANARD_CAN_FRAME_EFF) != 0; + if (ext != rhs_ext) + { + uint32_t arb11 = ext ? (clean_id >> 18U) : clean_id; + uint32_t rhs_arb11 = rhs_ext ? (rhs_clean_id >> 18U) : rhs_clean_id; + if (arb11 != rhs_arb11) + { + return arb11 < rhs_arb11; + } + else + { + return rhs_ext; + } + } + + /* + * RTR vs Data frame - if frame identifiers and frame types are the same, RTR loses. + */ + const bool rtr = (id & CANARD_CAN_FRAME_RTR) != 0; + const bool rhs_rtr = (rhs & CANARD_CAN_FRAME_RTR) != 0; + if (clean_id == rhs_clean_id && rtr != rhs_rtr) + { + return rhs_rtr; + } + + /* + * Plain ID arbitration - greater value loses. + */ + return clean_id < rhs_clean_id; +} + +/** + * preps the rx state for the next transfer. does not delete the state + */ +CANARD_INTERNAL void prepareForNextTransfer(CanardRxState* state) +{ + CANARD_ASSERT(state->buffer_blocks == CANARD_BUFFER_IDX_NONE); + state->transfer_id++; + state->payload_len = 0; + state->next_toggle = 0; +} + +/** + * returns data type from id + */ +uint16_t extractDataType(uint32_t id) +{ + if (extractTransferType(id) == CanardTransferTypeBroadcast) + { + uint16_t dtid = MSG_TYPE_FROM_ID(id); + if (SOURCE_ID_FROM_ID(id) == CANARD_BROADCAST_NODE_ID) + { + dtid &= (1U << ANON_MSG_DATA_TYPE_ID_BIT_LEN) - 1U; + } + return dtid; + } + else + { + return (uint16_t) SRV_TYPE_FROM_ID(id); + } +} + +/** + * returns transfer type from id + */ +CanardTransferType extractTransferType(uint32_t id) +{ + const bool is_service = SERVICE_NOT_MSG_FROM_ID(id); + if (!is_service) + { + return CanardTransferTypeBroadcast; + } + else if (REQUEST_NOT_RESPONSE_FROM_ID(id) == 1) + { + return CanardTransferTypeRequest; + } + else + { + return CanardTransferTypeResponse; + } +} + +/* + * CanardRxState functions + */ + +/** + * Traverses the list of CanardRxState's and returns a pointer to the CanardRxState + * with either the Id or a new one at the end + */ +CANARD_INTERNAL CanardRxState* traverseRxStates(CanardInstance* ins, uint32_t transfer_descriptor) +{ + CanardRxState* states = ins->rx_states; + + if (states == NULL) // initialize CanardRxStates + { + states = createRxState(&ins->allocator, transfer_descriptor); + + if(states == NULL) + { + return NULL; + } + + ins->rx_states = states; + return states; + } + + states = findRxState(ins, transfer_descriptor); + if (states != NULL) + { + return states; + } + else + { + return prependRxState(ins, transfer_descriptor); + } +} + +/** + * returns pointer to the rx state of transfer descriptor or null if not found + */ +CANARD_INTERNAL CanardRxState* findRxState(CanardInstance *ins, uint32_t transfer_descriptor) +{ + CanardRxState *state = ins->rx_states; + while (state != NULL) + { + if (state->dtid_tt_snid_dnid == transfer_descriptor) + { + return state; + } + state = canardRxFromIdx(&ins->allocator, state->next); + } + return NULL; +} + +/** + * prepends rx state to the canard instance rx_states + */ +CANARD_INTERNAL CanardRxState* prependRxState(CanardInstance* ins, uint32_t transfer_descriptor) +{ + CanardRxState* state = createRxState(&ins->allocator, transfer_descriptor); + + if(state == NULL) + { + return NULL; + } + + state->next = canardRxToIdx(&ins->allocator, ins->rx_states); + ins->rx_states = state; + return state; +} + +CANARD_INTERNAL CanardRxState* createRxState(CanardPoolAllocator* allocator, uint32_t transfer_descriptor) +{ + CanardRxState init = { + .next = CANARD_BUFFER_IDX_NONE, + .buffer_blocks = CANARD_BUFFER_IDX_NONE, + .dtid_tt_snid_dnid = transfer_descriptor + }; + + CanardRxState* state = (CanardRxState*) allocateBlock(allocator); + if (state == NULL) + { + return NULL; + } + memcpy(state, &init, sizeof(*state)); + + return state; +} + +CANARD_INTERNAL uint64_t releaseStatePayload(CanardInstance* ins, CanardRxState* rxstate) +{ + while (rxstate->buffer_blocks != CANARD_BUFFER_IDX_NONE) + { + CanardBufferBlock* block = canardBufferFromIdx(&ins->allocator, rxstate->buffer_blocks); + CanardBufferBlock* const temp = block->next; + freeBlock(&ins->allocator, block); + rxstate->buffer_blocks = canardBufferToIdx(&ins->allocator, temp); + } + rxstate->payload_len = 0; + return CANARD_OK; +} + +/* + * CanardBufferBlock functions + */ + +/** + * pushes data into the rx state. Fills the buffer head, then appends data to buffer blocks + */ +CANARD_INTERNAL int16_t bufferBlockPushBytes(CanardPoolAllocator* allocator, + CanardRxState* state, + const uint8_t* data, + uint8_t data_len) +{ + uint16_t data_index = 0; + + // if head is not full, add data to head + if ((CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE - state->payload_len) > 0) + { + for (uint16_t i = (uint16_t)state->payload_len; + i < CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE && data_index < data_len; + i++, data_index++) + { + state->buffer_head[i] = data[data_index]; + } + if (data_index >= data_len) + { + state->payload_len = + (uint16_t)(state->payload_len + data_len) & ((1U << CANARD_TRANSFER_PAYLOAD_LEN_BITS) - 1U); + return 1; + } + } // head is full. + + uint16_t index_at_nth_block = + (uint16_t)(((state->payload_len) - CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) % CANARD_BUFFER_BLOCK_DATA_SIZE); + + // get to current block + CanardBufferBlock* block = NULL; + + // buffer blocks uninitialized + if (state->buffer_blocks == CANARD_BUFFER_IDX_NONE) + { + block = createBufferBlock(allocator); + state->buffer_blocks = canardBufferToIdx(allocator, block); + if (block == NULL) + { + return -CANARD_ERROR_OUT_OF_MEMORY; + } + + index_at_nth_block = 0; + } + else + { + uint16_t nth_block = 1; + + // get to block + block = canardBufferFromIdx(allocator, state->buffer_blocks); + while (block->next != NULL) + { + nth_block++; + block = block->next; + } + + const uint16_t num_buffer_blocks = + (uint16_t) (((((uint32_t)state->payload_len + data_len) - CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) / + CANARD_BUFFER_BLOCK_DATA_SIZE) + 1U); + + if (num_buffer_blocks > nth_block && index_at_nth_block == 0) + { + block->next = createBufferBlock(allocator); + if (block->next == NULL) + { + return -CANARD_ERROR_OUT_OF_MEMORY; + } + block = block->next; + } + } + + // add data to current block until it becomes full, add new block if necessary + while (data_index < data_len) + { + for (uint16_t i = index_at_nth_block; + i < CANARD_BUFFER_BLOCK_DATA_SIZE && data_index < data_len; + i++, data_index++) + { + block->data[i] = data[data_index]; + } + + if (data_index < data_len) + { + block->next = createBufferBlock(allocator); + if (block->next == NULL) + { + return -CANARD_ERROR_OUT_OF_MEMORY; + } + block = block->next; + index_at_nth_block = 0; + } + } + + state->payload_len = (uint16_t)(state->payload_len + data_len) & ((1U << CANARD_TRANSFER_PAYLOAD_LEN_BITS) - 1U); + + return 1; +} + +CANARD_INTERNAL CanardBufferBlock* createBufferBlock(CanardPoolAllocator* allocator) +{ + CanardBufferBlock* block = (CanardBufferBlock*) allocateBlock(allocator); + if (block == NULL) + { + return NULL; + } + block->next = NULL; + return block; +} + +/** + * Bit array copy routine, originally developed by Ben Dyer for Libuavcan. Thanks Ben. + */ +void copyBitArray(const uint8_t* src, uint32_t src_offset, uint32_t src_len, + uint8_t* dst, uint32_t dst_offset) +{ + CANARD_ASSERT(src_len > 0U); + + // Normalizing inputs + src += src_offset / 8U; + dst += dst_offset / 8U; + + src_offset %= 8U; + dst_offset %= 8U; + + const size_t last_bit = src_offset + src_len; + while (last_bit - src_offset) + { + const uint8_t src_bit_offset = (uint8_t)(src_offset % 8U); + const uint8_t dst_bit_offset = (uint8_t)(dst_offset % 8U); + + const uint8_t max_offset = MAX(src_bit_offset, dst_bit_offset); + const uint32_t copy_bits = (uint32_t)MIN(last_bit - src_offset, 8U - max_offset); + +#if WORD_ADDRESSING_IS_16BITS + /* + * (uint8_t) same as (uint16_t) + * Mask 0xFF must be used + */ + const uint8_t write_mask = (uint8_t)((uint8_t)((0xFF00U >> copy_bits)&0xFF) >> dst_bit_offset)&0xFF; + const uint8_t src_data = (uint8_t)(((uint32_t)src[src_offset / 8U] << src_bit_offset) >> dst_bit_offset)&0xFF; + + dst[dst_offset / 8U] = + (uint8_t)(((uint32_t)dst[dst_offset / 8U] & (uint32_t)~write_mask) | (uint32_t)(src_data & write_mask))&0xFF; +#else + const uint8_t write_mask = (uint8_t)((uint8_t)(0xFF00U >> copy_bits) >> dst_bit_offset); + const uint8_t src_data = (uint8_t)(((uint32_t)src[src_offset / 8U] << src_bit_offset) >> dst_bit_offset); + + dst[dst_offset / 8U] = + (uint8_t)(((uint32_t)dst[dst_offset / 8U] & (uint32_t)~write_mask) | (uint32_t)(src_data & write_mask)); +#endif + + src_offset += copy_bits; + dst_offset += copy_bits; + } +} + +CANARD_INTERNAL int16_t descatterTransferPayload(const CanardRxTransfer* transfer, + uint32_t bit_offset, + uint8_t bit_length, + void* output) +{ + CANARD_ASSERT(transfer != 0); + + if (bit_offset >= transfer->payload_len * 8) + { + return 0; // Out of range, reading zero bits + } + + if (bit_offset + bit_length > transfer->payload_len * 8) + { + bit_length = (uint8_t)(transfer->payload_len * 8U - bit_offset); + } + + CANARD_ASSERT(bit_length > 0); + + if ((transfer->payload_middle != NULL) || (transfer->payload_tail != NULL)) // Multi frame + { + /* + * This part is hideously complicated and probably should be redesigned. + * The objective here is to copy the requested number of bits from scattered storage into the temporary + * local storage. We go through great pains to ensure that all corner cases are handled correctly. + */ + uint32_t input_bit_offset = bit_offset; + uint8_t output_bit_offset = 0; + uint8_t remaining_bit_length = bit_length; + + // Reading head + if (input_bit_offset < CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8) + { + const uint8_t amount = (uint8_t)MIN(remaining_bit_length, + CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8U - input_bit_offset); + + copyBitArray(&transfer->payload_head[0], input_bit_offset, amount, (uint8_t*) output, 0); + + input_bit_offset += amount; + output_bit_offset = (uint8_t)(output_bit_offset + amount); + remaining_bit_length = (uint8_t)(remaining_bit_length - amount); + } + + // Reading middle + uint32_t remaining_bits = (uint32_t)(transfer->payload_len * 8U - CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8U); + uint32_t block_bit_offset = CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8U; + const CanardBufferBlock* block = transfer->payload_middle; + + while ((block != NULL) && (remaining_bit_length > 0)) + { + CANARD_ASSERT(remaining_bits > 0); + const uint32_t block_end_bit_offset = block_bit_offset + MIN(CANARD_BUFFER_BLOCK_DATA_SIZE * 8, + remaining_bits); + + // Perform copy if we've reached the requested offset, otherwise jump over this block and try next + if (block_end_bit_offset > input_bit_offset) + { + const uint8_t amount = (uint8_t) MIN(remaining_bit_length, block_end_bit_offset - input_bit_offset); + + CANARD_ASSERT(input_bit_offset >= block_bit_offset); + const uint32_t bit_offset_within_block = input_bit_offset - block_bit_offset; + + copyBitArray(&block->data[0], bit_offset_within_block, amount, (uint8_t*) output, output_bit_offset); + + input_bit_offset += amount; + output_bit_offset = (uint8_t)(output_bit_offset + amount); + remaining_bit_length = (uint8_t)(remaining_bit_length - amount); + } + + CANARD_ASSERT(block_end_bit_offset > block_bit_offset); + remaining_bits -= block_end_bit_offset - block_bit_offset; + block_bit_offset = block_end_bit_offset; + block = block->next; + } + + CANARD_ASSERT(remaining_bit_length <= remaining_bits); + + // Reading tail + if ((transfer->payload_tail != NULL) && (remaining_bit_length > 0)) + { + CANARD_ASSERT(input_bit_offset >= block_bit_offset); + const uint32_t offset = input_bit_offset - block_bit_offset; + + copyBitArray(&transfer->payload_tail[0], offset, remaining_bit_length, (uint8_t*) output, + output_bit_offset); + + input_bit_offset += remaining_bit_length; + output_bit_offset = (uint8_t)(output_bit_offset + remaining_bit_length); + remaining_bit_length = 0; + } + + CANARD_ASSERT(input_bit_offset <= transfer->payload_len * 8); + CANARD_ASSERT(output_bit_offset <= 64); + CANARD_ASSERT(remaining_bit_length == 0); + } + else // Single frame + { + copyBitArray(&transfer->payload_head[0], bit_offset, bit_length, (uint8_t*) output, 0); + } + + return bit_length; +} + +CANARD_INTERNAL bool isBigEndian(void) +{ +#if defined(BYTE_ORDER) && defined(BIG_ENDIAN) + return BYTE_ORDER == BIG_ENDIAN; // Some compilers offer this neat shortcut +#else + union + { +#if WORD_ADDRESSING_IS_16BITS + /* + * with 16-bit memory addressing u8b[0]=u16a, u8b[1]=NOTHING + */ + uint32_t a; + uint16_t b[2]; +#else + uint16_t a; + uint8_t b[2]; +#endif + } u; + u.a = 1; + return u.b[1] == 1; // Some don't... +#endif +} + +CANARD_INTERNAL void swapByteOrder(void* data, unsigned size) +{ + CANARD_ASSERT(data != NULL); + + uint8_t* const bytes = (uint8_t*) data; + + size_t fwd = 0; + size_t rev = size - 1; + + while (fwd < rev) + { + const uint8_t x = bytes[fwd]; + bytes[fwd] = bytes[rev]; + bytes[rev] = x; + fwd++; + rev--; + } +} + +/* + * CRC functions + */ +CANARD_INTERNAL uint16_t crcAddByte(uint16_t crc_val, uint8_t byte) +{ + crc_val ^= (uint16_t) ((uint16_t) (byte) << 8U); + for (uint8_t j = 0; j < 8; j++) + { + if (crc_val & 0x8000U) + { + crc_val = (uint16_t) ((uint16_t) (crc_val << 1U) ^ 0x1021U); + } + else + { + crc_val = (uint16_t) (crc_val << 1U); + } + } + return crc_val; +} + +CANARD_INTERNAL uint16_t crcAddSignature(uint16_t crc_val, uint64_t data_type_signature) +{ + for (uint16_t shift_val = 0; shift_val < 64; shift_val = (uint16_t)(shift_val + 8U)) + { + crc_val = crcAddByte(crc_val, (uint8_t) (data_type_signature >> shift_val)); + } + return crc_val; +} + +CANARD_INTERNAL uint16_t crcAdd(uint16_t crc_val, const uint8_t* bytes, size_t len) +{ + while (len--) + { + crc_val = crcAddByte(crc_val, *bytes++); + } + return crc_val; +} + +/* + * Pool Allocator functions + */ +CANARD_INTERNAL void initPoolAllocator(CanardPoolAllocator* allocator, + void* buf, + uint16_t buf_len) +{ + size_t current_index = 0; + CanardPoolAllocatorBlock *abuf = buf; + allocator->arena = buf; + CanardPoolAllocatorBlock** current_block = &(allocator->free_list); + while (current_index < buf_len) + { + *current_block = &abuf[current_index]; + current_block = &((*current_block)->next); + current_index++; + } + *current_block = NULL; + + allocator->statistics.capacity_blocks = buf_len; + allocator->statistics.current_usage_blocks = 0; + allocator->statistics.peak_usage_blocks = 0; + // user should initialize semaphore after the canardInit + // or at first call of canard_allocate_sem_take + allocator->semaphore = NULL; +} + +CANARD_INTERNAL void* allocateBlock(CanardPoolAllocator* allocator) +{ +#if CANARD_ALLOCATE_SEM + canard_allocate_sem_take(allocator); +#endif + // Check if there are any blocks available in the free list. + if (allocator->free_list == NULL) + { +#if CANARD_ALLOCATE_SEM + canard_allocate_sem_give(allocator); +#endif + return NULL; + } + + // Take first available block and prepares next block for use. + void* result = allocator->free_list; + allocator->free_list = allocator->free_list->next; + + // Update statistics + allocator->statistics.current_usage_blocks++; + if (allocator->statistics.peak_usage_blocks < allocator->statistics.current_usage_blocks) + { + allocator->statistics.peak_usage_blocks = allocator->statistics.current_usage_blocks; + } +#if CANARD_ALLOCATE_SEM + canard_allocate_sem_give(allocator); +#endif + return result; +} + +CANARD_INTERNAL void freeBlock(CanardPoolAllocator* allocator, void* p) +{ +#if CANARD_ALLOCATE_SEM + canard_allocate_sem_take(allocator); +#endif + CanardPoolAllocatorBlock* block = (CanardPoolAllocatorBlock*) p; + + block->next = allocator->free_list; + allocator->free_list = block; + + CANARD_ASSERT(allocator->statistics.current_usage_blocks > 0); + allocator->statistics.current_usage_blocks--; +#if CANARD_ALLOCATE_SEM + canard_allocate_sem_give(allocator); +#endif +} diff --git a/bootloader/DroneCAN/libcanard/canard.h b/bootloader/DroneCAN/libcanard/canard.h new file mode 100644 index 00000000..78b738ad --- /dev/null +++ b/bootloader/DroneCAN/libcanard/canard.h @@ -0,0 +1,737 @@ +/* + * Copyright (c) 2016-2019 UAVCAN Team + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + * + * Contributors: https://github.com/UAVCAN/libcanard/contributors + * + * Documentation: http://uavcan.org/Implementations/Libcanard + */ + +#ifndef CANARD_H +#define CANARD_H + +#include +#include +#include +#include + +/// Build configuration header. Use it to provide your overrides. +#if defined(CANARD_ENABLE_CUSTOM_BUILD_CONFIG) && CANARD_ENABLE_CUSTOM_BUILD_CONFIG +# include "canard_build_config.h" +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +/// Libcanard version. API will be backwards compatible within the same major version. +#define CANARD_VERSION_MAJOR 0 +#define CANARD_VERSION_MINOR 2 + + +#ifndef CANARD_ENABLE_CANFD +#define CANARD_ENABLE_CANFD 0 +#endif + +#ifndef CANARD_MULTI_IFACE +#define CANARD_MULTI_IFACE 0 +#endif + +#ifndef CANARD_ENABLE_DEADLINE +#define CANARD_ENABLE_DEADLINE 0 +#endif + +#ifndef CANARD_ENABLE_TAO_OPTION +#if CANARD_ENABLE_CANFD +#define CANARD_ENABLE_TAO_OPTION 1 +#else +#define CANARD_ENABLE_TAO_OPTION 0 +#endif +#endif + +/// By default this macro resolves to the standard assert(). The user can redefine this if necessary. +#ifndef CANARD_ASSERT +#ifdef CANARD_ENABLE_ASSERTS +# define CANARD_ASSERT(x) assert(x) +#else +# define CANARD_ASSERT(x) +#endif +#endif // CANARD_ASSERT + +#define CANARD_GLUE(a, b) CANARD_GLUE_IMPL_(a, b) +#define CANARD_GLUE_IMPL_(a, b) a##b + +/// By default this macro expands to static_assert if supported by the language (C11, C++11, or newer). +/// The user can redefine this if necessary. +#ifndef CANARD_STATIC_ASSERT +# if (defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 201112L)) ||\ + (defined(__cplusplus) && (__cplusplus >= 201103L)) +# define CANARD_STATIC_ASSERT(...) static_assert(__VA_ARGS__) +# else +# define CANARD_STATIC_ASSERT(x, ...) typedef char CANARD_GLUE(_static_assertion_, __LINE__)[(x) ? 1 : -1] +# endif +#endif + +#ifndef CANARD_ALLOCATE_SEM +#define CANARD_ALLOCATE_SEM 0 +#endif +/// Error code definitions; inverse of these values may be returned from API calls. +#define CANARD_OK 0 +// Value 1 is omitted intentionally, since -1 is often used in 3rd party code +#define CANARD_ERROR_INVALID_ARGUMENT 2 +#define CANARD_ERROR_OUT_OF_MEMORY 3 +#define CANARD_ERROR_NODE_ID_NOT_SET 4 +#define CANARD_ERROR_INTERNAL 9 +#define CANARD_ERROR_RX_INCOMPATIBLE_PACKET 10 +#define CANARD_ERROR_RX_WRONG_ADDRESS 11 +#define CANARD_ERROR_RX_NOT_WANTED 12 +#define CANARD_ERROR_RX_MISSED_START 13 +#define CANARD_ERROR_RX_WRONG_TOGGLE 14 +#define CANARD_ERROR_RX_UNEXPECTED_TID 15 +#define CANARD_ERROR_RX_SHORT_FRAME 16 +#define CANARD_ERROR_RX_BAD_CRC 17 + +/// The size of a memory block in bytes. +#if CANARD_ENABLE_CANFD +#define CANARD_MEM_BLOCK_SIZE 128U +#elif CANARD_ENABLE_DEADLINE +#define CANARD_MEM_BLOCK_SIZE 40U +#else +#define CANARD_MEM_BLOCK_SIZE 32U +#endif + +#define CANARD_CAN_FRAME_MAX_DATA_LEN 8U +#if CANARD_ENABLE_CANFD +#define CANARD_CANFD_FRAME_MAX_DATA_LEN 64U +#endif + +/// Node ID values. Refer to the specification for more info. +#define CANARD_BROADCAST_NODE_ID 0 +#define CANARD_MIN_NODE_ID 1 +#define CANARD_MAX_NODE_ID 127 + +/// Refer to the type CanardRxTransfer +#define CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE (CANARD_MEM_BLOCK_SIZE - offsetof(CanardRxState, buffer_head)) + +/// Refer to the type CanardBufferBlock +#define CANARD_BUFFER_BLOCK_DATA_SIZE (CANARD_MEM_BLOCK_SIZE - offsetof(CanardBufferBlock, data)) + +/// Refer to canardCleanupStaleTransfers() for details. +#define CANARD_RECOMMENDED_STALE_TRANSFER_CLEANUP_INTERVAL_USEC 1000000U + +/// Transfer priority definitions +#define CANARD_TRANSFER_PRIORITY_HIGHEST 0 +#define CANARD_TRANSFER_PRIORITY_HIGH 8 +#define CANARD_TRANSFER_PRIORITY_MEDIUM 16 +#define CANARD_TRANSFER_PRIORITY_LOW 24 +#define CANARD_TRANSFER_PRIORITY_LOWEST 31 + +/// Related to CanardCANFrame +#define CANARD_CAN_EXT_ID_MASK 0x1FFFFFFFU +#define CANARD_CAN_STD_ID_MASK 0x000007FFU +#define CANARD_CAN_FRAME_EFF (1UL << 31U) ///< Extended frame format +#define CANARD_CAN_FRAME_RTR (1UL << 30U) ///< Remote transmission (not used by UAVCAN) +#define CANARD_CAN_FRAME_ERR (1UL << 29U) ///< Error frame (not used by UAVCAN) + +#define CANARD_TRANSFER_PAYLOAD_LEN_BITS 10U +#define CANARD_MAX_TRANSFER_PAYLOAD_LEN ((1U << CANARD_TRANSFER_PAYLOAD_LEN_BITS) - 1U) + +#ifndef CANARD_64_BIT +#ifdef __WORDSIZE +#define CANARD_64_BIT (__WORDSIZE == 64) +#else +#define CANARD_64_BIT 0 +#endif +#endif + +/* + canard_buffer_idx_t is used to avoid pointers in data structures + that have to have the same size on both 32 bit and 64 bit + platforms. It is an index into mem_arena passed to canardInit + treated as a uint8_t array + + A value of CANARD_BUFFER_IDX_NONE means a NULL pointer + */ +#if CANARD_64_BIT +typedef uint32_t canard_buffer_idx_t; +#define CANARD_BUFFER_IDX_NONE 0U +#else +typedef void* canard_buffer_idx_t; +#define CANARD_BUFFER_IDX_NONE NULL +#endif + + + +/** + * This data type holds a standard CAN 2.0B data frame with 29-bit ID. + */ +typedef struct +{ + /** + * Refer to the following definitions: + * - CANARD_CAN_FRAME_EFF + * - CANARD_CAN_FRAME_RTR + * - CANARD_CAN_FRAME_ERR + */ + uint32_t id; +#if CANARD_ENABLE_DEADLINE + uint64_t deadline_usec; +#endif +#if CANARD_ENABLE_CANFD + uint8_t data[CANARD_CANFD_FRAME_MAX_DATA_LEN]; +#else + uint8_t data[CANARD_CAN_FRAME_MAX_DATA_LEN]; +#endif + uint8_t data_len; + uint8_t iface_id; +#if CANARD_MULTI_IFACE + uint8_t iface_mask; +#endif +#if CANARD_ENABLE_CANFD + bool canfd; +#endif +} CanardCANFrame; + +/** + * Transfer types are defined by the UAVCAN specification. + */ +typedef enum +{ + CanardTransferTypeResponse = 0, + CanardTransferTypeRequest = 1, + CanardTransferTypeBroadcast = 2 +} CanardTransferType; + +/** + * Types of service transfers. These are not applicable to message transfers. + */ +typedef enum +{ + CanardResponse, + CanardRequest +} CanardRequestResponse; + +/* + * Forward declarations. + */ +typedef struct CanardInstance CanardInstance; +typedef struct CanardRxTransfer CanardRxTransfer; +typedef struct CanardRxState CanardRxState; +typedef struct CanardTxQueueItem CanardTxQueueItem; + +/** + * This struture provides information about encoded dronecan frame that needs + * to be put on the wire. + * + * In case of broadcast or request pointer to the Transfer ID should point to a persistent variable + * (e.g. static or heap allocated, not on the stack); it will be updated by the library after every transmission. + * The Transfer ID value cannot be shared between transfers that have different descriptors! + * More on this in the transport layer specification. + * + * For the case of response, the pointer to the Transfer ID is treated as const and generally points to transfer id + * in CanardRxTransfer structure. + * + */ +typedef struct { + CanardTransferType transfer_type; ///< Type of transfer: CanardTransferTypeBroadcast, CanardTransferTypeRequest, CanardTransferTypeResponse + uint64_t data_type_signature; ///< Signature of the message/service + uint16_t data_type_id; ///< ID of the message/service + uint8_t* inout_transfer_id; ///< Transfer ID reference + uint8_t priority; ///< Priority of the transfer + const uint8_t* payload; ///< Pointer to the payload + uint16_t payload_len; ///< Length of the payload +#if CANARD_ENABLE_CANFD + bool canfd; ///< True if CAN FD is enabled +#endif +#if CANARD_ENABLE_DEADLINE + uint64_t deadline_usec; ///< Deadline in microseconds +#endif +#if CANARD_MULTI_IFACE + uint8_t iface_mask; ///< Bitmask of interfaces to send the transfer on +#endif +#if CANARD_ENABLE_TAO_OPTION + bool tao; ///< True if tail array optimization is enabled +#endif +} CanardTxTransfer; + +struct CanardTxQueueItem +{ + CanardTxQueueItem* next; + CanardCANFrame frame; +}; +CANARD_STATIC_ASSERT(sizeof(CanardTxQueueItem) <= CANARD_MEM_BLOCK_SIZE, "Unexpected memory block size"); +/** + * The application must implement this function and supply a pointer to it to the library during initialization. + * The library calls this function to determine whether the transfer should be received. + * + * If the application returns true, the value pointed to by 'out_data_type_signature' must be initialized with the + * correct data type signature, otherwise transfer reception will fail with CRC mismatch error. Please refer to the + * specification for more details about data type signatures. Signature for any data type can be obtained in many + * ways; for example, using the command line tool distributed with Libcanard (see the repository). + */ +typedef bool (* CanardShouldAcceptTransfer)(const CanardInstance* ins, ///< Library instance + uint64_t* out_data_type_signature, ///< Must be set by the application! + uint16_t data_type_id, ///< Refer to the specification + CanardTransferType transfer_type, ///< Refer to CanardTransferType + uint8_t source_node_id); ///< Source node ID or Broadcast (0) + +/** + * This function will be invoked by the library every time a transfer is successfully received. + * If the application needs to send another transfer from this callback, it is highly recommended + * to call canardReleaseRxTransferPayload() first, so that the memory that was used for the block + * buffer can be released and re-used by the TX queue. + */ +typedef void (* CanardOnTransferReception)(CanardInstance* ins, ///< Library instance + CanardRxTransfer* transfer); ///< Ptr to temporary transfer object + +/** + * INTERNAL DEFINITION, DO NOT USE DIRECTLY. + * A memory block used in the memory block allocator. + */ +typedef union CanardPoolAllocatorBlock_u +{ + char bytes[CANARD_MEM_BLOCK_SIZE]; + union CanardPoolAllocatorBlock_u* next; +} CanardPoolAllocatorBlock; + +/** + * This structure provides usage statistics of the memory pool allocator. + * This data helps to evaluate whether the allocated memory is sufficient for the application. + */ +typedef struct +{ + uint16_t capacity_blocks; ///< Pool capacity in number of blocks + uint16_t current_usage_blocks; ///< Number of blocks that are currently allocated by the library + uint16_t peak_usage_blocks; ///< Maximum number of blocks used since initialization +} CanardPoolAllocatorStatistics; + +/** + * INTERNAL DEFINITION, DO NOT USE DIRECTLY. + * Buffer block for received data. + */ +typedef struct CanardBufferBlock +{ + struct CanardBufferBlock* next; + uint8_t data[]; +} CanardBufferBlock; + +/** + * INTERNAL DEFINITION, DO NOT USE DIRECTLY. + */ +typedef struct +{ + // user should initialize semaphore after the canardInit + // or at first call of canard_allocate_sem_take + void *semaphore; + CanardPoolAllocatorBlock* free_list; + CanardPoolAllocatorStatistics statistics; + void *arena; +} CanardPoolAllocator; + + +/** + * INTERNAL DEFINITION, DO NOT USE DIRECTLY. + */ +struct CanardRxState +{ + canard_buffer_idx_t next; + canard_buffer_idx_t buffer_blocks; + + uint64_t timestamp_usec; + + const uint32_t dtid_tt_snid_dnid; + + // We're using plain 'unsigned' here, because C99 doesn't permit explicit field type specification + unsigned calculated_crc : 16; + unsigned payload_len : CANARD_TRANSFER_PAYLOAD_LEN_BITS; + unsigned transfer_id : 5; + unsigned next_toggle : 1; // 16+10+5+1 = 32, aligned. + + uint16_t payload_crc; + uint8_t iface_id; + uint8_t buffer_head[]; +}; +CANARD_STATIC_ASSERT(offsetof(CanardRxState, buffer_head) <= 27, "Invalid memory layout"); +CANARD_STATIC_ASSERT(CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE >= 5, "Invalid memory layout"); + +/** + * This is the core structure that keeps all of the states and allocated resources of the library instance. + * The application should never access any of the fields directly! Instead, API functions should be used. + */ +struct CanardInstance +{ + uint8_t node_id; ///< Local node ID; may be zero if the node is anonymous + + CanardShouldAcceptTransfer should_accept; ///< Function to decide whether the application wants this transfer + CanardOnTransferReception on_reception; ///< Function the library calls after RX transfer is complete + + CanardPoolAllocator allocator; ///< Pool allocator + + CanardRxState* rx_states; ///< RX transfer states + CanardTxQueueItem* tx_queue; ///< TX frames awaiting transmission + + void* user_reference; ///< User pointer that can link this instance with other objects + +#if CANARD_ENABLE_TAO_OPTION + bool tao_disabled; ///< True if TAO is disabled +#endif +}; + +/** + * This structure represents a received transfer for the application. + * An instance of it is passed to the application via callback when the library receives a new transfer. + * Pointers to the structure and all its fields are invalidated after the callback returns. + */ +struct CanardRxTransfer +{ + /** + * Timestamp at which the first frame of this transfer was received. + */ + uint64_t timestamp_usec; + + /** + * Payload is scattered across three storages: + * - Head points to CanardRxState.buffer_head (length of which is up to CANARD_PAYLOAD_HEAD_SIZE), or to the + * payload field (possibly with offset) of the last received CAN frame. + * + * - Middle is located in the linked list of dynamic blocks (only for multi-frame transfers). + * + * - Tail points to the payload field (possibly with offset) of the last received CAN frame + * (only for multi-frame transfers). + * + * The tail offset depends on how much data of the last frame was accommodated in the last allocated block. + * + * For single-frame transfers, middle and tail will be NULL, and the head will point at first byte + * of the payload of the CAN frame. + * + * In simple cases it should be possible to get data directly from the head and/or tail pointers. + * Otherwise it is advised to use canardDecodeScalar(). + */ + const uint8_t* payload_head; ///< Always valid, i.e. not NULL. + ///< For multi frame transfers, the maximum size is defined in the constant + ///< CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE. + ///< For single-frame transfers, the size is defined in the + ///< field payload_len. + CanardBufferBlock* payload_middle; ///< May be NULL if the buffer was not needed. Always NULL for single-frame + ///< transfers. + const uint8_t* payload_tail; ///< Last bytes of multi-frame transfers. Always NULL for single-frame + ///< transfers. + uint16_t payload_len; ///< Effective length of the payload in bytes. + + /** + * These fields identify the transfer for the application. + */ + uint16_t data_type_id; ///< 0 to 255 for services, 0 to 65535 for messages + uint8_t transfer_type; ///< See CanardTransferType + uint8_t transfer_id; ///< 0 to 31 + uint8_t priority; ///< 0 to 31 + uint8_t source_node_id; ///< 1 to 127, or 0 if the source is anonymous +#if CANARD_ENABLE_TAO_OPTION + bool tao; +#endif +#if CANARD_ENABLE_CANFD + bool canfd; ///< frame canfd +#endif +}; + +/** + * Initializes a library instance. + * Local node ID will be set to zero, i.e. the node will be anonymous. + * + * Typically, size of the memory pool should not be less than 1K, although it depends on the application. The + * recommended way to detect the required pool size is to measure the peak pool usage after a stress-test. Refer to + * the function canardGetPoolAllocatorStatistics(). + */ +void canardInit(CanardInstance* out_ins, ///< Uninitialized library instance + void* mem_arena, ///< Raw memory chunk used for dynamic allocation + size_t mem_arena_size, ///< Size of the above, in bytes + CanardOnTransferReception on_reception, ///< Callback, see CanardOnTransferReception + CanardShouldAcceptTransfer should_accept, ///< Callback, see CanardShouldAcceptTransfer + void* user_reference); ///< Optional pointer for user's convenience, can be NULL + +/** + * Returns the value of the user pointer. + * The user pointer is configured once during initialization. + * It can be used to store references to any user-specific data, or to link the instance object with C++ objects. + */ +void* canardGetUserReference(const CanardInstance* ins); + +/** + * Assigns a new node ID value to the current node. + * Node ID can be assigned only once. + */ +void canardSetLocalNodeID(CanardInstance* ins, + uint8_t self_node_id); + +/** + * Returns node ID of the local node. + * Returns zero (broadcast) if the node ID is not set, i.e. if the local node is anonymous. + */ +uint8_t canardGetLocalNodeID(const CanardInstance* ins); + +/** + * Forgets the current node ID value so that a new Node ID can be assigned. + */ +void canardForgetLocalNodeID(CanardInstance* ins); + +/** + * Initialise TX transfer object. + * Should be called at least once before using transfer object to send transmissions. +*/ +void canardInitTxTransfer(CanardTxTransfer* transfer); + +/** + * Sends a broadcast transfer. + * If the node is in passive mode, only single frame transfers will be allowed (they will be transmitted as anonymous). + * + * For anonymous transfers, maximum data type ID (CanardTxTransfer::data_type_id) is limited to 3 (see specification for details). + * + * Please refer to the specification for more details about data type signatures (CanardTxTransfer::data_type_signature). Signature for + * any data type can be obtained in many ways; for example, using the generated code generated using dronecan_dsdlc (see the repository). + * + * Use CanardTxTransfer structure to pass the transfer parameters. The structure is initialized by the + * canardInitTxTransfer() function. + * + * Pointer to the Transfer ID (CanardTxTransfer::inout_transfer_id) should point to a persistent variable + * (e.g. static or heap allocated, not on the stack); it will be updated by the library after every transmission. + * The Transfer ID value cannot be shared between transfers that have different descriptors! + * More on this in the transport layer specification. + * + * Returns the number of frames enqueued, or negative error code. + */ + +int16_t canardBroadcastObj(CanardInstance* ins, ///< Library instance + CanardTxTransfer* transfer ///< Transfer object + ); + +// Legacy API, try to avoid using it, as this will not be extended with new features +int16_t canardBroadcast(CanardInstance* ins, ///< Library instance + uint64_t data_type_signature, ///< See above + uint16_t data_type_id, ///< Refer to the specification + uint8_t* inout_transfer_id, ///< Pointer to a persistent variable containing the transfer ID + uint8_t priority, ///< Refer to definitions CANARD_TRANSFER_PRIORITY_* + const void* payload, ///< Transfer payload + uint16_t payload_len ///< Length of the above, in bytes +#if CANARD_ENABLE_DEADLINE + ,uint64_t tx_deadline ///< Transmission deadline, microseconds +#endif +#if CANARD_MULTI_IFACE + ,uint8_t iface_mask ///< Bitmask of interfaces to transmit on +#endif +#if CANARD_ENABLE_CANFD + ,bool canfd ///< Is the frame canfd +#endif + ); +/** + * Sends a request or a response transfer. + * Fails if the node is in passive mode. + * + * Please refer to the specification for more details about data type signatures (CanardTxTransfer::data_type_signature). Signature for + * any data type can be obtained in many ways; for example, using the generated code generated using dronecan_dsdlc (see the repository). + * + * Pointer to the Transfer ID (CanardTxTransfer::inout_transfer_id) should point to a persistent variable + * (e.g. static or heap allocated, not on the stack); it will be updated by the library after every request. + * The Transfer ID value cannot be shared between requests that have different descriptors! + * More on this in the transport layer specification. + * + * For Response transfers, the pointer to the Transfer ID(CanardTxTransfer::inout_transfer_id) will be treated as const (i.e. read-only), + * and normally it should point to the transfer_id field of the structure CanardRxTransfer. + * + * Returns the number of frames enqueued, or negative error code. + */ + +int16_t canardRequestOrRespondObj(CanardInstance* ins, ///< Library instance + uint8_t destination_node_id, ///< Node ID of the server/client + CanardTxTransfer* transfer ///< Transfer object + ); +// Legacy API, try to avoid using it, as this will not be extended with new features +int16_t canardRequestOrRespond(CanardInstance* ins, ///< Library instance + uint8_t destination_node_id, ///< Node ID of the server/client + uint64_t data_type_signature, ///< See above + uint8_t data_type_id, ///< Refer to the specification + uint8_t* inout_transfer_id, ///< Pointer to a persistent variable with transfer ID + uint8_t priority, ///< Refer to definitions CANARD_TRANSFER_PRIORITY_* + CanardRequestResponse kind, ///< Refer to CanardRequestResponse + const void* payload, ///< Transfer payload + uint16_t payload_len ///< Length of the above, in bytes +#if CANARD_ENABLE_DEADLINE + ,uint64_t tx_deadline ///< Transmission deadline, microseconds +#endif +#if CANARD_MULTI_IFACE + ,uint8_t iface_mask ///< Bitmask of interfaces to transmit on +#endif +#if CANARD_ENABLE_CANFD + ,bool canfd ///< Is the frame canfd +#endif + ); +/** + * Returns a pointer to the top priority frame in the TX queue. + * Returns NULL if the TX queue is empty. + * The application will call this function after canardBroadcast() or canardRequestOrRespond() to transmit generated + * frames over the CAN bus. + */ +CanardCANFrame* canardPeekTxQueue(const CanardInstance* ins); + +/** + * Returns the timeout for the frame on top of TX queue. + * Returns zero if the TX queue is empty. + * The application will call this function after canardPeekTxQueue() to determine when to call canardPopTxQueue(), if + * the frame is not transmitted. + */ +#if CANARD_ENABLE_DEADLINE +uint64_t canardPeekTxQueueDeadline(const CanardInstance* ins); +#endif +/** + * Removes the top priority frame from the TX queue. + * The application will call this function after canardPeekTxQueue() once the obtained frame has been processed. + * Calling canardBroadcast() or canardRequestOrRespond() between canardPeekTxQueue() and canardPopTxQueue() + * is NOT allowed, because it may change the frame at the top of the TX queue. + */ +void canardPopTxQueue(CanardInstance* ins); + +/** + * Processes a received CAN frame with a timestamp. + * The application will call this function when it receives a new frame from the CAN bus. + * + * Return value will report any errors in decoding packets. + */ +int16_t canardHandleRxFrame(CanardInstance* ins, + const CanardCANFrame* frame, + uint64_t timestamp_usec); + +/** + * Traverses the list of transfers and removes those that were last updated more than timeout_usec microseconds ago. + * This function must be invoked by the application periodically, about once a second. + * Also refer to the constant CANARD_RECOMMENDED_STALE_TRANSFER_CLEANUP_INTERVAL_USEC. + */ +void canardCleanupStaleTransfers(CanardInstance* ins, + uint64_t current_time_usec); + +/** + * This function can be used to extract values from received UAVCAN transfers. It decodes a scalar value - + * boolean, integer, character, or floating point - from the specified bit position in the RX transfer buffer. + * Simple single-frame transfers can also be parsed manually. + * + * Returns the number of bits successfully decoded, which may be less than requested if operation ran out of + * buffer boundaries, or negated error code, such as invalid argument. + * + * Caveat: This function works correctly only on platforms that use two's complement signed integer representation. + * I am not aware of any modern microarchitecture that uses anything else than two's complement, so it should + * not affect portability in any way. + * + * The type of value pointed to by 'out_value' is defined as follows: + * + * | bit_length | value_is_signed | out_value points to | + * |------------|-----------------|------------------------------------------| + * | 1 | false | bool (may be incompatible with uint8_t!) | + * | 1 | true | N/A | + * | [2, 8] | false | uint8_t, or char | + * | [2, 8] | true | int8_t, or char | + * | [9, 16] | false | uint16_t | + * | [9, 16] | true | int16_t | + * | [17, 32] | false | uint32_t | + * | [17, 32] | true | int32_t, or 32-bit float | + * | [33, 64] | false | uint64_t | + * | [33, 64] | true | int64_t, or 64-bit float | + */ +int16_t canardDecodeScalar(const CanardRxTransfer* transfer, ///< The RX transfer where the data will be copied from + uint32_t bit_offset, ///< Offset, in bits, from the beginning of the transfer + uint8_t bit_length, ///< Length of the value, in bits; see the table + bool value_is_signed, ///< True if the value can be negative; see the table + void* out_value); ///< Pointer to the output storage; see the table + +/** + * This function can be used to encode values for later transmission in a UAVCAN transfer. It encodes a scalar value - + * boolean, integer, character, or floating point - and puts it to the specified bit position in the specified + * contiguous buffer. + * Simple single-frame transfers can also be encoded manually. + * + * Caveat: This function works correctly only on platforms that use two's complement signed integer representation. + * I am not aware of any modern microarchitecture that uses anything else than two's complement, so it should + * not affect portability in any way. + * + * The type of value pointed to by 'value' is defined as follows: + * + * | bit_length | value points to | + * |------------|------------------------------------------| + * | 1 | bool (may be incompatible with uint8_t!) | + * | [2, 8] | uint8_t, int8_t, or char | + * | [9, 16] | uint16_t, int16_t | + * | [17, 32] | uint32_t, int32_t, or 32-bit float | + * | [33, 64] | uint64_t, int64_t, or 64-bit float | + */ +void canardEncodeScalar(void* destination, ///< Destination buffer where the result will be stored + uint32_t bit_offset, ///< Offset, in bits, from the beginning of the destination buffer + uint8_t bit_length, ///< Length of the value, in bits; see the table + const void* value); ///< Pointer to the value; see the table + +/** + * This function can be invoked by the application to release pool blocks that are used + * to store the payload of the transfer. + * + * If the application needs to send new transfers from the transfer reception callback, this function should be + * invoked right before calling canardBroadcast() or canardRequestOrRespond(). Not releasing the buffers before + * transmission may cause higher peak usage of the memory pool. + * + * If the application didn't call this function before returning from the callback, the library will do that, + * so it is guaranteed that the memory will not leak. + */ +void canardReleaseRxTransferPayload(CanardInstance* ins, + CanardRxTransfer* transfer); + +/** + * Returns a copy of the pool allocator usage statistics. + * Refer to the type CanardPoolAllocatorStatistics. + * Use this function to determine worst case memory needs of your application. + */ +CanardPoolAllocatorStatistics canardGetPoolAllocatorStatistics(CanardInstance* ins); + +/** + * Float16 marshaling helpers. + * These functions convert between the native float and 16-bit float. + * It is assumed that the native float is IEEE 754 single precision float, otherwise results will be unpredictable. + * Vast majority of modern computers and microcontrollers use IEEE 754, so this limitation should not affect + * portability. + */ +uint16_t canardConvertNativeFloatToFloat16(float value); +float canardConvertFloat16ToNativeFloat(uint16_t value); + +uint16_t extractDataType(uint32_t id); +CanardTransferType extractTransferType(uint32_t id); + +/// Abort the build if the current platform is not supported. +#if CANARD_ENABLE_CANFD +CANARD_STATIC_ASSERT(((uint32_t)CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) < 128, + "Please define CANARD_64_BIT=1 for 64 bit builds"); +#else +CANARD_STATIC_ASSERT(((uint32_t)CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) < 32, + "Please define CANARD_64_BIT=1 for 64 bit builds"); +#endif + +#if CANARD_ALLOCATE_SEM +// user implemented functions for taking and freeing semaphores +void canard_allocate_sem_take(CanardPoolAllocator *allocator); +void canard_allocate_sem_give(CanardPoolAllocator *allocator); +#endif + +#ifdef __cplusplus +} +#endif +#endif diff --git a/bootloader/DroneCAN/libcanard/canard_internals.h b/bootloader/DroneCAN/libcanard/canard_internals.h new file mode 100644 index 00000000..c147c941 --- /dev/null +++ b/bootloader/DroneCAN/libcanard/canard_internals.h @@ -0,0 +1,201 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2016-2017 UAVCAN Team + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + * + * Contributors: https://github.com/UAVCAN/libcanard/contributors + */ + +/* + * This file holds function declarations that expose the library's internal definitions for unit testing. + * It is NOT part of the library's API and should not even be looked at by the user. + */ + +#ifndef CANARD_INTERNALS_H +#define CANARD_INTERNALS_H + +#include "canard.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/// This macro is needed only for testing and development. Do not redefine this in production. +#ifndef CANARD_INTERNAL +# define CANARD_INTERNAL static +#endif + +/* + * Some MCUs like TMS320 have 16-bits addressing, so + * 1. (uint8_t) same (uint16_t) + * 2. sizeof(float) is 2 + * 3. union not same like STM32, because type uint8_t does not exist in hardware + * + * union + * { + * uint64_t u8; + * uint64_t u16; + * uint64_t u32; + * uint64_t u64; + * uint8_t bytes[8]; + * } storage; + * + * address:| bytes: | u64: | u32: | u16: | u8: + * 0x00 | bytes[0] | (u64 )&0xFF | (u32 )&0xFF | u16 | u8 + * 0x01 | bytes[1] | (u64>>16)&0xFF | (u32>>16)&0xFF | + * 0x02 | bytes[2] | (u64>>32)&0xFF | + * 0x03 | bytes[3] | (u64>>48)&0xFF | + * 0x04 | bytes[4] | + * 0x05 | bytes[5] | + * 0x06 | bytes[6] | + * 0x07 | bytes[7] | + * + */ +#ifndef WORD_ADDRESSING_IS_16BITS +#if defined(__TI_COMPILER_VERSION__) || defined(__TMS320C2000__) +#define WORD_ADDRESSING_IS_16BITS 1 +#else +#define WORD_ADDRESSING_IS_16BITS 0 +#endif +#endif + +#if WORD_ADDRESSING_IS_16BITS +# define uint8_t uint16_t +# define int8_t int16_t +# define CANARD_SIZEOF_FLOAT 2 +#else +# define CANARD_SIZEOF_FLOAT 4 +#endif + +CANARD_INTERNAL CanardRxState* traverseRxStates(CanardInstance* ins, + uint32_t transfer_descriptor); + +CANARD_INTERNAL CanardRxState* createRxState(CanardPoolAllocator* allocator, + uint32_t transfer_descriptor); + +CANARD_INTERNAL CanardRxState* prependRxState(CanardInstance* ins, + uint32_t transfer_descriptor); + +CANARD_INTERNAL CanardRxState* findRxState(CanardInstance *ins, + uint32_t transfer_descriptor); + +CANARD_INTERNAL int16_t bufferBlockPushBytes(CanardPoolAllocator* allocator, + CanardRxState* state, + const uint8_t* data, + uint8_t data_len); + +CANARD_INTERNAL CanardBufferBlock* createBufferBlock(CanardPoolAllocator* allocator); + +CANARD_INTERNAL void pushTxQueue(CanardInstance* ins, + CanardTxQueueItem* item); + +CANARD_INTERNAL bool isPriorityHigher(uint32_t id, + uint32_t rhs); + +CANARD_INTERNAL CanardTxQueueItem* createTxItem(CanardPoolAllocator* allocator); + +CANARD_INTERNAL void prepareForNextTransfer(CanardRxState* state); + +CANARD_INTERNAL int16_t computeTransferIDForwardDistance(uint8_t a, + uint8_t b); + +CANARD_INTERNAL void incrementTransferID(uint8_t* transfer_id); + +CANARD_INTERNAL uint64_t releaseStatePayload(CanardInstance* ins, + CanardRxState* rxstate); + +CANARD_INTERNAL uint16_t dlcToDataLength(uint16_t dlc); +CANARD_INTERNAL uint16_t dataLengthToDlc(uint16_t data_length); + +/// Returns the number of frames enqueued +CANARD_INTERNAL int16_t enqueueTxFrames(CanardInstance* ins, + uint32_t can_id, + uint16_t crc, + CanardTxTransfer* transfer); + +CANARD_INTERNAL void copyBitArray(const uint8_t* src, + uint32_t src_offset, + uint32_t src_len, + uint8_t* dst, + uint32_t dst_offset); + +/** + * Moves specified bits from the scattered transfer storage to a specified contiguous buffer. + * Returns the number of bits copied, or negated error code. + */ +CANARD_INTERNAL int16_t descatterTransferPayload(const CanardRxTransfer* transfer, + uint32_t bit_offset, + uint8_t bit_length, + void* output); + +CANARD_INTERNAL bool isBigEndian(void); + +CANARD_INTERNAL void swapByteOrder(void* data, unsigned size); + +/* + * Transfer CRC + */ +CANARD_INTERNAL uint16_t crcAddByte(uint16_t crc_val, + uint8_t byte); + +CANARD_INTERNAL uint16_t crcAddSignature(uint16_t crc_val, + uint64_t data_type_signature); + +CANARD_INTERNAL uint16_t crcAdd(uint16_t crc_val, + const uint8_t* bytes, + size_t len); + +/** + * Inits a memory allocator. + * + * @param [in] allocator The memory allocator to initialize. + * @param [in] buf The buffer used by the memory allocator. + * @param [in] buf_len The number of blocks in buf. + */ +CANARD_INTERNAL void initPoolAllocator(CanardPoolAllocator* allocator, + void *buf, + uint16_t buf_len); + +/** + * Allocates a block from the given pool allocator. + */ +CANARD_INTERNAL void* allocateBlock(CanardPoolAllocator* allocator); + +/** + * Frees a memory block previously returned by canardAllocateBlock. + */ +CANARD_INTERNAL void freeBlock(CanardPoolAllocator* allocator, + void* p); + +CANARD_INTERNAL uint16_t calculateCRC(const CanardTxTransfer* transfer_object); + +CANARD_INTERNAL CanardBufferBlock *canardBufferFromIdx(CanardPoolAllocator* allocator, canard_buffer_idx_t idx); + +CANARD_INTERNAL canard_buffer_idx_t canardBufferToIdx(CanardPoolAllocator* allocator, const CanardBufferBlock *buf); + +CANARD_INTERNAL CanardRxState *canardRxFromIdx(CanardPoolAllocator* allocator, canard_buffer_idx_t idx); + +CANARD_INTERNAL canard_buffer_idx_t canardRxToIdx(CanardPoolAllocator* allocator, const CanardRxState *rx); + +#ifdef __cplusplus +} +#endif +#endif diff --git a/bootloader/DroneCAN/regenerate.sh b/bootloader/DroneCAN/regenerate.sh new file mode 100755 index 00000000..7c19ed47 --- /dev/null +++ b/bootloader/DroneCAN/regenerate.sh @@ -0,0 +1,48 @@ +#!/bin/bash +# regenerate the C API from DSDL + +[ -d Src/DroneCAN ] || { + echo "Must be run from top level of AM32 source tree" + exit 1 +} + +download() +{ + /bin/rm -rf tmp + mkdir -p tmp + + echo "Cloning DSDL" +git clone --depth 1 https://github.com/DroneCAN/DSDL tmp/DSDL + + echo "Cloning dronecan_dsdlc" +git clone --depth 1 https://github.com/DroneCAN/dronecan_dsdlc tmp/dronecan_dsdlc +} + +generate() +{ + echo "Running generator" + python3 tmp/dronecan_dsdlc/dronecan_dsdlc.py -O tmp/dsdl_generated tmp/DSDL/dronecan tmp/DSDL/uavcan tmp/DSDL/com tmp/DSDL/ardupilot +} + +download +generate + +# list of messages which we need to support, wildcards are added to get the sub-messages +MSGS="uavcan.protocol.NodeStatus uavcan.protocol.HardwareVersion uavcan.protocol.SoftwareVersion uavcan.protocol.GetNodeInfo uavcan.equipment.esc uavcan.protocol.dynamic_node_id uavcan.protocol.param uavcan.protocol.file uavcan.protocol.RestartNode uavcan.protocol.RestartNode uavcan.protocol.debug uavcan.equipment.safety.ArmingStatus" + + rm -rf Src/DroneCAN/dsdl_generated + mkdir -p Src/DroneCAN/dsdl_generated/src + mkdir -p Src/DroneCAN/dsdl_generated/include + + for m in $MSGS; do +echo "Copying $m" +cp tmp/dsdl_generated/src/$m* Src/DroneCAN/dsdl_generated/src/ +cp tmp/dsdl_generated/include/$m* Src/DroneCAN/dsdl_generated/include/ +done + +echo "#pragma once" > Src/DroneCAN/dsdl_generated/dronecan_msgs.h +for f in $(/bin/ls Src/DroneCAN/dsdl_generated/include); do + echo "#include \"$f\"" >> Src/DroneCAN/dsdl_generated/dronecan_msgs.h + done + + rm -rf tmp diff --git a/bootloader/DroneCAN/sys_can.h b/bootloader/DroneCAN/sys_can.h new file mode 100644 index 00000000..a6676144 --- /dev/null +++ b/bootloader/DroneCAN/sys_can.h @@ -0,0 +1,84 @@ +/* + sys_can.h - MCU specific CAN API + */ + +#pragma once + +#include + +/* + CAN statistics shared by low level and high level code + */ +struct CANStats { + uint32_t num_commands; + uint32_t total_commands; + uint32_t num_receive; + uint32_t num_tx_interrupts; + uint32_t num_rx_interrupts; + uint32_t rx_errors; + uint32_t esr; + uint32_t rxframe_error; + int32_t rx_ecode; + uint32_t should_accept; + uint32_t on_receive; + uint64_t last_raw_command_us; +}; + +extern struct CANStats canstats; + + +/* + disable/enable CAN interripts + */ +void sys_can_disable_IRQ(void); +void sys_can_enable_IRQ(void); + +/* + get a 16 byte unique ID for this node +*/ +void sys_can_getUniqueID(uint8_t id[16]); + +/* + initialise CAN hardware + */ +void sys_can_init(void); + +/* + called from CAN IRQ indicating we may have a free TX slot + */ +extern void DroneCAN_processTxQueue(); + +/* + called from CAN IRQ indicating we have a new frame waiting + */ +extern void DroneCAN_receiveFrame(); + +/* + called from IRQ to handle incoming frame + */ +void DroneCAN_handleFrame(CanardCANFrame *frame); + +/* + try to transmit a frame. + return 1 for success, 0 for no space, -ve for error + */ +int16_t sys_can_transmit(const CanardCANFrame* txf); + +/* + check for an incoming frame + return 1 for success, 0 for no frame, -ve for error + */ +int16_t sys_can_receive(CanardCANFrame *rx_frame); + +/* + get/set RTC backup registers. Used to detect firmware update state + */ +uint32_t get_rtc_backup_register(uint8_t idx); +void set_rtc_backup_register(uint8_t idx, uint32_t value); + +/* + magic values for RTC backup registers + */ +#define RTC_BKUP0_FWUPDATE 0x42c7 // top byte is CAN node number, 2nd byte is file server node +#define RTC_BKUP0_BOOTED 0x8c42c8 // set when main started +#define RTC_BKUP0_SIGNAL 0x8c42c9 // set on 5 DroneCAN messages processed diff --git a/bootloader/DroneCAN/sys_can_at32.c b/bootloader/DroneCAN/sys_can_at32.c new file mode 100644 index 00000000..6efba795 --- /dev/null +++ b/bootloader/DroneCAN/sys_can_at32.c @@ -0,0 +1,260 @@ +/* + sys_can.c - MCU specific CAN code for AT32 bxCAN + */ + +#if DRONECAN_SUPPORT && defined(ARTERY) + +#include "sys_can.h" +#include "functions.h" +#include +#include +#include +#include + + +//#pragma GCC optimize("O0") + +/* + usleep is needed by canard_stm32.c startup code + */ +void usleep(uint32_t usec) +{ + delayMicros(usec); +} + +/* + get a 16 byte unique ID for this node +*/ +void sys_can_getUniqueID(uint8_t id[16]) +{ + const uint8_t *uidbase = (const uint8_t *)0x1FFFF7E8; // 96 bit UID + memcpy(id, uidbase, 12); + memset(&id[12], 0, 4); +} + +/** + * @brief can gpio config + * @param none + * @retval none + */ +static void can_gpio_config(void) +{ + gpio_init_type gpio_init_struct; + + crm_periph_clock_enable(CRM_GPIOA_PERIPH_CLOCK, TRUE); + crm_periph_clock_enable(CRM_IOMUX_PERIPH_CLOCK, TRUE); + gpio_pin_remap_config(CAN1_GMUX_0000,TRUE); // CAN_RX=PA11/CAN_TX=PA12 + // gpio_pin_remap_config(CAN1_GMUX_0010,TRUE); // CAN_RX=PB8/CAN_TX=PB9 + + gpio_default_para_init(&gpio_init_struct); + /* can tx pin */ + gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER; + gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL; + gpio_init_struct.gpio_mode = GPIO_MODE_MUX; + gpio_init_struct.gpio_pins = GPIO_PINS_12; + gpio_init_struct.gpio_pull = GPIO_PULL_NONE; + gpio_init(GPIOA, &gpio_init_struct); + /* can rx pin */ + gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER; + gpio_init_struct.gpio_mode = GPIO_MODE_INPUT; + gpio_init_struct.gpio_pins = GPIO_PINS_11; + gpio_init_struct.gpio_pull = GPIO_PULL_UP; + gpio_init(GPIOA, &gpio_init_struct); +} + +/* + initialise CAN hardware + */ +void sys_can_init(void) +{ + nvic_priority_group_config(NVIC_PRIORITY_GROUP_4); + can_gpio_config(); + + can_base_type can_base_struct; + can_baudrate_type can_baudrate_struct; + + crm_periph_clock_enable(CRM_CAN1_PERIPH_CLOCK, TRUE); + /* can base init */ + can_default_para_init(&can_base_struct); + can_base_struct.mode_selection = CAN_MODE_COMMUNICATE; + can_base_struct.ttc_enable = FALSE; + can_base_struct.aebo_enable = TRUE; + can_base_struct.aed_enable = TRUE; + can_base_struct.prsf_enable = FALSE; + can_base_struct.mdrsel_selection = CAN_DISCARDING_FIRST_RECEIVED; + can_base_struct.mmssr_selection = CAN_SENDING_BY_REQUEST; + can_base_init(CAN1, &can_base_struct); + + crm_clocks_freq_type clocks; + crm_clocks_freq_get(&clocks); + + /* can baudrate, set baudrate = pclk/(baudrate_div *(1 + bts1_size + bts2_size)) */ + can_baudrate_struct.baudrate_div = 6; + can_baudrate_struct.rsaw_size = CAN_RSAW_3TQ; + can_baudrate_struct.bts1_size = CAN_BTS1_8TQ; + can_baudrate_struct.bts2_size = CAN_BTS2_3TQ; + can_baudrate_set(CAN1, &can_baudrate_struct); + + /* can filter init */ + can_filter_init_type can_filter_init_struct; + can_filter_init_struct.filter_activate_enable = TRUE; + can_filter_init_struct.filter_fifo = CAN_FILTER_FIFO0; + can_filter_init_struct.filter_number = 0; + can_filter_init_struct.filter_bit = CAN_FILTER_32BIT; + can_filter_init_struct.filter_id_high = 0; + can_filter_init_struct.filter_id_low = 0; + can_filter_init_struct.filter_mask_high = 0; + can_filter_init_struct.filter_mask_low = 0; + can_filter_init(CAN1, &can_filter_init_struct); + + can_filter_init_struct.filter_fifo = CAN_FILTER_FIFO1; + can_filter_init_struct.filter_number = 1; + can_filter_init(CAN1, &can_filter_init_struct); + + /* interrupt enable */ + can_interrupt_enable(CAN1, CAN_TCIEN_INT, TRUE); + can_interrupt_enable(CAN1, CAN_RF0MIEN_INT, TRUE); + can_interrupt_enable(CAN1, CAN_RF1MIEN_INT, TRUE); + can_interrupt_enable(CAN1, CAN_ETRIEN_INT, TRUE); + can_interrupt_enable(CAN1, CAN_EOIEN_INT, TRUE); +} + +void sys_can_enable_IRQ(void) +{ + nvic_irq_enable(CAN1_SE_IRQn, 0x00, 0x00); + nvic_irq_enable(CAN1_RX0_IRQn, 0x00, 0x00); + nvic_irq_enable(CAN1_RX1_IRQn, 0x00, 0x00); + nvic_irq_enable(CAN1_TX_IRQn, 0x00, 0x00); +} + +void sys_can_disable_IRQ(void) +{ + nvic_irq_disable(CAN1_SE_IRQn); + nvic_irq_disable(CAN1_RX0_IRQn); + nvic_irq_disable(CAN1_RX1_IRQn); + nvic_irq_disable(CAN1_TX_IRQn); +} + +/* + try to transmit a frame. + return 1 for success, 0 for no space, -ve for error + */ +int16_t sys_can_transmit(const CanardCANFrame* txf) +{ + can_tx_message_type tx_message_struct; + if (txf->id & CANARD_CAN_FRAME_EFF) { + tx_message_struct.id_type = CAN_ID_EXTENDED; + tx_message_struct.standard_id = 0; + tx_message_struct.extended_id = txf->id & CANARD_CAN_EXT_ID_MASK; + } else { + tx_message_struct.id_type = CAN_ID_STANDARD; + tx_message_struct.standard_id = txf->id & CANARD_CAN_STD_ID_MASK; + tx_message_struct.extended_id = 0; + } + tx_message_struct.frame_type = CAN_TFT_DATA; + tx_message_struct.dlc = txf->data_len; + memcpy(tx_message_struct.data, txf->data, txf->data_len); + const uint8_t transmit_mailbox = can_message_transmit(CAN1, &tx_message_struct); + if (transmit_mailbox == CAN_TX_STATUS_NO_EMPTY) { + return 0; + } + return 1; +} + +/* + check for an incoming frame + return 1 for success, 0 for no frame, -ve for error + */ +int16_t sys_can_receive(CanardCANFrame *rx_frame) +{ + can_rx_message_type frm; + bool have_frame = false; + if (CAN1->rf0_bit.rf0mn) { + can_message_receive(CAN1, CAN_RX_FIFO0, &frm); + have_frame = true; + } else if (CAN1->rf1_bit.rf1mn) { + can_message_receive(CAN1, CAN_RX_FIFO1, &frm); + have_frame = true; + } + if (!have_frame) { + return 0; + } + if (frm.id_type == CAN_ID_EXTENDED) { + rx_frame->id = frm.extended_id | CANARD_CAN_FRAME_EFF; + } else if (frm.id_type == CAN_ID_STANDARD) { + rx_frame->id = frm.standard_id; + } else { + return 0; + } + rx_frame->data_len = frm.dlc; + memcpy(rx_frame->data, frm.data, rx_frame->data_len); + return 1; +} + +/** + * @brief can1 interrupt function + * @param none + * @retval none + */ +void CAN1_RX0_IRQHandler(void) +{ + DroneCAN_receiveFrame(); +} + +void CAN1_RX1_IRQHandler(void) +{ + DroneCAN_receiveFrame(); +} + +void CAN1_TX_IRQHandler(void) +{ + CAN1->tsts = CAN_TSTS_TM0TCF_VAL | CAN_TSTS_TM1TCF_VAL | CAN_TSTS_TM2TCF_VAL; + DroneCAN_processTxQueue(); +} + +/** + * @brief can1 interrupt function se + * @param none + * @retval none + */ +void CAN1_SE_IRQHandler(void) +{ + __IO uint32_t err_index = 0; + if (CAN1->ests_bit.etr) { + err_index = CAN1->ests & 0x70; + CAN1->msts = CAN_MSTS_EOIF_VAL; + CAN1->ests = 0; + /* error type is stuff error */ + if (err_index == 0x00000010) { + /* when stuff error occur: in order to ensure communication normally, + user must restart can or send a frame of highest priority message here + */ + } + } +} + +static void ertc_init(void) +{ + static bool done_init; + if (done_init) { + return; + } + done_init = true; + crm_periph_clock_enable(CRM_PWC_PERIPH_CLOCK, TRUE); + pwc_battery_powered_domain_access(TRUE); +} + +uint32_t get_rtc_backup_register(uint8_t idx) +{ + ertc_init(); + return ertc_bpr_data_read((ertc_dt_type)idx); +} + +void set_rtc_backup_register(uint8_t idx, uint32_t value) +{ + ertc_init(); + ertc_bpr_data_write((ertc_dt_type)idx, value); +} + +#endif // DRONECAN_SUPPORT && defined(ARTERY) + diff --git a/bootloader/DroneCAN/sys_can_stm32.c b/bootloader/DroneCAN/sys_can_stm32.c new file mode 100644 index 00000000..8482c19e --- /dev/null +++ b/bootloader/DroneCAN/sys_can_stm32.c @@ -0,0 +1,459 @@ +/* + sys_can.c - MCU specific CAN code for STM32 bxCAN + + This driver is based on the ArduPilot bxCAN driver + https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_HAL_ChibiOS/CanIface.cpp + */ + +#if DRONECAN_SUPPORT && defined(MCU_L431) + +#include "sys_can.h" +#include +#include +#include + +typedef struct { + volatile uint32_t TIR; + volatile uint32_t TDTR; + volatile uint32_t TDLR; + volatile uint32_t TDHR; +} TxMailboxType; + +typedef struct { + volatile uint32_t RIR; + volatile uint32_t RDTR; + volatile uint32_t RDLR; + volatile uint32_t RDHR; +} RxMailboxType; + +typedef struct { + volatile uint32_t FR1; + volatile uint32_t FR2; +} FilterRegisterType; + +typedef struct { + volatile uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ + volatile uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ + volatile uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ + volatile uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ + volatile uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ + volatile uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ + volatile uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ + volatile uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ + uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ + TxMailboxType TxMailbox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ + RxMailboxType RxMailbox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ + uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ + volatile uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ + volatile uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ + uint32_t RESERVED2; /*!< Reserved, 0x208 */ + volatile uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ + uint32_t RESERVED3; /*!< Reserved, 0x210 */ + volatile uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ + uint32_t RESERVED4; /*!< Reserved, 0x218 */ + volatile uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ + uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ + FilterRegisterType FilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ +} CanType; + +#define BXCAN ((volatile CanType*)0x40006400U) + +/* CAN master control register */ +static uint32_t MCR_INRQ = (1U << 0); /* Bit 0: Initialization Request */ +static uint32_t MCR_SLEEP = (1U << 1); /* Bit 1: Sleep Mode Request */ +static uint32_t MCR_AWUM = (1U << 5); /* Bit 5: Automatic Wakeup Mode */ +static uint32_t MCR_ABOM = (1U << 6); /* Bit 6: Automatic Bus-Off Management */ + +/* CAN master status register */ +static uint32_t MSR_INAK = (1U << 0); /* Bit 0: Initialization Acknowledge */ + +/* CAN transmit status register */ +#define TSR_RQCP0 (1U << 0) /* Bit 0: Request Completed Mailbox 0 */ +#define TSR_TXOK0 (1U << 1) /* Bit 1 : Transmission OK of Mailbox 0 */ +#define TSR_ALST0 (1U << 2) /* Bit 2 : Arbitration Lost for Mailbox 0 */ +#define TSR_TERR0 (1U << 3) /* Bit 3 : Transmission Error of Mailbox 0 */ +#define TSR_ABRQ0 (1U << 7) /* Bit 7 : Abort Request for Mailbox 0 */ +#define TSR_RQCP1 (1U << 8) /* Bit 8 : Request Completed Mailbox 1 */ +#define TSR_TXOK1 (1U << 9) /* Bit 9 : Transmission OK of Mailbox 1 */ +#define TSR_ALST1 (1U << 10)/* Bit 10 : Arbitration Lost for Mailbox 1 */ +#define TSR_TERR1 (1U << 11)/* Bit 11 : Transmission Error of Mailbox 1 */ +#define TSR_ABRQ1 (1U << 15)/* Bit 15 : Abort Request for Mailbox 1 */ +#define TSR_RQCP2 (1U << 16)/* Bit 16 : Request Completed Mailbox 2 */ +#define TSR_TXOK2 (1U << 17)/* Bit 17 : Transmission OK of Mailbox 2 */ +#define TSR_ALST2 (1U << 18)/* Bit 18: Arbitration Lost for Mailbox 2 */ +#define TSR_TERR2 (1U << 19)/* Bit 19: Transmission Error of Mailbox 2 */ +#define TSR_ABRQ2 (1U << 23)/* Bit 23: Abort Request for Mailbox 2 */ +#define TSR_CODE_SHIFT (24U) /* Bits 25-24: Mailbox Code */ +#define TSR_CODE_MASK (3U << 24) +#define TSR_TME0 (1U << 26)/* Bit 26: Transmit Mailbox 0 Empty */ +#define TSR_TME1 (1U << 27)/* Bit 27: Transmit Mailbox 1 Empty */ +#define TSR_TME2 (1U << 28)/* Bit 28: Transmit Mailbox 2 Empty */ +#define TSR_LOW0 (1U << 29)/* Bit 29: Lowest Priority Flag for Mailbox 0 */ +#define TSR_LOW1 (1U << 30)/* Bit 30: Lowest Priority Flag for Mailbox 1 */ +#define TSR_LOW2 (1U << 31)/* Bit 31: Lowest Priority Flag for Mailbox 2 */ + +/* CAN receive FIFO 0/1 registers */ +static uint32_t RFR_FMP_MASK = (3U << 0); +static uint32_t RFR_FULL = (1U << 3); /* Bit 3: FIFO 0 Full */ +static uint32_t RFR_FOVR = (1U << 4); /* Bit 4: FIFO 0 Overrun */ +static uint32_t RFR_RFOM = (1U << 5); /* Bit 5: Release FIFO 0 Output Mailbox */ + +/* CAN interrupt enable register */ + +static uint32_t IER_TMEIE = (1U << 0); /* Bit 0: Transmit Mailbox Empty Interrupt Enable */ +static uint32_t IER_FMPIE0 = (1U << 1); /* Bit 1: FIFO Message Pending Interrupt Enable */ +static uint32_t IER_FMPIE1 = (1U << 4); /* Bit 4: FIFO Message Pending Interrupt Enable */ + +/* CAN error status register */ +#define ESR_LEC_SHIFT 4U /* Bits 6-4: Last Error Code */ +static uint32_t ESR_LEC_MASK = (7U << ESR_LEC_SHIFT); + +/* TX mailbox identifier register */ +static uint32_t TIR_TXRQ = (1U << 0); /* Bit 0: Transmit Mailbox Request */ +static uint32_t TIR_RTR = (1U << 1); /* Bit 1: Remote Transmission Request */ +static uint32_t TIR_IDE = (1U << 2); /* Bit 2: Identifier Extension */ + +/* Rx FIFO mailbox identifier register */ + +static uint32_t RIR_RTR = (1U << 1); /* Bit 1: Remote Transmission Request */ +static uint32_t RIR_IDE = (1U << 2); /* Bit 2: Identifier Extension */ +#define RIR_EXID_SHIFT 3U /* Bit 3-31: Extended Identifier */ +#define RIR_STID_SHIFT 21U /* Bits 21-31: Standard Identifier */ + +/* CAN filter master register */ +static uint32_t FMR_FINIT = (1U << 0); /* Bit 0: Filter Init Mode */ + +#define NumTxMailboxes 3 +#define MaskExtID 0x1FFFFFFFU +#define MaskStdID 0x7FFU +#define NumFilters 14 + +/* + send a CAN frame + */ +static bool can_send(const CanardCANFrame *frame) +{ + /* + * Seeking for an empty slot + */ + uint8_t txmailbox = 0xFF; + if ((BXCAN->TSR & TSR_TME0) == TSR_TME0) { + txmailbox = 0; + } else if ((BXCAN->TSR & TSR_TME1) == TSR_TME1) { + txmailbox = 1; + } else if ((BXCAN->TSR & TSR_TME2) == TSR_TME2) { + txmailbox = 2; + } else { + return false; // No slot free + } + + /* + * Setting up the mailbox + */ + volatile TxMailboxType *mb = &BXCAN->TxMailbox[txmailbox]; + if (frame->id & CANARD_CAN_FRAME_EFF) { + // 29 bit extended addressing + mb->TIR = ((frame->id & MaskExtID) << 3) | TIR_IDE; + } else { + // 11 bit addressing + mb->TIR = ((frame->id & MaskStdID) << 21); + } + + if (frame->id & CANARD_CAN_FRAME_RTR) { + mb->TIR |= TIR_RTR; + } + + mb->TDTR = frame->data_len; + + const uint32_t *d32 = (const uint32_t *)&frame->data[0]; + mb->TDHR = d32[1]; + mb->TDLR = d32[0]; + + mb->TIR |= TIR_TXRQ; // Go. + + return true; +} + +static void handleTxMailboxInterrupt(uint8_t mailbox_index, bool txok) +{ +#if 0 + // in the bootloader we don't do interrupt driven transmit, send + // happens from main loop only + DroneCAN_processTxQueue(); +#endif +} + +static void pollErrorFlagsFromISR() +{ + const uint8_t lec = (uint8_t)((BXCAN->ESR & ESR_LEC_MASK) >> ESR_LEC_SHIFT); + if (lec != 0) { + BXCAN->ESR = 0; + } +} + +static void handleTxInterrupt(void) +{ + // TXOK == false means that there was a hardware failure + if (BXCAN->TSR & TSR_RQCP0) { + const bool txok = BXCAN->TSR & TSR_TXOK0; + BXCAN->TSR = TSR_RQCP0; + handleTxMailboxInterrupt(0, txok); + } + if (BXCAN->TSR & TSR_RQCP1) { + const bool txok = BXCAN->TSR & TSR_TXOK1; + BXCAN->TSR = TSR_RQCP1; + handleTxMailboxInterrupt(1, txok); + } + if (BXCAN->TSR & TSR_RQCP2) { + const bool txok = BXCAN->TSR & TSR_TXOK2; + BXCAN->TSR = TSR_RQCP2; + handleTxMailboxInterrupt(2, txok); + } + + pollErrorFlagsFromISR(); +} + +volatile struct { + uint32_t rx_overflow; +} can_stats; + +static void handleRxInterrupt(uint8_t fifo_index) +{ + volatile uint32_t* const rfr_reg = (fifo_index == 0) ? &BXCAN->RF0R : &BXCAN->RF1R; + if ((*rfr_reg & RFR_FMP_MASK) == 0) { + return; + } + + /* + * Register overflow as a hardware error + */ + if ((*rfr_reg & RFR_FOVR) != 0) { + can_stats.rx_overflow++; + } + + /* + * Read the frame contents + */ + CanardCANFrame frame = {}; + const volatile RxMailboxType *rf = &BXCAN->RxMailbox[fifo_index]; + + if ((rf->RIR & RIR_IDE) == 0) { + frame.id = MaskStdID & (rf->RIR >> 21); + } else { + frame.id = MaskExtID & (rf->RIR >> 3); + frame.id |= CANARD_CAN_FRAME_EFF; + } + + if ((rf->RIR & RIR_RTR) != 0) { + frame.id |= CANARD_CAN_FRAME_RTR; + } + + frame.data_len = rf->RDTR & 15; + + uint32_t *d32 = (uint32_t *)&frame.data[0]; + d32[0] = rf->RDLR; + d32[1] = rf->RDHR; + + *rfr_reg = RFR_RFOM | RFR_FOVR | RFR_FULL; // Release FIFO entry we just read + + DroneCAN_handleFrame(&frame); + + pollErrorFlagsFromISR(); +} + +/* + get a 16 byte unique ID for this node +*/ +void sys_can_getUniqueID(uint8_t id[16]) +{ + const uint8_t *uidbase = (const uint8_t *)UID_BASE; + memcpy(id, uidbase, 12); + + // put CPU ID in last 4 bytes, handy for knowing the exact MCU we are on + const uint32_t cpuid = SCB->CPUID; + memcpy(&id[12], &cpuid, 4); +} + +/* + interrupt handlers for CAN1 +*/ +void CAN1_RX0_IRQHandler(void) +{ + handleRxInterrupt(0); +} + +void CAN1_RX1_IRQHandler(void) +{ + handleRxInterrupt(1); +} + +void CAN1_TX_IRQHandler(void) +{ + handleTxInterrupt(); +} + +/* + try to transmit a frame. + return 1 for success, 0 for no space, -ve for failure + */ +int16_t sys_can_transmit(const CanardCANFrame* txf) +{ + return can_send(txf) ? 1 : 0; +} + +/* + check for an incoming frame + return 1 on new frame, 0 for no frame, -ve for erro + */ +int16_t sys_can_receive(CanardCANFrame *rx_frame) +{ + // not used on STM32 + return -1; +} + +/* + disable CAN IRQs + */ +void sys_can_disable_IRQ(void) +{ + NVIC_DisableIRQ(CAN1_TX_IRQn); + NVIC_DisableIRQ(CAN1_RX1_IRQn); + NVIC_DisableIRQ(CAN1_RX0_IRQn); +} + +/* + enable CAN IRQs + */ +void sys_can_enable_IRQ(void) +{ + NVIC_EnableIRQ(CAN1_RX0_IRQn); + NVIC_EnableIRQ(CAN1_RX1_IRQn); + NVIC_EnableIRQ(CAN1_TX_IRQn); +} + +/* + init code should be small, not fast + */ +#pragma GCC optimize("Os") + +static void waitMsrINakBitStateChange(bool target_state) +{ + while (true) { + const bool state = (BXCAN->MSR & MSR_INAK) != 0; + if (state == target_state) { + return; + } + } +} + +static void can_init(void) +{ +#if defined(RCC_APB1ENR1_CAN1EN) + RCC->APB1ENR1 |= RCC_APB1ENR1_CAN1EN; + RCC->APB1RSTR1 |= RCC_APB1RSTR1_CAN1RST; + RCC->APB1RSTR1 &= ~RCC_APB1RSTR1_CAN1RST; +#else + RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; + RCC->APB1RSTR |= RCC_APB1RSTR_CAN1RST; + RCC->APB1RSTR &= ~RCC_APB1RSTR_CAN1RST; +#endif + + /* + * We need to silence the controller in the first order, otherwise it may interfere with the following operations. + */ + BXCAN->MCR &= ~MCR_SLEEP; // Exit sleep mode + BXCAN->MCR |= MCR_INRQ; // Request init + + BXCAN->IER = 0; // Disable interrupts while initialization is in progress + + waitMsrINakBitStateChange(true); + + /* + * Hardware initialization (the hardware has already confirmed initialization mode, see above) + */ + BXCAN->MCR = MCR_ABOM | MCR_AWUM | MCR_INRQ; // RM page 648 + + // timings assuming 80MHz clock + const uint8_t sjw = 0; + const uint8_t bs1 = 7; + const uint8_t bs2 = 0; + const uint8_t prescaler = 7; + + BXCAN->BTR = + ((sjw & 3U) << 24) | + ((bs1 & 15U) << 16) | + ((bs2 & 7U) << 20) | + (prescaler & 1023U); + + BXCAN->IER = IER_TMEIE | // TX mailbox empty + IER_FMPIE0 | // RX FIFO 0 is not empty + IER_FMPIE1; // RX FIFO 1 is not empty + + BXCAN->MCR &= ~MCR_INRQ; // Leave init mode + + waitMsrINakBitStateChange(false); + + /* + * Default filter configuration + */ + BXCAN->FMR |= FMR_FINIT; + + BXCAN->FMR &= 0xFFFFC0F1; + BXCAN->FMR |= NumFilters << 8; // Slave (CAN2) gets half of the filters + + BXCAN->FFA1R = 0; // All assigned to FIFO0 by default + BXCAN->FM1R = 0; // Indentifier Mask mode + + BXCAN->FS1R = 0x1fff; + BXCAN->FilterRegister[0].FR1 = 0; + BXCAN->FilterRegister[0].FR2 = 0; + BXCAN->FA1R = 1; + + BXCAN->FMR &= ~FMR_FINIT; +} + +/* + initialise CAN hardware + */ +void sys_can_init(void) +{ + /* + setup CAN RX and TX pins + */ + LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_CAN1); + LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOA); + + // assume PA11/PA12 for now + LL_GPIO_InitTypeDef GPIO_InitStruct = {0}; + GPIO_InitStruct.Pin = LL_GPIO_PIN_11 | LL_GPIO_PIN_12; + GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE; + GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL; + GPIO_InitStruct.Pull = LL_GPIO_PULL_NO; + GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_MEDIUM; + GPIO_InitStruct.Alternate = 9; // AF9==CAN + LL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + can_init(); + + /* + enable interrupt for CAN receive and transmit + */ + NVIC_SetPriority(CAN1_RX0_IRQn, 5); + NVIC_SetPriority(CAN1_RX1_IRQn, 5); + NVIC_SetPriority(CAN1_TX_IRQn, 5); +} + +uint32_t get_rtc_backup_register(uint8_t idx) +{ + const volatile uint32_t *bkp = &RTC->BKP0R; + return bkp[idx]; +} + +void set_rtc_backup_register(uint8_t idx, uint32_t value) +{ + volatile uint32_t *bkp = &RTC->BKP0R; + bkp[idx] = value; +} + +#endif // DRONECAN_SUPPORT && defined(MCU_L431) + diff --git a/bootloader/ldscript_bl.ld b/bootloader/ldscript_bl.ld index 50e12581..8637f7f0 100644 --- a/bootloader/ldscript_bl.ld +++ b/bootloader/ldscript_bl.ld @@ -12,7 +12,8 @@ _Min_Stack_Size = 0x400; /* required amount of stack */ /* Specify the memory areas */ MEMORY { -FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 4K +FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 4K-32 +DEVINFO (r) : ORIGIN = ORIGIN(FLASH)+LENGTH(FLASH), LENGTH = 32 RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 4K } @@ -27,7 +28,14 @@ SECTIONS . = ALIGN(4); } >FLASH - /* The program code and other data goes into FLASH */ + .devinfo : + { + . = ALIGN(4); + KEEP (*(.devinfo)) + . = ALIGN(4); + } >DEVINFO + +/* The program code and other data goes into FLASH */ .text : { . = ALIGN(4); diff --git a/bootloader/ldscript_bl_CAN.ld b/bootloader/ldscript_bl_CAN.ld new file mode 100644 index 00000000..439387a4 --- /dev/null +++ b/bootloader/ldscript_bl_CAN.ld @@ -0,0 +1,135 @@ +/* + linker file for AM32 bootloader +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +_estack = 0x20004000; /* end of RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x2000; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 16K +} + +/* 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/bootloader/main.c b/bootloader/main.c index 3a00ec56..da8ca9fa 100644 --- a/bootloader/main.c +++ b/bootloader/main.c @@ -27,6 +27,9 @@ // the string HELLO_WORLD is output every 10ms //#define BOOTLOADER_TEST_STRING +// use this to check the backup domain registers work +//#define BOOTLOADER_TEST_BKUP + // when there is no app fw yet, disable jump() //#define DISABLE_JUMP @@ -59,8 +62,16 @@ #endif #ifndef FIRMWARE_RELATIVE_START +#if DRONECAN_SUPPORT +#define FIRMWARE_RELATIVE_START 0x4000 +#else #define FIRMWARE_RELATIVE_START 0x1000 #endif +#endif + +#ifndef EEPROM_MAX_SIZE +#define EEPROM_MAX_SIZE 1024 // must be multiple of 256 +#endif #ifdef USE_PA2 #define input_pin GPIO_PIN(2) @@ -95,36 +106,82 @@ static uint16_t invalid_command; #include +#if DRONECAN_SUPPORT +#include "DroneCAN/DroneCAN.h" +#include "DroneCAN/sys_can.h" +#endif + #ifndef BOARD_FLASH_SIZE #error "must define BOARD_FLASH_SIZE" #endif +#define PIN_CODE (PORT_LETTER << 4 | PIN_NUMBER) + /* currently only support 32, 64 or 128 k flash */ #if BOARD_FLASH_SIZE == 32 #define EEPROM_START_ADD (MCU_FLASH_START+0x7c00) -static uint8_t deviceInfo[9] = {0x34,0x37,0x31,0x00,0x1f,0x06,0x06,0x01,0x30}; +#define FLASH_SIZE_CODE 0x1f #define ADDRESS_SHIFT 0 #elif BOARD_FLASH_SIZE == 64 #define EEPROM_START_ADD (MCU_FLASH_START+0xf800) -static uint8_t deviceInfo[9] = {0x34,0x37,0x31,0x64,0x35,0x06,0x06,0x01,0x30}; +#define FLASH_SIZE_CODE 0x35 #define ADDRESS_SHIFT 0 #elif BOARD_FLASH_SIZE == 128 -static uint8_t deviceInfo[9] = {0x34,0x37,0x31,0x64,0x2B,0x06,0x06,0x01,0x30}; #define EEPROM_START_ADD (MCU_FLASH_START+0x1f800) +#define FLASH_SIZE_CODE 0x2B #define ADDRESS_SHIFT 2 // addresses from the bl client are shifted 2 bits before being used - #else #error "unsupported BOARD_FLASH_SIZE" #endif +/* + a bootloader protocol version, sent as byte 8 in the deviceInfo + this should change when the configurator applications need to know + about a changed feature set in the bootloader + */ +#define BOOTLOADER_PROTOCOL_VERSION 2 + +/* + the devinfo structure tells the configuration client our pin code, + flash size and device type. It can also be used by the main firmware + to confirm we have the right eeprom address and pin code. We have 2 + 32bit magic values so the main firmware can confirm the bootloader + supports this feature + */ +#define DEVINFO_MAGIC1 0x5925e3da +#define DEVINFO_MAGIC2 0x4eb863d9 + +static const struct { + uint32_t magic1; + uint32_t magic2; + const uint8_t deviceInfo[9]; +} devinfo __attribute__((section(".devinfo"))) = { + .magic1 = DEVINFO_MAGIC1, + .magic2 = DEVINFO_MAGIC2, + .deviceInfo = {'4','7','1',PIN_CODE,FLASH_SIZE_CODE,0x06,0x06,BOOTLOADER_PROTOCOL_VERSION,0x30} +}; + typedef void (*pFunction)(void); #define APPLICATION_ADDRESS (uint32_t)(MCU_FLASH_START + FIRMWARE_RELATIVE_START) +/* + a magic value for CMD_SET_ADDRESS which sets the address to + EEPROM_START_ADD. Supported for BOOTLOADER_PROTOCOL_VERSION 2 and + later + */ +#define ADDRESS_MAGIC_EEPROM 0x20 + +// magic address for FILE_NAME +#define ADDRESS_MAGIC_FILE_NAME 0x21 + +// magic address for continue transfer from last read +#define ADDRESS_MAGIC_CONTINUE 0x22 + #define CMD_RUN 0x00 #define CMD_PROG_FLASH 0x01 @@ -140,50 +197,55 @@ typedef void (*pFunction)(void); #define CMD_SET_ADDRESS 0xFF #define CMD_SET_BUFFER 0xFE -static uint16_t low_pin_count; static char receiveByte; -static int count; -static char messagereceived; -static uint16_t address_expected_increment; +static bool messagereceived; static int cmd; -static char eeprom_req; static int received; - -static uint8_t pin_code = PORT_LETTER << 4 | PIN_NUMBER; - - - static uint8_t rxBuffer[258]; static uint8_t payLoadBuffer[256]; -static char rxbyte; +static uint8_t rxbyte; static uint32_t address; +static uint32_t continue_address; -typedef union __attribute__ ((packed)) { - uint8_t bytes[2]; - uint16_t word; +typedef union __attribute__ ((packed)) +{ + uint8_t bytes[2]; + uint16_t word; } uint8_16_u; static uint16_t len; -static uint8_t calculated_crc_low_byte; -static uint8_t calculated_crc_high_byte; static uint16_t payload_buffer_size; static char incoming_payload_no_command; /* USER CODE BEGIN PFP */ -static void sendString(uint8_t data[], int len); +static void sendString(const uint8_t data[], int len); static void receiveBuffer(); static void serialwriteChar(uint8_t data); +static void serialwriteOneChar(uint8_t data); #define BAUDRATE 19200 #define BITTIME 52 // 1000000/BAUDRATE #define HALFBITTIME 26 // 500000/BAUDRATE -static void delayMicroseconds(uint32_t micros) +// used for timing bytes +static uint16_t us_start; + +static void bl_timer_reset(void) { - bl_timer_reset(); - while (bl_timer_us() < micros) { - } + us_start = bl_timer_us(); +} + +static uint16_t bl_timer_elapsed(void) +{ + return bl_timer_us() - us_start; +} + +static void delayMicroseconds(uint16_t micros) +{ + bl_timer_reset(); + while (bl_timer_elapsed() < micros) { + } } /* @@ -193,336 +255,365 @@ static void jump() { #ifndef DISABLE_JUMP #if CHECK_EEPROM_BEFORE_JUMP - uint8_t value = *(uint8_t*)(EEPROM_START_ADD); - if (value != 0x01) { // check first byte of eeprom to see if its programmed, if not do not jump - invalid_command = 0; - return; - } + uint8_t value = *(uint8_t*)(EEPROM_START_ADD); + if (value != 0x01) { // check first byte of eeprom to see if its programmed, if not do not jump + invalid_command = 0; + return; + } #endif #ifndef DISABLE_APP_HEADER_CHECKS - /* - first word of the app is the stack pointer - make sure that it is in range - */ - const uint32_t *app = (uint32_t*)(MCU_FLASH_START + FIRMWARE_RELATIVE_START); - const uint32_t ram_start = 0x20000000; - const uint32_t ram_limit_kb = 64; - const uint32_t ram_end = ram_start+ram_limit_kb*1024; - if (app[0] < ram_start || app[0] > ram_end) { - invalid_command = 0; - return; - } - /* - 2nd word is the entry point of the main app. Ensure that is in range - */ - const uint32_t flash_limit_kb = 256; - if (app[1] < APPLICATION_ADDRESS || app[1] > APPLICATION_ADDRESS+flash_limit_kb*1024) { - // outside a 256k range, really unlikely to be a valid - // application, don't jump - invalid_command = 0; - return; - } + /* + first word of the app is the stack pointer - make sure that it is in range + */ + const uint32_t *app = (uint32_t*)(MCU_FLASH_START + FIRMWARE_RELATIVE_START); + const uint32_t ram_start = 0x20000000; + const uint32_t ram_limit_kb = 64; + const uint32_t ram_end = ram_start+ram_limit_kb*1024; + if (app[0] < ram_start || app[0] > ram_end) { + invalid_command = 0; + return; + } + /* + 2nd word is the entry point of the main app. Ensure that is in range + */ + const uint32_t flash_limit_kb = 256; + if (app[1] < APPLICATION_ADDRESS || app[1] > APPLICATION_ADDRESS+flash_limit_kb*1024) { + // outside a 256k range, really unlikely to be a valid + // application, don't jump + invalid_command = 0; + return; + } #endif // DISABLE_APP_HEADER_CHECKS - jump_to_application(); -#endif -} +#if DRONECAN_SUPPORT + if (!DroneCAN_boot_ok()) { + invalid_command = 0; + return; + } + sys_can_disable_IRQ(); +#endif -static void makeCrc(uint8_t* pBuff, uint16_t length) -{ - static uint8_16_u CRC_16; - CRC_16.word=0; - - for(int i = 0; i < length; i++) { - - - uint8_t xb = pBuff[i]; - for (uint8_t j = 0; j < 8; j++) - { - if (((xb & 0x01) ^ (CRC_16.word & 0x0001)) !=0 ) { - CRC_16.word = CRC_16.word >> 1; - CRC_16.word = CRC_16.word ^ 0xA001; - } else { - CRC_16.word = CRC_16.word >> 1; - } - xb = xb >> 1; - } - } - calculated_crc_low_byte = CRC_16.bytes[0]; - calculated_crc_high_byte = CRC_16.bytes[1]; + jump_to_application(); +#endif } -static char checkCrc(uint8_t* pBuff, uint16_t length) +/* + 16 bit CRC + */ +uint16_t crc16(const uint8_t* pBuff, uint16_t length) { + uint16_t ret = 0; + + for (int i = 0; i < length; i++) { + uint8_t xb = pBuff[i]; + for (uint8_t j = 0; j < 8; j++) { + if (((xb & 0x01) ^ (ret & 0x0001)) != 0) { + ret >>= 1; + ret ^= 0xA001; + } else { + ret >>= 1; + } + xb = xb >> 1; + } + } + return ret; +} - char received_crc_low_byte2 = pBuff[length]; // one higher than len in buffer - char received_crc_high_byte2 = pBuff[length+1]; - makeCrc(pBuff,length); +static bool checkCrc(uint8_t* pBuff, uint16_t length) +{ + const uint16_t crcin = pBuff[length] | (pBuff[length+1]<<8); + const uint16_t crc2 = crc16(pBuff, length); - if((calculated_crc_low_byte==received_crc_low_byte2) && (calculated_crc_high_byte==received_crc_high_byte2)){ - return 1; - }else{ - return 0; - } + return crcin == crc2; } static void setReceive() { - gpio_mode_set_input(input_pin, GPIO_PULL_UP); - received = 0; + gpio_mode_set_input(input_pin, GPIO_PULL_UP); + received = 0; } static void setTransmit() { - // set high before we set as output to guarantee idle high - gpio_set(input_pin); - gpio_mode_set_output(input_pin, GPIO_OUTPUT_PUSH_PULL); + // set high before we set as output to guarantee idle high + gpio_set(input_pin); + gpio_mode_set_output(input_pin, GPIO_OUTPUT_PUSH_PULL); - // delay a bit to let the sender get setup for receiving - delayMicroseconds(BITTIME); + // delay a bit to let the sender get setup for receiving + delayMicroseconds(BITTIME); } +static void serialwriteOneChar(uint8_t c) +{ + setTransmit(); + serialwriteChar(c); + setReceive(); +} static void send_ACK() { - setTransmit(); - serialwriteChar(0x30); // good ack! - setReceive(); + serialwriteOneChar(0x30); // good ack! + invalid_command = 0; } static void send_BAD_ACK() { - setTransmit(); - serialwriteChar(0xC1); // bad command message. - setReceive(); + serialwriteOneChar(0xC1); // bad command message. + invalid_command++; } static void send_BAD_CRC_ACK() { - setTransmit(); - serialwriteChar(0xC2); // bad command message. - setReceive(); + serialwriteOneChar(0xC2); // bad command message. + invalid_command++; } static void sendDeviceInfo() { - setTransmit(); - sendString(deviceInfo,9); - setReceive(); + sendString(devinfo.deviceInfo,sizeof(devinfo.deviceInfo)); } static bool checkAddressWritable(uint32_t address) { - return address >= APPLICATION_ADDRESS; + return address >= APPLICATION_ADDRESS; } static void decodeInput() { - if (incoming_payload_no_command) { - len = payload_buffer_size; - if (checkCrc(rxBuffer,len)) { - memset(payLoadBuffer, 0, sizeof(payLoadBuffer)); // reset buffer + if (incoming_payload_no_command) { + len = payload_buffer_size; + if (checkCrc(rxBuffer,len)) { + memset(payLoadBuffer, 0, sizeof(payLoadBuffer)); // reset buffer - for(int i = 0; i < len; i++){ - payLoadBuffer[i]= rxBuffer[i]; - } - send_ACK(); - incoming_payload_no_command = 0; - return; - }else{ - send_BAD_CRC_ACK(); - return; - } + for (int i = 0; i < len; i++) { + payLoadBuffer[i]= rxBuffer[i]; + } + send_ACK(); + incoming_payload_no_command = 0; + return; + } else { + send_BAD_CRC_ACK(); + return; } + } - cmd = rxBuffer[0]; + cmd = rxBuffer[0]; - if (rxBuffer[16] == 0x7d) { - if(rxBuffer[8] == 13 && rxBuffer[9] == 66) { - sendDeviceInfo(); - rxBuffer[20]= 0; + if (rxBuffer[16] == 0x7d) { + if (rxBuffer[8] == 13 && rxBuffer[9] == 66) { + sendDeviceInfo(); + rxBuffer[20]= 0; - } - return; } + return; + } - if (rxBuffer[20] == 0x7d) { - if(rxBuffer[12] == 13 && rxBuffer[13] == 66) { - sendDeviceInfo(); - rxBuffer[20]= 0; - return; - } - - } - if (rxBuffer[40] == 0x7d) { - if (rxBuffer[32] == 13 && rxBuffer[33] == 66) { - sendDeviceInfo(); - rxBuffer[20]= 0; - return; - } + if (rxBuffer[20] == 0x7d) { + if (rxBuffer[12] == 13 && rxBuffer[13] == 66) { + sendDeviceInfo(); + rxBuffer[20]= 0; + return; } - if (cmd == CMD_RUN) { - // starts the main app - if((rxBuffer[1] == 0) && (rxBuffer[2] == 0) && (rxBuffer[3] == 0)) { - invalid_command = 101; - } + } + if (rxBuffer[40] == 0x7d) { + if (rxBuffer[32] == 13 && rxBuffer[33] == 66) { + sendDeviceInfo(); + rxBuffer[20]= 0; + return; } + } - if (cmd == CMD_PROG_FLASH) { - len = 2; - if (!checkCrc((uint8_t*)rxBuffer, len)) { - send_BAD_CRC_ACK(); + if (cmd == CMD_RUN) { + // starts the main app + if ((rxBuffer[1] == 0) && (rxBuffer[2] == 0) && (rxBuffer[3] == 0)) { + invalid_command = 101; + } + } - return; - } + if (cmd == CMD_PROG_FLASH) { + len = 2; + if (!checkCrc((uint8_t*)rxBuffer, len)) { + send_BAD_CRC_ACK(); - if (!checkAddressWritable(address)) { - send_BAD_ACK(); + return; + } - return; - } + if (!checkAddressWritable(address)) { + send_BAD_ACK(); - if (!save_flash_nolib((uint8_t*)payLoadBuffer, payload_buffer_size,address)) { - send_BAD_ACK(); - } else { - send_ACK(); - } + return; + } - return; + if (address == EEPROM_START_ADD && payload_buffer_size > 2) { + /* + if the configuration client is writing the eeprom area + then replace the bootloader version byte in the buffer + with the right version. This makes the update_EEPROM() + less likely to need to erase any flash + */ + payLoadBuffer[2] = BOOTLOADER_VERSION; } - if (cmd == CMD_SET_ADDRESS) { - // command set addressinput format is: CMD, 00 , High byte - // address, Low byte address, crclb ,crchb - len = 4; // package without 2 byte crc - if (!checkCrc((uint8_t*)rxBuffer, len)) { - send_BAD_CRC_ACK(); + if (!save_flash_nolib((uint8_t*)payLoadBuffer, payload_buffer_size,address)) { + send_BAD_ACK(); + } else { + send_ACK(); + } - return; - } + return; + } + if (cmd == CMD_SET_ADDRESS) { + // command set addressinput format is: CMD, 00 , High byte + // address, Low byte address, crclb ,crchb + len = 4; // package without 2 byte crc + if (!checkCrc((uint8_t*)rxBuffer, len)) { + send_BAD_CRC_ACK(); + return; + } - // will send Ack 0x30 and read input after transfer out callback - invalid_command = 0; - address = MCU_FLASH_START + ((rxBuffer[2] << 8 | rxBuffer[3]) << ADDRESS_SHIFT); - send_ACK(); + invalid_command = 0; - return; - } + address = rxBuffer[2] << 8 | rxBuffer[3]; - if (cmd == CMD_SET_BUFFER) { - // for writing buffer rx buffer 0 = command byte. command set - // address, input , format is CMD, 00 , 00 or 01 (if buffer is 256), - // buffer_size, - len = 4; // package without 2 byte crc - if (!checkCrc((uint8_t*)rxBuffer, len)) { - send_BAD_CRC_ACK(); + /* + check for magic addresses that map to specific areas + */ + if (address == ADDRESS_MAGIC_EEPROM) { + // config app has requested access to the eeprom region + address = EEPROM_START_ADD; + } else if (address == ADDRESS_MAGIC_FILE_NAME) { + // config app has requested access to the FILE_NAME. Assume eeprom-32 for now, + // this may change for some MCUs in the future + address = EEPROM_START_ADD - 32; + } else if (address == ADDRESS_MAGIC_CONTINUE) { + // allow easy continue from last address, for breaking up eeprom into multiple small reads + address = continue_address; + } else if (address < 1024) { + // other addresses below 1024 are reserved for future magic values + send_BAD_ACK(); + return; + } else { + // cope with ADDRESS_SHIFT for 128k flash boards, and add + // in MCU base flash address + address = MCU_FLASH_START + (address << ADDRESS_SHIFT); + } + + send_ACK(); + return; + } + + if (cmd == CMD_SET_BUFFER) { + // for writing buffer rx buffer 0 = command byte. command set + // address, input , format is CMD, 00 , 00 or 01 (if buffer is 256), + // buffer_size, + len = 4; // package without 2 byte crc + if (!checkCrc((uint8_t*)rxBuffer, len)) { + send_BAD_CRC_ACK(); + + return; + } + + // no ack with command set buffer; + if (rxBuffer[2] == 0x01) { + payload_buffer_size = 256; // if nothing in this buffer + } else { + payload_buffer_size = rxBuffer[3]; + } + incoming_payload_no_command = 1; + setReceive(); - return; - } + return; + } - // no ack with command set buffer; - if(rxBuffer[2] == 0x01){ - payload_buffer_size = 256; // if nothing in this buffer - }else{ - payload_buffer_size = rxBuffer[3]; - } - incoming_payload_no_command = 1; - address_expected_increment = 256; - setReceive(); + if (cmd == CMD_KEEP_ALIVE) { + len = 2; + if (!checkCrc((uint8_t*)rxBuffer, len)) { + send_BAD_CRC_ACK(); - return; + return; } - if (cmd == CMD_KEEP_ALIVE) { - len = 2; - if (!checkCrc((uint8_t*)rxBuffer, len)) { - send_BAD_CRC_ACK(); + serialwriteOneChar(0xC1); // bad command message. - return; - } + return; + } - setTransmit(); - serialwriteChar(0xC1); // bad command message. - setReceive(); + if (cmd == CMD_ERASE_FLASH) { + len = 2; + if (!checkCrc((uint8_t*)rxBuffer, len)) { + send_BAD_CRC_ACK(); - return; + return; } - if (cmd == CMD_ERASE_FLASH) { - len = 2; - if (!checkCrc((uint8_t*)rxBuffer, len)) { - send_BAD_CRC_ACK(); + if (!checkAddressWritable(address)) { + send_BAD_ACK(); - return; - } + return; + } - if (!checkAddressWritable(address)) { - send_BAD_ACK(); + send_ACK(); + return; + } - return; - } + if (cmd == CMD_READ_FLASH_SIL) { + // for sending contents of flash memory at the memory location set in + // bootloader.c need to still set memory with data from set mem + // command + len = 2; + if (!checkCrc((uint8_t*)rxBuffer, len)) { + send_BAD_CRC_ACK(); - send_ACK(); - return; + return; } - if (cmd == CMD_READ_EEPROM) { - eeprom_req = 1; + if (address == 0) { + // must send SET_ADDRESS first + send_BAD_ACK(); + return; } - if (cmd == CMD_READ_FLASH_SIL) { - // for sending contents of flash memory at the memory location set in - // bootloader.c need to still set memory with data from set mem - // command - len = 2; - if (!checkCrc((uint8_t*)rxBuffer, len)) { - send_BAD_CRC_ACK(); - - return; - } - - count++; - uint16_t out_buffer_size = rxBuffer[1];// - if(out_buffer_size == 0){ - out_buffer_size = 256; - } - address_expected_increment = 128; + uint16_t out_buffer_size = rxBuffer[1];// + if (out_buffer_size == 0) { + out_buffer_size = 256; + } - setTransmit(); - uint8_t read_data[out_buffer_size + 3]; // make buffer 3 larger to fit CRC and ACK - memset(read_data, 0, sizeof(read_data)); - // read_flash((uint8_t*)read_data , address); // make sure read_flash reads two less than buffer. - read_flash_bin((uint8_t*)read_data , address, out_buffer_size); + uint8_t read_data[out_buffer_size + 3]; // make buffer 3 larger to fit CRC and ACK + memset(read_data, 0, sizeof(read_data)); + // read_flash((uint8_t*)read_data , address); // make sure read_flash reads two less than buffer. + read_flash_bin((uint8_t*)read_data, address, out_buffer_size); - makeCrc(read_data,out_buffer_size); - read_data[out_buffer_size] = calculated_crc_low_byte; - read_data[out_buffer_size + 1] = calculated_crc_high_byte; - read_data[out_buffer_size + 2] = 0x30; - sendString(read_data, out_buffer_size+3); + const uint16_t crc = crc16(read_data,out_buffer_size); + read_data[out_buffer_size] = crc&0xFF; + read_data[out_buffer_size + 1] = crc>>8; + read_data[out_buffer_size + 2] = 0x30; + sendString(read_data, out_buffer_size+3); - setReceive(); + // allow the client to continue to the next address with ADDRESS_MAGIC_CONTINUE + continue_address = address + out_buffer_size; - return; - } + // ensure client sends a SET_ADDRESS each time + address = 0; - setTransmit(); + return; + } - serialwriteChar(0xC1); // bad command message. - invalid_command++; - setReceive(); + serialwriteOneChar(0xC1); // bad command message. + invalid_command++; } #ifdef SERIAL_STATS // stats for debugging serial protocol struct { - uint32_t no_idle; - uint32_t no_start; - uint32_t bad_start; - uint32_t bad_stop; - uint32_t good; + uint32_t no_idle; + uint32_t no_start; + uint32_t bad_start; + uint32_t bad_stop; + uint32_t good; } stats; #endif @@ -533,234 +624,267 @@ struct { */ static bool serialreadChar() { - rxbyte=0; - bl_timer_reset(); - - // UART is idle high, wait for it to be in the idle state - while (!gpio_read(input_pin)) { // wait for rx to go high - if (bl_timer_us() > 20000) { - /* - if we don't get a command for 20ms then assume we should - be trying to boot the main firmware, invalid_command 101 - triggers the jump immediately - */ - invalid_command = 101; + rxbyte=0; + bl_timer_reset(); + + // UART is idle high, wait for it to be in the idle state + while (!gpio_read(input_pin)) { // wait for rx to go high + if (bl_timer_elapsed() > 20000U) { + /* + if we don't get a command for 20ms then assume we should + be trying to boot the main firmware, invalid_command 101 + triggers the jump immediately + */ + invalid_command = 101; #ifdef SERIAL_STATS - stats.no_idle++; + stats.no_idle++; #endif - return false; - } + return false; } + } - // now we need to wait for the start bit leading edge, which is low - bl_timer_reset(); - while (gpio_read(input_pin)) { - if (bl_timer_us() > 5*BITTIME && messagereceived) { - // we've been waiting too long, don't allow for long gaps - // between bytes + // now we need to wait for the start bit leading edge, which is low + bl_timer_reset(); + while (gpio_read(input_pin)) { + if (bl_timer_elapsed() > 5*BITTIME) { +#if DRONECAN_SUPPORT + if (DroneCAN_update()) { + jump(); + } +#endif + if (messagereceived) { + // we've been waiting too long, don't allow for long gaps + // between bytes #ifdef SERIAL_STATS - stats.no_start++; + stats.no_start++; #endif - return false; - } + return false; + } } + } - // wait to get the center of bit time. We want to sample at the - // middle of each bit - delayMicroseconds(HALFBITTIME); - if (gpio_read(input_pin)) { - // bad framing, we should be half-way through the start bit - // which should still be low + // wait to get the center of bit time. We want to sample at the + // middle of each bit + delayMicroseconds(HALFBITTIME); + if (gpio_read(input_pin)) { + // bad framing, we should be half-way through the start bit + // which should still be low #ifdef SERIAL_STATS - stats.bad_start++; + stats.bad_start++; #endif - return false; - } - - /* - now sample the 8 data bits - */ - int bits_to_read = 0; - while (bits_to_read < 8) { - delayMicroseconds(BITTIME); - rxbyte = rxbyte | gpio_read(input_pin) << bits_to_read; - bits_to_read++; - } - - // wait till middle of stop bit, so we can check that too + return false; + } + + /* + now sample the 8 data bits + */ + int bits_to_read = 0; + while (bits_to_read < 8) { delayMicroseconds(BITTIME); - if (!gpio_read(input_pin)) { - // bad framing, stop bit should be high + rxbyte = rxbyte | gpio_read(input_pin) << bits_to_read; + bits_to_read++; + } + + // wait till middle of stop bit, so we can check that too + delayMicroseconds(BITTIME); + if (!gpio_read(input_pin)) { + // bad framing, stop bit should be high #ifdef SERIAL_STATS - stats.bad_stop++; + stats.bad_stop++; #endif - return false; - } + return false; + } - // we got a good byte - messagereceived = 1; - receiveByte = rxbyte; + // we got a good byte + messagereceived = true; + receiveByte = rxbyte; #ifdef SERIAL_STATS - stats.good++; + stats.good++; #endif - return true; + return true; } static void serialwriteChar(uint8_t data) { - // start bit is low - gpio_clear(input_pin); + // start bit is low + gpio_clear(input_pin); + delayMicroseconds(BITTIME); + + // send data bits + uint8_t bits_written = 0; + while (bits_written < 8) { + if (data & 0x01) { + gpio_set(input_pin); + } else { + // GPIO_BC(input_port) = input_pin; + gpio_clear(input_pin); + } + bits_written++; + data = data >> 1; delayMicroseconds(BITTIME); + } - // send data bits - uint8_t bits_written = 0; - while (bits_written < 8) { - if (data & 0x01) { - gpio_set(input_pin); - } else { - // GPIO_BC(input_port) = input_pin; - gpio_clear(input_pin); - } - bits_written++; - data = data >> 1; - delayMicroseconds(BITTIME); - } - - // send stop bit - gpio_set(input_pin); + // send stop bit + gpio_set(input_pin); - /* - note that we skip the delay by BITTIME for the full stop bit and - do it in sendString() instead to ensure when sending an ACK - immediately followed by a setReceive() on a slow MCU that we - start on the receive as soon as possible. - */ + /* + note that we skip the delay by BITTIME for the full stop bit and + do it in sendString() instead to ensure when sending an ACK + immediately followed by a setReceive() on a slow MCU that we + start on the receive as soon as possible. + */ } -static void sendString(uint8_t *data, int len) +static void sendString(const uint8_t *data, int len) { - for(int i = 0; i < len; i++){ - serialwriteChar(data[i]); - // for multi-byte writes we add the stop bit delay - delayMicroseconds(BITTIME); - } + setTransmit(); + for (int i = 0; i < len; i++) { + serialwriteChar(data[i]); + // for multi-byte writes we add the stop bit delay + delayMicroseconds(BITTIME); + } + setReceive(); } static void receiveBuffer() { - count = 0; - messagereceived = 0; - memset(rxBuffer, 0, sizeof(rxBuffer)); + uint16_t count = 0; + messagereceived = false; + memset(rxBuffer, 0, sizeof(rxBuffer)); - setReceive(); + setReceive(); + + for (uint32_t i = 0; i < sizeof(rxBuffer); i++) { + if (!serialreadChar()) { + break; + } + + if (incoming_payload_no_command) { + if (count == payload_buffer_size+2U) { + break; + } + rxBuffer[i] = rxbyte; + count++; + } else { + if (bl_timer_elapsed() > 250) { + + count = 0; + + break; + } else { + rxBuffer[i] = rxbyte; + if (i == 257) { + invalid_command+=20; // needs one hundred to trigger a jump but will be reset on next set address commmand - for(uint32_t i = 0; i < sizeof(rxBuffer); i++){ - if (!serialreadChar()) { - break; - } - - if(incoming_payload_no_command) { - if(count == payload_buffer_size+2){ - break; - } - rxBuffer[i] = rxbyte; - count++; - } else { - if(bl_timer_us() > 250){ - - count = 0; - - break; - } else { - rxBuffer[i] = rxbyte; - if(i == 257){ - invalid_command+=20; // needs one hundred to trigger a jump but will be reset on next set address commmand - - } - } - } - } - if (messagereceived) { - decodeInput(); + } + } } + } + if (messagereceived) { + decodeInput(); + } } #ifdef UPDATE_EEPROM_ENABLE static void update_EEPROM() { - read_flash_bin(rxBuffer , EEPROM_START_ADD , 48); - if (BOOTLOADER_VERSION != rxBuffer[2]) { - if (rxBuffer[2] == 0xFF || rxBuffer[2] == 0x00){ - return; - } - rxBuffer[2] = BOOTLOADER_VERSION; - save_flash_nolib(rxBuffer, 48, EEPROM_START_ADD); - } + if (!bl_was_software_reset()) { + // we only update the bootloader version on a software reset to reduce the chances + // of a brownout or spark causing a eeprom write that corrupts the settings + return; + } + const uint8_t *eeprom = (const uint8_t *)EEPROM_START_ADD; + if (BOOTLOADER_VERSION != eeprom[2]) { + if (eeprom[2] == 0xFF || eeprom[2] == 0x00) { + return; + } + + // update only the bootloader version, preserve all other bytes up to EEPROM_MAX_SIZE + uint8_t data[EEPROM_MAX_SIZE]; + memcpy(data, eeprom, EEPROM_MAX_SIZE); + data[2] = BOOTLOADER_VERSION; + + // flash in 256 byte chunks as save_flash_nolib may not support larger chunks + uint32_t remaining = EEPROM_MAX_SIZE; + uint32_t addr = EEPROM_START_ADD; + const uint8_t *p = &data[0]; + + while (remaining > 0) { + const uint32_t chunk = 256; + save_flash_nolib(p, chunk, addr); + p += chunk; + addr += chunk; + remaining -= chunk; + } + } } #endif // UPDATE_EEPROM_ENABLE +#define low_pin_count_threshold 450 // count signal pin is low before determining jump to main firmware +#define pull_down_pin_count_interations 4000 // greater interations extend grace period for input devices booting with signal pin high static void checkForSignal() { - gpio_mode_set_input(input_pin, GPIO_PULL_DOWN); - - delayMicroseconds(500); + uint16_t low_pin_count = 0; + + gpio_mode_set_input(input_pin, GPIO_PULL_DOWN); - for(int i = 0 ; i < 500; i ++){ - if(!gpio_read(input_pin)){ - low_pin_count++; - }else{ - } + delayMicroseconds(500); - delayMicroseconds(10); + for (int i = 0 ; i < pull_down_pin_count_interations ; i ++) { + if (!gpio_read(input_pin)) { + low_pin_count++; + } + + delayMicroseconds(10); + if (low_pin_count > low_pin_count_threshold) { + i = pull_down_pin_count_interations ; // end for loop if low_pin_count_threshold has already been exceeded } - if (low_pin_count > 450) { + } + if (low_pin_count > low_pin_count_threshold) { // pulled low & majority stayed low - jump to application #if CHECK_SOFTWARE_RESET - if (!bl_was_software_reset()) { - jump(); - } + if (!bl_was_software_reset()) { + jump(); + } #else - jump(); + jump(); #endif - } + } - gpio_mode_set_input(input_pin, GPIO_PULL_UP); - - delayMicroseconds(500); + gpio_mode_set_input(input_pin, GPIO_PULL_UP); - for (int i = 0 ; i < 500; i++) { - if( !(gpio_read(input_pin))){ - low_pin_count++; - }else{ + delayMicroseconds(500); - } - delayMicroseconds(10); - } - if (low_pin_count == 0) { - return; // all high while pin is pulled low, bootloader signal - } + for (int i = 0 ; i < 500; i++) { + if ( !(gpio_read(input_pin))) { + low_pin_count++; + } else { - low_pin_count = 0; + } + delayMicroseconds(10); + } + if (low_pin_count == 0) { + return; // pulled high & never low in history - stay in bootloader only + } - gpio_mode_set_input(input_pin, GPIO_PULL_NONE); + low_pin_count = 0; - delayMicroseconds(500); + gpio_mode_set_input(input_pin, GPIO_PULL_NONE); - for (int i = 0 ; i < 500; i ++) { - if( !(gpio_read(input_pin))){ - low_pin_count++; - } + delayMicroseconds(500); - delayMicroseconds(10); - } - if (low_pin_count == 0) { - return; // when floated all + for (int i = 0 ; i < 500; i ++) { + if ( !(gpio_read(input_pin))) { + low_pin_count++; } - if (low_pin_count > 0) { - jump(); - } + delayMicroseconds(10); + } + + if (low_pin_count > 0) { + jump(); // floating & low at least once - jump to application + } } #ifdef BOOTLOADER_TEST_CLOCK @@ -769,15 +893,15 @@ static void checkForSignal() */ static void test_clock(void) { - setTransmit(); - while (1) { - gpio_clear(input_pin); - bl_timer_reset(); - while (bl_timer_us() < 2000) ; - gpio_set(input_pin); - bl_timer_reset(); - while (bl_timer_us() < 1000) ; - } + setTransmit(); + while (1) { + gpio_clear(input_pin); + bl_timer_reset(); + while (bl_timer_elapsed() < 2000) ; + gpio_set(input_pin); + bl_timer_reset(); + while (bl_timer_elapsed() < 1000) ; + } } #endif // BOOTLOADER_TEST_CLOCK @@ -787,45 +911,75 @@ static void test_clock(void) */ static void test_string(void) { - setTransmit(); - while (1) { - delayMicroseconds(10000); - sendString((uint8_t*)"HELLO_WORLD",11); - } + while (1) { + delayMicroseconds(10000); + sendString((uint8_t*)"HELLO_WORLD",11); + } } #endif // BOOTLOADER_TEST_STRING + +#ifdef BOOTLOADER_TEST_BKUP +/* + test operation of backup domain registers + */ +volatile struct { + uint32_t value; + uint32_t fail; +} bkup; + +static void test_rtc_backup(void) +{ + const uint8_t idx = 1; + while (true) { + bkup.value++; + set_rtc_backup_register(idx, bkup.value); + const uint32_t bkup_value2 = get_rtc_backup_register(idx); + if (bkup_value2 != bkup.value) { + bkup.fail++; + } + delayMicroseconds(1000); + } +} +#endif + int main(void) { - bl_clock_config(); - bl_timer_init(); - bl_gpio_init(); + bl_clock_config(); + bl_timer_init(); + bl_gpio_init(); #ifdef BOOTLOADER_TEST_CLOCK - test_clock(); + test_clock(); #endif #ifdef BOOTLOADER_TEST_STRING - test_string(); + test_string(); #endif +#ifdef BOOTLOADER_TEST_BKUP + test_rtc_backup(); +#endif + + checkForSignal(); - checkForSignal(); + gpio_mode_set_input(input_pin, GPIO_PULL_NONE); - gpio_mode_set_input(input_pin, GPIO_PULL_NONE); - #ifdef USE_ADC_INPUT // go right to application - jump(); + jump(); #endif - deviceInfo[3] = pin_code; - #ifdef UPDATE_EEPROM_ENABLE - update_EEPROM(); + update_EEPROM(); #endif - while (1) { - receiveBuffer(); - if (invalid_command > 100) { - jump(); - } + while (1) { + receiveBuffer(); + if (invalid_command > 100) { + jump(); } +#if DRONECAN_SUPPORT + if (DroneCAN_update()) { + jump(); + } +#endif + } } diff --git a/f415makefile.mk b/f415makefile.mk index 8f6c157d..d85013f7 100644 --- a/f415makefile.mk +++ b/f415makefile.mk @@ -19,9 +19,21 @@ CFLAGS_$(MCU) := \ -I$(HAL_FOLDER_$(MCU))/Drivers/CMSIS/cm4/device_support CFLAGS_$(MCU) += \ - -D$(PART) \ + -D$(PART) -DARTERY \ -DUSE_STDPERIPH_DRIVER SRC_$(MCU) := $(foreach dir,$(SRC_DIR_$(MCU)),$(wildcard $(dir)/*.[cs])) SRC_$(MCU)_BL := $(foreach dir,$(SRC_BASE_DIR_$(MCU)),$(wildcard $(dir)/*.[cs])) \ $(wildcard $(HAL_FOLDER_$(MCU))/Src/*.c) + +# additional CFLAGS and source for DroneCAN +CFLAGS_DRONECAN_$(MCU) += \ + -Ibootloader/DroneCAN \ + -Ibootloader/DroneCAN/libcanard \ + -Ibootloader/DroneCAN/dsdl_generated/include + +SRC_DIR_DRONECAN_$(MCU) += bootloader/DroneCAN \ + bootloader/DroneCAN/dsdl_generated/src \ + bootloader/DroneCAN/libcanard + +SRC_DRONECAN_$(MCU) := $(foreach dir,$(SRC_DIR_DRONECAN_$(MCU)),$(wildcard $(dir)/*.[cs])) diff --git a/l431makefile.mk b/l431makefile.mk index c707ab48..6d039b3b 100644 --- a/l431makefile.mk +++ b/l431makefile.mk @@ -19,6 +19,7 @@ CFLAGS_$(MCU) := \ CFLAGS_$(MCU) += \ -DHSE_VALUE=8000000 \ -D$(PART) \ + -DMCU_$(MCU) \ -DHSE_STARTUP_TIMEOUT=100 \ -DLSE_STARTUP_TIMEOUT=5000 \ -DLSE_VALUE=32768 \ @@ -32,3 +33,15 @@ CFLAGS_$(MCU) += \ SRC_$(MCU)_BL := $(foreach dir,$(SRC_BASE_DIR_$(MCU)),$(wildcard $(dir)/*.[cs])) \ $(wildcard $(HAL_FOLDER_$(MCU))/Src/*.c) + +# additional CFLAGS and source for DroneCAN +CFLAGS_DRONECAN_$(MCU) += \ + -Ibootloader/DroneCAN \ + -Ibootloader/DroneCAN/libcanard \ + -Ibootloader/DroneCAN/dsdl_generated/include + +SRC_DIR_DRONECAN_$(MCU) += bootloader/DroneCAN \ + bootloader/DroneCAN/dsdl_generated/src \ + bootloader/DroneCAN/libcanard + +SRC_DRONECAN_$(MCU) := $(foreach dir,$(SRC_DIR_DRONECAN_$(MCU)),$(wildcard $(dir)/*.[cs])) diff --git a/tools/CodeStyle/am32-astyle.sh b/tools/CodeStyle/am32-astyle.sh new file mode 100755 index 00000000..d2611682 --- /dev/null +++ b/tools/CodeStyle/am32-astyle.sh @@ -0,0 +1,16 @@ +#!/usr/bin/env bash +# script for recormatting C code +# see https://astyle.sourceforge.net/astyle.html + +if [ -z "$1" ]; then + printf "\nArguments missing, Usage: '$0 '\n\n" + exit 1 +fi + +if [ $(uname) = "Darwin" ]; then + DIR=$(dirname $(greadlink -f $0)) +else + DIR=$(dirname $(readlink -f $0)) +fi + +astyle --options="${DIR}"/astylerc $* diff --git a/tools/CodeStyle/astylerc b/tools/CodeStyle/astylerc new file mode 100644 index 00000000..667b5501 --- /dev/null +++ b/tools/CodeStyle/astylerc @@ -0,0 +1,9 @@ +style=linux +keep-one-line-statements +add-braces +indent=spaces=2 +indent-col1-comments +min-conditional-indent=0 +suffix=none +lineend=linux +pad-header