diff --git a/Inc/common.h b/Inc/common.h index df7d1ea2..999c62c8 100644 --- a/Inc/common.h +++ b/Inc/common.h @@ -26,6 +26,11 @@ extern char ic_timer_prescaler; extern uint8_t buffersize; extern char output_timer_prescaler; extern uint8_t compute_dshot_flag; +extern uint16_t battery_voltage; +extern int16_t actual_current; +extern uint16_t e_rpm; + + #ifdef STMICRO extern GPIO_TypeDef* current_GPIO_PORT; #ifndef MCU_F031 @@ -73,3 +78,15 @@ typedef struct fastPID { int32_t integral_limit; int32_t output_limit; } fastPID; + +/* + input signal types + */ +enum inputType { + AUTO_IN = 0, + DSHOT_IN = 1, + SERVO_IN = 2, + SERIAL_IN = 3, + EDTARM_IN = 4, + DRONECAN_IN = 5, +}; diff --git a/Inc/eeprom.h b/Inc/eeprom.h index 2998b689..85b4cf1c 100644 --- a/Inc/eeprom.h +++ b/Inc/eeprom.h @@ -49,8 +49,18 @@ typedef union EEprom_u { uint8_t auto_advance; // 47 uint8_t reserved_2[4]; //48-51 uint8_t tune[124]; // 52-175 + struct { + uint8_t can_node; // 176 + uint8_t esc_index; // 177 + uint8_t require_arming; // 178 + uint8_t telem_rate; // 179 + uint8_t require_zero_throttle; // 180 + uint8_t filter_hz; // 181 + uint8_t debug_rate; // 182 + uint8_t reserved[9]; // 183-191 + } can; }; - uint8_t buffer[184]; + uint8_t buffer[192]; } EEprom_t; extern EEprom_t eepromBuffer; @@ -59,4 +69,4 @@ extern EEprom_t eepromBuffer; // void read_flash(uint8_t* data, uint32_t address); // void save_to_flash_bin(uint8_t *data, int length, uint32_t add); void read_flash_bin(uint8_t* data, uint32_t add, int out_buff_len); -void save_flash_nolib(uint8_t* data, int length, uint32_t add); \ No newline at end of file +void save_flash_nolib(uint8_t* data, int length, uint32_t add); diff --git a/Inc/targets.h b/Inc/targets.h index da9d9e23..8f13e3de 100644 --- a/Inc/targets.h +++ b/Inc/targets.h @@ -81,6 +81,18 @@ #define EEPROM_START_ADD (uint32_t)0x0800F800 #endif +#ifdef VIMDRONES_L431_CAN +#define FIRMWARE_NAME "VimdroneL431" +#define FILE_NAME "VIMDRONES_L431_CAN" +#define DRONECAN_SUPPORT 1 +#define DEAD_TIME 45 +#define HARDWARE_GROUP_L4_B +#define TARGET_VOLTAGE_DIVIDER 94 +#define MILLIVOLT_PER_AMP 30 +#define CURRENT_OFFSET 110 +#define USE_SERIAL_TELEMETRY +#endif + #ifdef VIMDRONES_NANO_L431 #define FIRMWARE_NAME "VM_NANO" #define FILE_NAME "VIMDRONES_NANO_L431" @@ -89,7 +101,31 @@ #define TARGET_VOLTAGE_DIVIDER 110 #define MILLIVOLT_PER_AMP 20 #define USE_SERIAL_TELEMETRY -#define EEPROM_START_ADD (uint32_t)0x0800F800 +#endif + +#ifdef VIMDRONES_NANO_L431_CAN +#define FIRMWARE_NAME "VM_NANO_CAN" +#define FILE_NAME "VIMDRONES_NANO_L431_CAN" +#define DRONECAN_SUPPORT 1 +#define USE_HSE +#undef HSE_VALUE +#define HSE_VALUE 24000000 +#define DEAD_TIME 45 +#define HARDWARE_GROUP_L4_B +#define TARGET_VOLTAGE_DIVIDER 110 +#define MILLIVOLT_PER_AMP 20 +#define USE_SERIAL_TELEMETRY +#endif + +#ifdef SIERRA_PULSE1_L431_CAN +#define FIRMWARE_NAME "SierraPulse1" +#define FILE_NAME "SIERRA_PULSE1_L431_CAN" +#define DRONECAN_SUPPORT 1 +#define DEAD_TIME 45 +#define HARDWARE_GROUP_L4_C +#define TARGET_VOLTAGE_DIVIDER 100 +#define MILLIVOLT_PER_AMP 100 +#define USE_SERIAL_TELEMETRY #endif #ifdef REF_L431 @@ -634,6 +670,43 @@ #define LOOP_FREQUENCY_HZ 20000 #endif +#ifdef TBS_12S_F415 +#define FIRMWARE_NAME "TBS 12S F415" +#define FILE_NAME "TBS_12S_F415" +#define DEAD_TIME 120 +#define HARDWARE_GROUP_AT_D +#define HARDWARE_GROUP_AT_045 +#define USE_SERIAL_TELEMETRY +#define ADC_CHANNEL_VOLTAGE ADC_CHANNEL_6 +#define ADC_CHANNEL_CURRENT ADC_CHANNEL_3 +#define TARGET_VOLTAGE_DIVIDER 210 +#define MILLIVOLT_PER_AMP 25 +#define RAMP_SPEED_LOW_RPM 1 +#define RAMP_SPEED_HIGH_RPM 1 +#define LOOP_FREQUENCY_HZ 20000 +#define PA6_VOLTAGE +#define EEPROM_START_ADD (uint32_t)0x0801F800 +#endif + +#ifdef TBS_12S_F415_CAN +#define FIRMWARE_NAME "TBS 12S CAN" +#define FILE_NAME "TBS_12S_F415_CAN" +#define DEAD_TIME 120 +#define HARDWARE_GROUP_AT_D +#define HARDWARE_GROUP_AT_045 +#define DRONECAN_SUPPORT 1 +#define USE_SERIAL_TELEMETRY +#define ADC_CHANNEL_VOLTAGE ADC_CHANNEL_6 +#define ADC_CHANNEL_CURRENT ADC_CHANNEL_3 +#define TARGET_VOLTAGE_DIVIDER 210 +#define MILLIVOLT_PER_AMP 25 +#define RAMP_SPEED_LOW_RPM 1 +#define RAMP_SPEED_HIGH_RPM 1 +#define LOOP_FREQUENCY_HZ 20000 +#define PA6_VOLTAGE +#define EEPROM_START_ADD (uint32_t)0x0801F800 +#endif + #ifdef AIKON_SINGLE_F421 #define FIRMWARE_NAME "AIKON S F4 " #define FILE_NAME "AIKON_SINGLE_F421" @@ -663,6 +736,23 @@ #define USE_SERIAL_TELEMETRY #endif +#ifdef REF_F415_CAN +#define FIRMWARE_NAME "REF F415 CAN" +#define FILE_NAME "REF_F415_CAN" +#define DRONECAN_SUPPORT 1 +#define DEAD_TIME 120 +#define HARDWARE_GROUP_AT_D +#define HARDWARE_GROUP_AT_045 +#define USE_SERIAL_TELEMETRY +#define ADC_CHANNEL_VOLTAGE ADC_CHANNEL_6 +#define ADC_CHANNEL_CURRENT ADC_CHANNEL_3 +#define TARGET_VOLTAGE_DIVIDER 210 +#define MILLIVOLT_PER_AMP 25 +#define RAMP_SPEED_LOW_RPM 1 +#define RAMP_SPEED_HIGH_RPM 1 +#define LOOP_FREQUENCY_HZ 20000 +#endif + #ifdef DAKEFPV_35A_F415 #define FIRMWARE_NAME "DakeFPV 35A" #define FILE_NAME "DAKEFPV_35A_F415" // DISABLE_BUILD @@ -680,10 +770,11 @@ #define USE_SERIAL_TELEMETRY #endif -#ifdef TBS_CAN_F415 -#define FIRMWARE_NAME "TBS_CAN_F415" -#define FILE_NAME "TBS_CAN_F415" +#ifdef TBS_F415_CAN +#define FIRMWARE_NAME "TBS_F415_CAN" +#define FILE_NAME "TBS_F415_CAN" #define DEAD_TIME 120 +#define DRONECAN_SUPPORT 1 #define HARDWARE_GROUP_AT_H #define HARDWARE_GROUP_AT_045 #define TARGET_VOLTAGE_DIVIDER 210 @@ -3387,7 +3478,9 @@ #ifdef MCU_AT415 #define ARTERY #define CPU_FREQUENCY_MHZ 144 +#ifndef EEPROM_START_ADD #define EEPROM_START_ADD (uint32_t)0x08007C00 +#endif #define INTERVAL_TIMER TMR4 #define TEN_KHZ_TIMER TMR9 #define UTILITY_TIMER TMR10 @@ -3438,3 +3531,12 @@ #endif #define PID_LOOP_DIVIDER (LOOP_FREQUENCY_HZ / 1000) + +// default to no DroneCAN support +#ifndef DRONECAN_SUPPORT +#define DRONECAN_SUPPORT 0 +#elif DRONECAN_SUPPORT == 1 +// all DroneCAN ESCs use 128k flash layout +#undef EEPROM_START_ADD +#define EEPROM_START_ADD (uint32_t)0x0801F800 +#endif diff --git a/Makefile b/Makefile index bf251964..fa9ae551 100644 --- a/Makefile +++ b/Makefile @@ -44,7 +44,7 @@ FIRMWARE_VERSION := $(VERSION_MAJOR).$(VERSION_MINOR) # Compiler options CFLAGS_BASE := -fsingle-precision-constant -fomit-frame-pointer -ffast-math -CFLAGS_BASE += -I$(MAIN_INC_DIR) -g3 -O2 -ffunction-sections +CFLAGS_BASE += -I$(MAIN_INC_DIR) -g3 -O2 -ffunction-sections --specs=nosys.specs CFLAGS_BASE += -Wall -Wundef -Wextra -Werror -Wno-unused-parameter -Wno-stringop-truncation CFLAGS_COMMON := $(CFLAGS_BASE) @@ -59,6 +59,9 @@ SRC_COMMON := $(foreach dir,$(SRC_DIRS_COMMON),$(wildcard $(dir)/*.[cs])) OBJ := obj BIN_DIR := $(ROOT)/$(OBJ) +# Function to check for _CAN suffix +has_can_suffix = $(findstring _CAN,$1) + # find the SVD files $(foreach MCU,$(MCU_TYPES),$(eval SVD_$(MCU) := $(wildcard $(HAL_FOLDER_$(MCU))/*.svd))) @@ -88,20 +91,26 @@ $$($(2)_BASENAME).bin: $$($(2)_BASENAME).elf echo building BIN $$@ @$(ECHO) Generating $$(notdir $$@) $(QUIET)$(OBJCOPY) -O binary $$(<) $$@ + $(QUIET)python3 Src/DroneCAN/set_app_signature.py $$@ $$(<) $(QUIET)$(OBJCOPY) $$(<) -O ihex $$(@:.bin=.hex) + $(QUIET)$(CP) -f $$(<) $(OBJ)$(DSEP)debug.elf > $(NUL) + +# check for CAN support +$(eval xLDSCRIPT := $$(if $$(call has_can_suffix,$$(2)),$(LDSCRIPT_CAN_$(1)),$(LDSCRIPT_$(1)))) +$(eval xCFLAGS := $$(if $$(call has_can_suffix,$$(2)),$(CFLAGS_CAN_$(1)))) +$(eval xSRC := $$(if $$(call has_can_suffix,$$(2)),$(SRC_CAN_$(1)))) -CFLAGS_$(2) = $(MCU_$(1)) -D$(2) $(CFLAGS_$(1)) $(CFLAGS_COMMON) -LDFLAGS_$(2) = $(LDFLAGS_COMMON) $(LDFLAGS_$(1)) -T$(LDSCRIPT_$(1)) +CFLAGS_$(2) = -DAM32_MCU=\"$(MCU)\" $(MCU_$(1)) -D$(2) $(CFLAGS_$(1)) $(CFLAGS_COMMON) $(xCFLAGS) +LDFLAGS_$(2) = $(LDFLAGS_COMMON) $(LDFLAGS_$(1)) -T$(xLDSCRIPT) -include $$($(2)_BASENAME).d -$$($(2)_BASENAME).elf: $(SRC_COMMON) $$(SRC_$(1)) +$$($(2)_BASENAME).elf: $(SRC_COMMON) $$(SRC_$(1)) $(xSRC) @$(ECHO) Compiling $$(notdir $$@) $(QUIET)$(MKDIR) -p $(OBJ) - $(QUIET)$(CC) $$(CFLAGS_$(2)) $$(LDFLAGS_$(2)) -MMD -MP -MF $$(@:.elf=.d) -o $$(@) $(SRC_COMMON) $$(SRC_$(1)) + $(QUIET)$(CC) $$(CFLAGS_$(2)) $$(LDFLAGS_$(2)) -MMD -MP -MF $$(@:.elf=.d) -o $$(@) $(SRC_COMMON) $$(SRC_$(1)) $(xSRC) # we copy debug.elf to give us a constant debug target for vscode # this means the debug button will always debug the last target built - $(QUIET)$(CP) -f $$(@) $(OBJ)$(DSEP)debug.elf > $(NUL) $(QUIET)$(CP) -f $$(SVD_$(1)) $(OBJ)/debug.svd # also copy the openocd.cfg from the MCU directory to obj/openocd.cfg for auto config of Cortex-Debug # in vscode 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/Src/eeprom.c b/Mcu/f415/Src/eeprom.c index d06e31f8..21d69cb3 100644 --- a/Mcu/f415/Src/eeprom.c +++ b/Mcu/f415/Src/eeprom.c @@ -1,46 +1,54 @@ #include "eeprom.h" +#include "targets.h" #include +#include + +//#pragma GCC optimize("O0") #include "at32f415_flash.h" -// #define APP_START (uint32_t)0x08001000 -// #define FLASH_STORAGE 0x08005000 // at the 31kb mark -#define page_size 0x400 // 1 kb for f051 -// uint32_t FLASH_FKEY1 =0x45670123; -// uint32_t FLASH_FKEY2 =0xCDEF89AB; +/* + the F415 can be either 1k or 2k sector size. The 256k flash part has + 2k sector size. We only support ESCs with 128k flash or less, so 1k + sector size, but it is useful to work with 2k sector size when using + a F415 dev board like the AT-Start F415, so we detect here. + */ +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; +} void save_flash_nolib(uint8_t* data, int length, uint32_t add) -{ /// todo - - // fmc_wscnt_set(2); - - // fmc_prefetch_enable(); - - uint32_t data_to_FLASH[length / 4]; - memset(data_to_FLASH, 0, length / 4); - for (int i = 0; i < length / 4; i++) { - data_to_FLASH[i] = data[i * 4 + 3] << 24 | data[i * 4 + 2] << 16 | data[i * 4 + 1] << 8 | data[i * 4]; // make 16 bit +{ + if ((add & 0x3) != 0 || (length & 0x3) != 0) { + return; } - volatile uint32_t data_length = length / 4; + /* + 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 1024 - if ((add % 1024) == 0) { - flash_sector_erase(add); + // erase page if address even divisable by sector size + if ((add % sector_size()) == 0) { + flash_sector_erase(add); } - volatile uint32_t index = 0; - while (index < data_length) { - // fmc_word_program(add + (index*4),data_to_FLASH[index]); - flash_word_program(add + (index * 4), data_to_FLASH[index]); - // fmc_flag_clear(FMC_FLAG_END | - // FMC_FLAG_WPERR | - // FMC_FLAG_PGERR); - flash_flag_clear(FLASH_PROGRAM_ERROR | FLASH_EPP_ERROR | FLASH_OPERATE_DONE); + 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(); @@ -48,8 +56,5 @@ void save_flash_nolib(uint8_t* data, int length, uint32_t add) void read_flash_bin(uint8_t* data, uint32_t add, int out_buff_len) { - // volatile uint32_t read_data; - for (int i = 0; i < out_buff_len; i++) { - data[i] = *(uint8_t*)(add + i); - } -} \ No newline at end of file + memcpy(data, (void*)add, out_buff_len); +} diff --git a/Mcu/f415/Src/system_at32f415.c b/Mcu/f415/Src/system_at32f415.c index adf7b452..7898c7c8 100644 --- a/Mcu/f415/Src/system_at32f415.c +++ b/Mcu/f415/Src/system_at32f415.c @@ -33,13 +33,18 @@ */ #include "at32f415.h" +#include "targets.h" +#include "string.h" /** @addtogroup AT32F415_system_private_defines * @{ */ -#define VECT_TAB_OFFSET \ - 0x1000 /*!< vector table base offset field. this value must be a multiple \ - of 0x200. */ +/*!< vector table base offset field. this value must be a multiple of 0x200. */ +#if DRONECAN_SUPPORT +#define VECT_TAB_OFFSET 0x4000 +#else +#define VECT_TAB_OFFSET 0x1000 +#endif /** * @} */ diff --git a/Mcu/f415/AT32F415x8_FLASH.ld b/Mcu/f415/ldscript.ld similarity index 91% rename from Mcu/f415/AT32F415x8_FLASH.ld rename to Mcu/f415/ldscript.ld index 6dabc92e..5727cb8d 100644 --- a/Mcu/f415/AT32F415x8_FLASH.ld +++ b/Mcu/f415/ldscript.ld @@ -22,7 +22,7 @@ ENTRY(Reset_Handler) /* Highest address of the user mode stack */ -_estack = 0x20008000; /* end of RAM */ +_estack = 0x20004000; /* end of RAM, assume 16k */ /* Generate a link error if heap and stack don't fit into RAM */ _Min_Heap_Size = 0x200; /* required amount of heap */ @@ -31,11 +31,11 @@ _Min_Stack_Size = 0x400; /* required amount of stack */ /* Specify the memory areas */ MEMORY { -FLASH (rx) : ORIGIN = 0x08001000, LENGTH = 27K -FLASH_VERSION (rx) : ORIGIN = 0x08007C00 - 48, LENGTH = 16 -FILE_NAME (rx) : ORIGIN = 0x08007C00 - 32, LENGTH = 32 -EEPROM (rx) : ORIGIN = 0x08007C00, LENGTH = 1K -RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 32K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 16K + FLASH (rx) : ORIGIN = 0x08001000, LENGTH = 57K + EEPROM (rx) : ORIGIN = 0x0800f800, LENGTH = 2K + FLASH_VERSION (rx) : ORIGIN = ORIGIN(EEPROM) - 48, LENGTH = 16 + FILE_NAME (rx) : ORIGIN = ORIGIN(EEPROM) - 32, LENGTH = 32 } /* Define output sections */ diff --git a/Mcu/f415/ldscript_CAN.ld b/Mcu/f415/ldscript_CAN.ld new file mode 100644 index 00000000..a72f4eb8 --- /dev/null +++ b/Mcu/f415/ldscript_CAN.ld @@ -0,0 +1,180 @@ +/* +***************************************************************************** +** +** File : AT32F415x8_FLASH.ld +** +** Abstract : Linker script for AT32F415x8 Device with +** 64KByte FLASH, 32KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : Artery Tek AT32 +** +** Environment : Arm gcc toolchain +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20008000; /* end of RAM, assume 32k part */ + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 32K + FLASH1 (rx) : ORIGIN = 0x08004000, LENGTH = 512 + FILE_NAME (rx) : ORIGIN = ORIGIN(FLASH1)+LENGTH(FLASH1), LENGTH = 32 + EEPROM (rx) : ORIGIN = 0x0801f800, LENGTH = 2K + FLASH (rx) : ORIGIN = ORIGIN(FILE_NAME)+LENGTH(FILE_NAME), LENGTH = ORIGIN(EEPROM)-(ORIGIN(FILE_NAME)+LENGTH(FILE_NAME)) +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code into "FLASH" Rom type memory */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + KEEP(*(.app_signature)) + . = ALIGN(4); + } > FLASH1 + + .fill_flash1 : + { + FILL(0x00); + . = ORIGIN(FLASH1) + LENGTH(FLASH1) - 1; + BYTE(0x00) + } > FLASH1 + + /* 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 + + .flash_fill : + { + . = ALIGN(4); + BYTE(0x00); + } > FLASH + + /* The file name */ + .file_name : + { + . = ALIGN(4); + KEEP (*(.file_name)) + . = ALIGN(4); + } >FILE_NAME + + /* 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/Mcu/l431/Drivers/STM32L4xx_HAL_Driver/Inc/stm32l4xx_ll_rcc.h b/Mcu/l431/Drivers/STM32L4xx_HAL_Driver/Inc/stm32l4xx_ll_rcc.h index 6bd72bd6..eabc9668 100644 --- a/Mcu/l431/Drivers/STM32L4xx_HAL_Driver/Inc/stm32l4xx_ll_rcc.h +++ b/Mcu/l431/Drivers/STM32L4xx_HAL_Driver/Inc/stm32l4xx_ll_rcc.h @@ -19,6 +19,11 @@ #ifndef STM32L4xx_LL_RCC_H #define STM32L4xx_LL_RCC_H +/* + AM32 hack to allow HSE_VALUE define in targets.h + */ +#include + #ifdef __cplusplus extern "C" { #endif diff --git a/Mcu/l431/Src/eeprom.c b/Mcu/l431/Src/eeprom.c index 1da99a19..ff20afbd 100644 --- a/Mcu/l431/Src/eeprom.c +++ b/Mcu/l431/Src/eeprom.c @@ -8,82 +8,69 @@ #include "eeprom.h" #include +#include - -#define page_size 0x800 // 2 kb for g071 +#define page_size 0x800 // 2 kb for l431 uint32_t FLASH_FKEY1 =0x45670123; uint32_t FLASH_FKEY2 =0xCDEF89AB; - - +/* + write to flash, done as a RAM function to allow for DroneCAN fw update + */ void save_flash_nolib(uint8_t *data, int length, uint32_t add){ - uint32_t data_to_FLASH[length / 4]; - memset(data_to_FLASH, 0, length / 4); - for(int i = 0; i < length / 4 ; i ++ ){ - data_to_FLASH[i] = data[i*4+3] << 24 |data[i*4+2] << 16|data[i*4+1] << 8| data[i*4]; // make 16 bit - } - volatile uint32_t data_length = length / 4; - - // 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 % 2048) == 0){ - - - FLASH->CR |= FLASH_CR_PER; - FLASH->CR |= (add/2048) << 3; - FLASH->CR |= FLASH_CR_STRT; - while ((FLASH->SR & FLASH_SR_BSY) != 0){ - /* add time-out */ - } - if ((FLASH->SR & FLASH_SR_EOP) != 0){ - FLASH->SR = FLASH_SR_EOP; - } - else{ - /* error */ - } - FLASH->CR &= ~FLASH_CR_PER; - - } - - volatile uint32_t write_cnt=0, index=0; - while(index < data_length) - { - - FLASH->CR |= FLASH_CR_PG; /* (1) */ - *(__IO uint32_t*)(add+write_cnt) = data_to_FLASH[index]; - *(__IO uint32_t*)(add+write_cnt+4) = data_to_FLASH[index+1]; - while ((FLASH->SR & FLASH_SR_BSY) != 0){ /* add time-out */ - } - if ((FLASH->SR & FLASH_SR_EOP) != 0){ - FLASH->SR = FLASH_SR_EOP; - } - else{ - /* error */ - } - FLASH->CR &= ~FLASH_CR_PG; - write_cnt += 8; - index +=2; - } - SET_BIT(FLASH->CR, FLASH_CR_LOCK); + if ((add & 0x7) != 0 || (length & 0x7)) { + // address and length must be on 8 byte boundary + return; + } + // 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) ; + } + + uint32_t index = 0; + volatile uint32_t *fdata = (volatile uint32_t *)add; + + while (index < data_length) { + // flash two words at a time + uint32_t words[2]; + memcpy((void*)&words[0], &data[index*4], sizeof(words)); + + flash->CR = FLASH_CR_PG; + + fdata[index] = words[0]; + fdata[index+1] = words[1]; + + while ((flash->SR & FLASH_SR_BSY) != 0) ; + + flash->SR |= FLASH_SR_EOP; + flash->CR = 0; + index += 2; + } + + // lock flash again + SET_BIT(flash->CR, FLASH_CR_LOCK); } - - - -void read_flash_bin(uint8_t* data , uint32_t add , int out_buff_len){ - //volatile uint32_t read_data; - for (int i = 0; i < out_buff_len ; i ++){ - data[i] = *(uint8_t*)(add + i); - } +void read_flash_bin(uint8_t* data , uint32_t add, int out_buff_len) { + memcpy(data, (const void*)add, out_buff_len); } - - diff --git a/Mcu/l431/Src/peripherals.c b/Mcu/l431/Src/peripherals.c index 5712d98f..f0429fa6 100644 --- a/Mcu/l431/Src/peripherals.c +++ b/Mcu/l431/Src/peripherals.c @@ -47,7 +47,6 @@ void initCorePeripherals(void) void initAfterJump() { - SCB->VTOR = 0x08001000; __enable_irq(); } @@ -61,6 +60,17 @@ void SystemClock_Config(void) while (LL_PWR_IsActiveFlag_VOS() != 0) { } + +#ifdef USE_HSE + LL_RCC_HSE_EnableBypass(); + LL_RCC_HSE_Enable(); +#if HSE_VALUE == 24000000 + LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSE, LL_RCC_PLLM_DIV_3, 20, LL_RCC_PLLR_DIV_2); +#else +#error "Unsupported HSE_VALUE" +#endif + +#else LL_RCC_MSI_Enable(); /* Wait till MSI is ready */ @@ -72,6 +82,8 @@ void SystemClock_Config(void) 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); +#endif + LL_RCC_PLL_EnableDomain_SYS(); LL_RCC_PLL_Enable(); diff --git a/Mcu/l431/Src/system_stm32l4xx.c b/Mcu/l431/Src/system_stm32l4xx.c index 1773244d..fcb87985 100644 --- a/Mcu/l431/Src/system_stm32l4xx.c +++ b/Mcu/l431/Src/system_stm32l4xx.c @@ -22,72 +22,13 @@ * Then SystemInit() function is called, in "startup_stm32l4xx.s" file, to * configure the system clock before to branch to main program. * - * This file configures the system clock as follows: - *============================================================================= - *----------------------------------------------------------------------------- - * System Clock source | MSI - *----------------------------------------------------------------------------- - * SYSCLK(Hz) | 4000000 - *----------------------------------------------------------------------------- - * HCLK(Hz) | 4000000 - *----------------------------------------------------------------------------- - * AHB Prescaler | 1 - *----------------------------------------------------------------------------- - * APB1 Prescaler | 1 - *----------------------------------------------------------------------------- - * APB2 Prescaler | 1 - *----------------------------------------------------------------------------- - * PLL_M | 1 - *----------------------------------------------------------------------------- - * PLL_N | 8 - *----------------------------------------------------------------------------- - * PLL_P | 7 - *----------------------------------------------------------------------------- - * PLL_Q | 2 - *----------------------------------------------------------------------------- - * PLL_R | 2 - *----------------------------------------------------------------------------- - * PLLSAI1_P | NA - *----------------------------------------------------------------------------- - * PLLSAI1_Q | NA - *----------------------------------------------------------------------------- - * PLLSAI1_R | NA - *----------------------------------------------------------------------------- - * PLLSAI2_P | NA - *----------------------------------------------------------------------------- - * PLLSAI2_Q | NA - *----------------------------------------------------------------------------- - * PLLSAI2_R | NA - *----------------------------------------------------------------------------- - * Require 48MHz for USB OTG FS, | Disabled - * SDIO and RNG clock | - *----------------------------------------------------------------------------- - *============================================================================= - ****************************************************************************** - * @attention - * - * Copyright (c) 2017 STMicroelectronics. - * All rights reserved. - * - * This software is licensed under terms that can be found in the LICENSE file - * in the root directory of this software component. - * If no LICENSE file comes with this software, it is provided AS-IS. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32l4xx_system - * @{ - */ - -/** @addtogroup STM32L4xx_System_Private_Includes - * @{ */ +/* + init code should be small, not fast + */ +#pragma GCC optimize("Os") +#include "targets.h" #include "stm32l4xx.h" /** @@ -102,47 +43,6 @@ * @} */ -/** @addtogroup STM32L4xx_System_Private_Defines - * @{ - */ - -#if !defined (HSE_VALUE) - #define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */ -#endif /* HSE_VALUE */ - -#if !defined (MSI_VALUE) - #define MSI_VALUE 4000000U /*!< Value of the Internal oscillator in Hz*/ -#endif /* MSI_VALUE */ - -#if !defined (HSI_VALUE) - #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/ -#endif /* HSI_VALUE */ - -/* Note: Following vector table addresses must be defined in line with linker - configuration. */ -/*!< Uncomment the following line if you need to relocate the vector table - anywhere in Flash or Sram, else the vector table is kept at the automatic - remap of boot address selected */ -/* #define USER_VECT_TAB_ADDRESS */ - -#if defined(USER_VECT_TAB_ADDRESS) -/*!< Uncomment the following line if you need to relocate your vector Table - in Sram else user remap will be done in Flash. */ -/* #define VECT_TAB_SRAM */ - -#if defined(VECT_TAB_SRAM) -#define VECT_TAB_BASE_ADDRESS SRAM1_BASE /*!< Vector Table base address field. - This value must be a multiple of 0x200. */ -#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field. - This value must be a multiple of 0x200. */ -#else -#define VECT_TAB_BASE_ADDRESS FLASH_BASE /*!< Vector Table base address field. - This value must be a multiple of 0x200. */ -#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field. - This value must be a multiple of 0x200. */ -#endif /* VECT_TAB_SRAM */ -#endif /* USER_VECT_TAB_ADDRESS */ - /******************************************************************************/ /** * @} @@ -159,35 +59,20 @@ /** @addtogroup STM32L4xx_System_Private_Variables * @{ */ - /* The SystemCoreClock variable is updated in three ways: - 1) by calling CMSIS function SystemCoreClockUpdate() - 2) by calling HAL API function HAL_RCC_GetHCLKFreq() - 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency - Note: If you use this function to configure the system clock; then there - is no need to call the 2 first functions listed above, since SystemCoreClock - variable is updated automatically. - */ - uint32_t SystemCoreClock = 4000000U; - - const uint8_t AHBPrescTable[16] = {0U, 0U, 0U, 0U, 0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U, 6U, 7U, 8U, 9U}; - const uint8_t APBPrescTable[8] = {0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U}; - const uint32_t MSIRangeTable[12] = {100000U, 200000U, 400000U, 800000U, 1000000U, 2000000U, \ - 4000000U, 8000000U, 16000000U, 24000000U, 32000000U, 48000000U}; -/** - * @} - */ - -/** @addtogroup STM32L4xx_System_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32L4xx_System_Private_Functions - * @{ - */ +/* The SystemCoreClock variable is updated in three ways: + 1) by calling CMSIS function SystemCoreClockUpdate() + 2) by calling HAL API function HAL_RCC_GetHCLKFreq() + 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency + Note: If you use this function to configure the system clock; then there + is no need to call the 2 first functions listed above, since SystemCoreClock + variable is updated automatically. +*/ +uint32_t SystemCoreClock = 4000000U; + +const uint8_t AHBPrescTable[16] = {0U, 0U, 0U, 0U, 0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U, 6U, 7U, 8U, 9U}; +const uint8_t APBPrescTable[8] = {0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U}; +const uint32_t MSIRangeTable[12] = {100000U, 200000U, 400000U, 800000U, 1000000U, 2000000U, \ + 4000000U, 8000000U, 16000000U, 24000000U, 32000000U, 48000000U}; /** * @brief Setup the microcontroller system. @@ -225,126 +110,3 @@ void SystemInit(void) /* Disable all interrupts */ RCC->CIER = 0x00000000U; } - -/** - * @brief Update SystemCoreClock variable according to Clock Register Values. - * The SystemCoreClock variable contains the core clock (HCLK), it can - * be used by the user application to setup the SysTick timer or configure - * other parameters. - * - * @note Each time the core clock (HCLK) changes, this function must be called - * to update SystemCoreClock variable value. Otherwise, any configuration - * based on this variable will be incorrect. - * - * @note - The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined - * constant and the selected clock source: - * - * - If SYSCLK source is MSI, SystemCoreClock will contain the MSI_VALUE(*) - * - * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**) - * - * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***) - * - * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(***) - * or HSI_VALUE(*) or MSI_VALUE(*) multiplied/divided by the PLL factors. - * - * (*) MSI_VALUE is a constant defined in stm32l4xx_hal.h file (default value - * 4 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * - * (**) HSI_VALUE is a constant defined in stm32l4xx_hal.h file (default value - * 16 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * - * (***) HSE_VALUE is a constant defined in stm32l4xx_hal.h file (default value - * 8 MHz), user has to ensure that HSE_VALUE is same as the real - * frequency of the crystal used. Otherwise, this function may - * have wrong result. - * - * - The result of this function could be not correct when using fractional - * value for HSE crystal. - * - * @retval None - */ -void SystemCoreClockUpdate(void) -{ - uint32_t tmp, msirange, pllvco, pllsource, pllm, pllr; - - /* Get MSI Range frequency--------------------------------------------------*/ - if ((RCC->CR & RCC_CR_MSIRGSEL) == 0U) - { /* MSISRANGE from RCC_CSR applies */ - msirange = (RCC->CSR & RCC_CSR_MSISRANGE) >> 8U; - } - else - { /* MSIRANGE from RCC_CR applies */ - msirange = (RCC->CR & RCC_CR_MSIRANGE) >> 4U; - } - /*MSI frequency range in HZ*/ - msirange = MSIRangeTable[msirange]; - - /* Get SYSCLK source -------------------------------------------------------*/ - switch (RCC->CFGR & RCC_CFGR_SWS) - { - case 0x00: /* MSI used as system clock source */ - SystemCoreClock = msirange; - break; - - case 0x04: /* HSI used as system clock source */ - SystemCoreClock = HSI_VALUE; - break; - - case 0x08: /* HSE used as system clock source */ - SystemCoreClock = HSE_VALUE; - break; - - case 0x0C: /* PLL used as system clock source */ - /* PLL_VCO = (HSE_VALUE or HSI_VALUE or MSI_VALUE/ PLLM) * PLLN - SYSCLK = PLL_VCO / PLLR - */ - pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC); - pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> 4U) + 1U ; - - switch (pllsource) - { - case 0x02: /* HSI used as PLL clock source */ - pllvco = (HSI_VALUE / pllm); - break; - - case 0x03: /* HSE used as PLL clock source */ - pllvco = (HSE_VALUE / pllm); - break; - - default: /* MSI used as PLL clock source */ - pllvco = (msirange / pllm); - break; - } - pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 8U); - pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 25U) + 1U) * 2U; - SystemCoreClock = pllvco/pllr; - break; - - default: - SystemCoreClock = msirange; - break; - } - /* Compute HCLK clock frequency --------------------------------------------*/ - /* Get HCLK prescaler */ - tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4U)]; - /* HCLK clock frequency */ - SystemCoreClock >>= tmp; -} - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - diff --git a/Mcu/l431/STM32L431KCUX_FLASH.ld b/Mcu/l431/ldscript.ld similarity index 98% rename from Mcu/l431/STM32L431KCUX_FLASH.ld rename to Mcu/l431/ldscript.ld index 312c9562..f61a3fca 100644 --- a/Mcu/l431/STM32L431KCUX_FLASH.ld +++ b/Mcu/l431/ldscript.ld @@ -157,9 +157,6 @@ SECTIONS _sdata = .; /* create a global symbol at data start */ *(.data) /* .data sections */ *(.data*) /* .data* sections */ - *(.RamFunc) /* .RamFunc sections */ - *(.RamFunc*) /* .RamFunc* sections */ - . = ALIGN(4); _edata = .; /* define a global symbol at data end */ diff --git a/Mcu/l431/ldscript_CAN.ld b/Mcu/l431/ldscript_CAN.ld new file mode 100644 index 00000000..ed1cede1 --- /dev/null +++ b/Mcu/l431/ldscript_CAN.ld @@ -0,0 +1,182 @@ +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */ + +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Memories definition */ +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K + FLASH1 (rx) : ORIGIN = 0x08004000, LENGTH = 512 + FILE_NAME (rx) : ORIGIN = ORIGIN(FLASH1)+LENGTH(FLASH1), LENGTH = 32 + EEPROM (rx) : ORIGIN = 0x0801f800, LENGTH = 2K + FLASH (rx) : ORIGIN = ORIGIN(FILE_NAME)+LENGTH(FILE_NAME), LENGTH = ORIGIN(EEPROM)-(ORIGIN(FILE_NAME)+LENGTH(FILE_NAME)) +} + +/* Sections */ +SECTIONS +{ + /* The startup code into "FLASH" Rom type memory */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + KEEP(*(.app_signature)) + . = ALIGN(4); + } > FLASH1 + + .fill_flash1 : + { + FILL(0x00); + . = ORIGIN(FLASH1) + LENGTH(FLASH1) - 1; + BYTE(0x00) + } > FLASH1 + + /* The program code and other data into "FLASH" Rom type memory */ + .text : + { + FILL(0x00); + . = 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 into "FLASH" Rom type memory */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { + . = ALIGN(4); + *(.ARM.extab* .gnu.linkonce.armextab.*) + . = ALIGN(4); + } >FLASH + + .ARM : { + . = ALIGN(4); + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + . = ALIGN(4); + } >FLASH + + .preinit_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + . = ALIGN(4); + } >FLASH + + .init_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + . = ALIGN(4); + } >FLASH + + .fini_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + . = ALIGN(4); + } >FLASH + + .flash_fill : + { + . = ALIGN(4); + BYTE(0x00); + } > FLASH + + /* The file name */ + .file_name : + { + FILL(0x00); + . = ALIGN(4); + KEEP (*(.file_name)) + BYTE(0x00) + } >FILE_NAME + + .filename_fill : + { + BYTE(0x00); + } > FILE_NAME + + /* Used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections into "RAM" Ram type memory */ + .data : + { + FILL(0x00); + . = 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 into "RAM" Ram type memory */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _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" Ram type memory left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + /* Remove information from the compiler libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/Src/DroneCAN/DroneCAN.c b/Src/DroneCAN/DroneCAN.c new file mode 100644 index 00000000..0bde9e75 --- /dev/null +++ b/Src/DroneCAN/DroneCAN.c @@ -0,0 +1,1222 @@ +/* + * DroneCAN.c - support for DroneCAN protocol for ESC control and telemetry + */ + +#include "targets.h" + +// #pragma GCC optimize("O0") + +#if DRONECAN_SUPPORT + +#include "peripherals.h" +#include "serial_telemetry.h" +#include +#include +#include +#include +#include +#include +#include +#include "sys_can.h" +#include +#include "phaseouts.h" +#include "functions.h" +#include "filter.h" + +// 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 + +// use set input at 1kHz +#define TARGET_PERIOD_US 1000U + +static CanardInstance canard; +static uint8_t canard_memory_pool[CANARD_POOL_SIZE]; + +struct CANStats canstats; + +static bool dronecan_armed; +static bool done_startup; + +#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, +}; + +enum VarType { + T_BOOL = 0, + T_UINT8, + T_UINT16, + T_STRING, +}; + +#define PACKED __attribute__((__packed__)) + +/* + structure sent with FlexDebug + */ +static struct PACKED { + uint8_t version; + uint32_t commutation_interval; + uint16_t num_commands; + uint16_t num_input; + uint16_t rx_errors; + uint16_t rxframe_error; + int32_t rx_ecode; + uint8_t auto_advance_level; +} debug1; + +static void can_printf(const char *fmt, ...); + +// some convenience macros +#define MIN(a,b) ((a)<(b)?(a):(b)) +#define C_TO_KELVIN(temp) (temp + 273.15f) +#define ARRAY_SIZE(x) (sizeof(x)/sizeof(x[0])) + +/* + access to settings from main.c + */ +extern uint16_t motor_kv; +extern char armed; +extern uint32_t commutation_interval; +extern uint8_t auto_advance_level; +extern uint16_t low_cell_volt_cutoff; + +static uint16_t last_can_input; +static struct { + uint32_t sum; + uint32_t count; +} current; + +extern void saveEEpromSettings(void); +extern void loadEEpromSettings(void); +static void set_input(uint16_t input); + +/* + the set of parameters to present to the user over DroneCAN +*/ +static const struct parameter { + char *name; + enum VarType vtype; + uint16_t min_value; + uint16_t max_value; + uint16_t default_value; + void *ptr; +} parameters[] = { + // list of settable parameters + // dronecan specific parameters + { "CAN_NODE", T_UINT8, 0, 127, 0, &eepromBuffer.can.can_node}, + { "ESC_INDEX", T_UINT8, 0, 32, 0, &eepromBuffer.can.esc_index}, + { "TELEM_RATE", T_UINT8, 0, 200, 25, &eepromBuffer.can.telem_rate}, + { "DEBUG_RATE", T_UINT8, 0, 200, 0, &eepromBuffer.can.debug_rate}, + { "REQUIRE_ARMING", T_BOOL, 0, 1, 1, &eepromBuffer.can.require_arming}, + { "REQUIRE_ZERO_THROTTLE", T_BOOL, 0, 1, 1, &eepromBuffer.can.require_zero_throttle}, + { "MOTOR_KV", T_UINT16,20, 10220, 2000, &motor_kv}, + { "MOTOR_POLES", T_UINT8, 2, 64, 14, &eepromBuffer.motor_poles}, + + // motor_kv, low_cell_volt_cutoff, STARTUP_TUNE, CURRENT_LIMIT value need to adjust to dronecan gui tool + // motor_kv 1k/V + // CURRENT_LIMIT A, range 0 ~ 200, 0 to disable + // TEMPERATURE_LIMIT degrees celsius, range 70 ~ 141, 0 to disable + // low_cell_volt_cutoff 10mV, range 250 ~ 350 + // STARTUP_TUNE RTTTL string + + { "DIR_REVERSED", T_BOOL, 0, 1, 0, &eepromBuffer.dir_reversed}, + { "BI_DIRECTIONAL", T_BOOL, 0, 1, 0, &eepromBuffer.bi_direction}, + { "BEEP_VOLUME", T_UINT8, 0, 11, 5, &eepromBuffer.beep_volume}, + { "VARIABLE_PWM", T_BOOL, 0, 1, 1, &eepromBuffer.variable_pwm}, + { "PWM_FREQUENCY", T_UINT8, 8, 48, 24, &eepromBuffer.pwm_frequency}, + { "USE_SIN_START", T_BOOL, 0, 1, 0, &eepromBuffer.use_sine_start}, + { "COMP_PWM", T_BOOL, 0, 1, 1, &eepromBuffer.comp_pwm}, + { "STUCK_ROTOR_PROTECTION", T_BOOL, 0, 1, 1, &eepromBuffer.stuck_rotor_protection}, + { "ADVANCE_LEVEL", T_UINT8, 0, 4, 2, &eepromBuffer.advance_level}, + { "AUTO_ADVANCE", T_BOOL, 0, 1, 0, &eepromBuffer.auto_advance}, + { "STARTUP_POWER", T_UINT8, 50,150, 10, &eepromBuffer.startup_power}, + { "CURRENT_LIMIT", T_UINT8, 0, 200, 0, &eepromBuffer.limits.current}, + { "TEMPERATURE_LIMIT", T_UINT8, 70,255, 255,&eepromBuffer.limits.temperature}, + { "LOW_VOLTAGE_CUTOFF", T_BOOL, 0, 1, 0, &eepromBuffer.low_voltage_cut_off}, + { "CELL_VOLTAGE_THRESHOLD", T_UINT16, 250, 350, 300, &low_cell_volt_cutoff}, + { "BRAKE_ON_STOP", T_BOOL, 0, 1, 1, &eepromBuffer.brake_on_stop}, + { "DRIVING_BRAKE_STRENGTH", T_UINT8, 1, 10, 10, &eepromBuffer.driving_brake_strength}, + { "DRAG_BRAKE_STRENGTH", T_UINT8, 1, 10, 10, &eepromBuffer.drag_brake_strength}, + { "INPUT_SIGNAL_TYPE", T_UINT8, 0, 5, 5, &eepromBuffer.input_type}, + { "INPUT_FILTER_HZ", T_UINT8, 0, 100, 0, &eepromBuffer.can.filter_hz}, + { "STARTUP_TUNE", T_STRING,0, 4, 0, &eepromBuffer.tune}, +}; + +/* + get settings from eeprom +*/ +static void load_settings(void) +{ + /* + run through parameters checking for those in the eepromBuffer + structure. For those parameters reset to default if out of + range. This allows the use of a defaults array that does not + include the CAN parameters + */ + for (uint8_t i=0; ivtype) { + case T_BOOL: + case T_UINT8: { + uint8_t *pvalue = (uint8_t *)p->ptr; + uint8_t max_value = p->max_value; + if (pvalue == &eepromBuffer.limits.current) { + max_value = max_value / 2; + } + if (*pvalue < p->min_value || *pvalue > max_value) { + *pvalue = p->default_value; + } + break; + } + case T_UINT16: + case T_STRING: + break; + } + } +} + +/* + save settings to flash + */ +static void save_settings(void) +{ + saveEEpromSettings(); + can_printf("saved settings"); +} + +/* + hold our node status as a static variable. It will be updated on any errors +*/ +static struct uavcan_protocol_NodeStatus node_status; + +static bool safe_to_write_settings(void) +{ + return !running || newinput == 0; +} + +/* + 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; +#ifdef ARTERY + uint16_t cnt = UTILITY_TIMER->cval; +#else + uint16_t cnt = UTILITY_TIMER->CNT; +#endif + 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, 0x01, 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 +}; + +// printf to CAN LogMessage for debugging +static void can_printf(const char *fmt, ...) +{ + struct uavcan_protocol_debug_LogMessage pkt; + memset(&pkt, 0, sizeof(pkt)); + + uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE]; + va_list ap; + va_start(ap, fmt); + uint32_t n = vsnprintf((char*)pkt.text.data, sizeof(pkt.text.data), fmt, ap); + va_end(ap); + pkt.text.len = MIN(n, sizeof(pkt.text.data)); + + 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 GetSet request +*/ +static void handle_param_GetSet(CanardInstance* ins, CanardRxTransfer* transfer) +{ + struct uavcan_protocol_param_GetSetRequest req; + if (uavcan_protocol_param_GetSetRequest_decode(transfer, &req)) { + return; + } + + volatile const struct parameter *p = NULL; + if (req.name.len != 0) { + for (uint16_t i=0; ivtype) { + case T_UINT8: { + uint8_t *ptr8 = (uint8_t *)p->ptr; + if (ptr8 == &eepromBuffer.limits.current) { + *ptr8 = req.value.integer_value / 2; + } else { + *ptr8 = req.value.integer_value; + } + break; + } + case T_UINT16: { + uint16_t *ptr16 = (uint16_t *)p->ptr; + *ptr16 = req.value.integer_value; + if (ptr16 == &motor_kv) { + eepromBuffer.motor_kv = (uint8_t)((*(uint16_t *)p->ptr - 20) / 40); + } else if (ptr16 == &low_cell_volt_cutoff) { + eepromBuffer.low_cell_volt_cutoff = (uint8_t)(*ptr16 - 250); + } + break; + } + case T_BOOL: + *(uint8_t *)p->ptr = req.value.boolean_value?1:0; + break; + case T_STRING: + if (req.value.union_tag == UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE) { + if (p->ptr == (void*)eepromBuffer.tune) { + for (size_t i = 0; i < sizeof(eepromBuffer.tune); i++) { + if (i < req.value.string_value.len) { + eepromBuffer.tune[i] = req.value.string_value.data[i]; + } else { + eepromBuffer.tune[i] = 0xFF; + } + } + } + } + break; + default: + return; + } + + if (last_dir_reversed != eepromBuffer.dir_reversed || + last_bi_direction != eepromBuffer.bi_direction) { + // make dir_reversed and bi_direction change work without + // reboot + forward = 1 - eepromBuffer.dir_reversed; + running = 0; + armed = 0; + set_input(0); + } + } + + /* + for both set and get we reply with the current value + */ + struct uavcan_protocol_param_GetSetResponse pkt; + memset(&pkt, 0, sizeof(pkt)); + + const uint32_t eindex = (uint32_t)(((const uint8_t *)p->ptr) - &eepromBuffer.buffer[0]); + + if (p != NULL) { + switch (p->vtype) { + case T_UINT8: + pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; + pkt.value.integer_value = *(uint8_t *)p->ptr; + pkt.default_value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; + if (eindex < sizeof(default_settings)) { + pkt.default_value.integer_value = default_settings[eindex]; + } else { + pkt.default_value.integer_value = p->default_value; + } + pkt.max_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE; + pkt.max_value.integer_value = p->max_value; + pkt.min_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE; + pkt.min_value.integer_value = p->min_value; + + // special case scaling + if ((uint8_t *)p->ptr == &eepromBuffer.limits.current) { + pkt.default_value.integer_value *= 2; + pkt.value.integer_value *= 2; + } + break; + case T_UINT16: + pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; + pkt.value.integer_value = *(uint16_t *)p->ptr; + pkt.default_value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; + pkt.default_value.integer_value = p->default_value; + pkt.max_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE; + pkt.max_value.integer_value = p->max_value; + pkt.min_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE; + pkt.min_value.integer_value = p->min_value; + break; + case T_STRING: + pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE; + if (p->ptr == (void*)eepromBuffer.tune) { + pkt.value.string_value.len = sizeof(eepromBuffer.tune); + if (pkt.value.string_value.len > sizeof(pkt.value.string_value.data)) { + pkt.value.string_value.len = sizeof(pkt.value.string_value.data); + } + for (size_t i=0; i < pkt.value.string_value.len; i++) { + pkt.value.string_value.data[i] = eepromBuffer.tune[i]; + } + } + break; + case T_BOOL: + pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_BOOLEAN_VALUE; + pkt.value.boolean_value = (*(uint8_t *)p->ptr)?true:false; + pkt.default_value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_BOOLEAN_VALUE; + if (eindex < sizeof(default_settings)) { + pkt.default_value.boolean_value = !!default_settings[eindex]; + } else { + pkt.default_value.boolean_value = !!p->default_value; + } + break; + default: + return; + } + pkt.name.len = strlen(p->name); + strcpy((char *)pkt.name.data, p->name); + } + + uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE]; + uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer); + + canardRequestOrRespond(ins, + transfer->source_node_id, + UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE, + UAVCAN_PROTOCOL_PARAM_GETSET_ID, + &transfer->transfer_id, + transfer->priority, + CanardResponse, + &buffer[0], + total_size); +} + +/* + 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) { + if (!safe_to_write_settings()) { + can_printf("No erase while running"); + } else { + can_printf("resetting to defaults"); + memset(eepromBuffer.buffer, 0xff, sizeof(eepromBuffer.buffer)); + memcpy(eepromBuffer.buffer, default_settings, sizeof(default_settings)); + save_flash_nolib(eepromBuffer.buffer, sizeof(eepromBuffer.buffer), eeprom_address); + loadEEpromSettings(); + load_settings(); + pkt.ok = true; + } + } + if (req.opcode == UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_SAVE) { + if (!safe_to_write_settings()) { + can_printf("No save while running"); + } else { + save_settings(); + 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) +{ + // reboot the ESC + allOff(); + set_rtc_backup_register(0, 0); + 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 = VERSION_MAJOR; + pkt.software_version.minor = VERSION_MINOR; + 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, FIRMWARE_NAME, 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); +} + +extern void transfercomplete(); +extern void setInput(); + + +/* + process throttle input from DroneCAN + */ +static void set_input(uint16_t input) +{ + if (!armed && input != 0 && eepromBuffer.can.require_arming && + dronecan_armed && !eepromBuffer.can.require_zero_throttle) { + // allow restart if unexpected ESC reboot in flight + armed = 1; + } + + const uint16_t unfiltered_input = (dronecan_armed || !eepromBuffer.can.require_arming)? input : 0; + const uint16_t filtered_input = Filter2P_apply(unfiltered_input, eepromBuffer.can.filter_hz, 1000); + + newinput = filtered_input; + last_can_input = unfiltered_input; + inputSet = 1; + + // we must set dshot for bi_direction to work + dshot = eepromBuffer.bi_direction; + + transfercomplete(); + setInput(); + + canstats.num_input++; +} + +/* + handle a ESC RawCommand request +*/ +static void handle_RawCommand(CanardInstance *ins, CanardRxTransfer *transfer) +{ + struct uavcan_equipment_esc_RawCommand cmd; + if (uavcan_equipment_esc_RawCommand_decode(transfer, &cmd)) { + return; + } + // see if it is for us + if (cmd.cmd.len <= eepromBuffer.can.esc_index) { + return; + } + + // throttle demand is a value from -8191 to 8191. Negative values + // are for reverse throttle + const int16_t input_can = cmd.cmd.data[(unsigned)eepromBuffer.can.esc_index]; + + /* + we need to map onto the AM32 expected range, which is a 11 bit number, where: + 0: off + 1-46: special codes + 47-2047: throttle + */ + uint16_t this_input = 0; + if (input_can == 0) { + this_input = 0; + } else if (eepromBuffer.bi_direction) { + const float scaled_value = input_can * (1000.0 / 8192); + if (scaled_value >= 0) { + this_input = (uint16_t)(47 + scaled_value); + } else { + this_input = (uint16_t)(47 + (1000 - scaled_value)); + } + } else if (input_can > 0) { + const float scaled_value = input_can * (2000.0 / 8192); + this_input = (uint16_t)(47 + scaled_value); + } + + const uint64_t ts = micros64(); + canstats.num_commands++; + canstats.total_commands++; + canstats.last_raw_command_us = ts; + + set_input(this_input); +} + +/* + handle ArmingStatus messages +*/ +static void handle_ArmingStatus(CanardInstance *ins, CanardRxTransfer *transfer) +{ + struct uavcan_equipment_safety_ArmingStatus cmd; + if (uavcan_equipment_safety_ArmingStatus_decode(transfer, &cmd)) { + return; + } + + dronecan_armed = (cmd.status == UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_FULLY_ARMED); + if (!dronecan_armed && eepromBuffer.can.require_arming && canstats.last_raw_command_us != 0) { + set_input(0); + } +} + +/* + handle a BeginFirmwareUpdate request from a management tool like + DroneCAN GUI tool or MissionPlanner + */ +static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* transfer) +{ + if (!safe_to_write_settings()) { + can_printf("No update while running"); + return; + } + + struct uavcan_protocol_file_BeginFirmwareUpdateRequest req; + if (uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(transfer, &req)) { + return; + } + + sys_can_disable_IRQ(); + + uint32_t reg[2] = {0,0}; + if (req.image_file_remote_path.path.len <= 8) { + // path is normally hashed and fits in 8 bytes, put in rtc backup registers 1 and 2 + memcpy((uint8_t *)reg, 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); + + while (canardPeekTxQueue(&canard) != NULL) { + DroneCAN_processTxQueue(); + } + + // time to transmit + delayMillis(2); + } + + set_rtc_backup_register(1, reg[0]); + set_rtc_backup_register(2, reg[1]); + + // tell the bootloader we are doing fw update + set_rtc_backup_register(0, + (canardGetLocalNodeID(&canard)<<24) | + (transfer->source_node_id<<16) | + RTC_BKUP0_FWUPDATE); + + // reboot and let bootloader handle the request, this means the + // first request doesn't get a reply, and the client re-sends. We + // need this to get the path to the client. We could instead + // define a memory block which is not reset on boot and put the + // path there, but this is simpler + NVIC_SystemReset(); +} + +/* + 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) +{ + // tell main loop we have had signal so we don't reset + signaltimeout = 0; + + canstats.on_receive++; + // 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_PARAM_GETSET_ID: { + handle_param_GetSet(ins, transfer); + break; + } + case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID: { + handle_param_ExecuteOpcode(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; + } + } + } + if (transfer->transfer_type == CanardTransferTypeBroadcast) { + // check if we want to handle a specific broadcast message + switch (transfer->data_type_id) { + case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID: { + handle_RawCommand(ins, transfer); + break; + } + case UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID: { + handle_DNA_Allocation(ins, transfer); + break; + } + case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID: { + handle_ArmingStatus(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) +{ + canstats.should_accept++; + 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_PARAM_GETSET_ID: { + *out_data_type_signature = UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE; + return true; + } + case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID: { + *out_data_type_signature = UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_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; + } + } + } + if (transfer_type == CanardTransferTypeBroadcast) { + // see if we want to handle a specific broadcast packet + switch (data_type_id) { + case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID: { + *out_data_type_signature = UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_SIGNATURE; + return true; + } + case UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID: { + *out_data_type_signature = UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE; + return true; + } + case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID: { + *out_data_type_signature = UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_SIGNATURE; + return 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_OPERATIONAL; + node_status.sub_mode = 0; + + // put number of commands we have received in vendor status since the last NodeStatus + // this means vendor status gives us approximate command rate in commands/second + node_status.vendor_specific_status_code = canstats.num_commands; + canstats.num_commands = 0; + + 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(); +} + +/* + send ESC status at TELEM_RATE Hz +*/ +static void send_ESCStatus(void) +{ + struct uavcan_equipment_esc_Status pkt; + uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE]; + + // make up some synthetic status data + pkt.error_count = 0; + pkt.voltage = battery_voltage * 0.01; + + pkt.current = (current.sum/(float)current.count) * 0.01; + current.sum = 0; + current.count = 0; + + pkt.temperature = C_TO_KELVIN(degrees_celsius); + pkt.rpm = (e_rpm * 200) / eepromBuffer.motor_poles; + pkt.power_rating_pct = 0; // how do we get this? + pkt.esc_index = eepromBuffer.can.esc_index; + + uint32_t len = uavcan_equipment_esc_Status_encode(&pkt, 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_EQUIPMENT_ESC_STATUS_SIGNATURE, + UAVCAN_EQUIPMENT_ESC_STATUS_ID, + &transfer_id, + CANARD_TRANSFER_PRIORITY_LOW, + buffer, + len); +} + +/* + send FlexDebug at DEBUG_RATE Hz +*/ +static void send_FlexDebug(void) +{ + static struct { + uint32_t total_commands; + uint32_t num_input; + } last; + /* + popupate debug1 + */ + debug1.version = 1; + debug1.commutation_interval = commutation_interval; + debug1.auto_advance_level = auto_advance_level; + debug1.num_commands = canstats.total_commands - last.total_commands; + debug1.num_input = canstats.num_input - last.num_input; + debug1.rx_errors = canstats.rx_errors; + debug1.rxframe_error = canstats.rxframe_error; + debug1.rx_ecode = canstats.rx_ecode; + + last.num_input = canstats.num_input; + last.total_commands = canstats.total_commands; + + struct dronecan_protocol_FlexDebug pkt; + uint8_t buffer[DRONECAN_PROTOCOL_FLEXDEBUG_MAX_SIZE]; + + pkt.id = DRONECAN_PROTOCOL_FLEXDEBUG_AM32_RESERVE_START+0; + pkt.u8.len = sizeof(debug1); + memcpy(pkt.u8.data, (const uint8_t *)&debug1, sizeof(debug1)); + uint32_t len = dronecan_protocol_FlexDebug_encode(&pkt, buffer); + + static uint8_t transfer_id; + + canardBroadcast(&canard, + DRONECAN_PROTOCOL_FLEXDEBUG_SIGNATURE, + DRONECAN_PROTOCOL_FLEXDEBUG_ID, + &transfer_id, + CANARD_TRANSFER_PRIORITY_LOW, + buffer, + len); +} + + +/* + receive one frame, only called from interrupt context +*/ +void DroneCAN_receiveFrame(void) +{ + CanardCANFrame rx_frame = {0}; + while (sys_can_receive(&rx_frame) > 0) { + canstats.num_receive++; + int ecode = canardHandleRxFrame(&canard, &rx_frame, micros64()); + if (ecode != CANARD_OK && ecode != -CANARD_ERROR_RX_NOT_WANTED) { + canstats.rx_ecode = ecode; + canstats.rxframe_error++; + } + } +} + +/* + 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); + } +} + +static void DroneCAN_Startup(void) +{ + load_settings(); + + 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 (eepromBuffer.can.can_node != 0) { + canardSetLocalNodeID(&canard, eepromBuffer.can.can_node); + } + + // initialise low level CAN peripheral hardware + sys_can_init(); + + if (eepromBuffer.input_type == DRONECAN_IN) { + /* + disable interrupts for DShot and PWM + */ +#ifdef MCU_L431 + NVIC_DisableIRQ(DMA1_Channel5_IRQn); + NVIC_DisableIRQ(EXTI15_10_IRQn); + EXTI->IMR1 &= ~(1U << 15); +#elif defined(MCU_AT415) + NVIC_DisableIRQ(DMA1_Channel6_IRQn); + NVIC_DisableIRQ(EXINT15_10_IRQn); + EXINT->inten &= ~EXINT_LINE_15; +#else + #error "unsupported MCU" +#endif + } + +} + +void DroneCAN_update() +{ + sys_can_disable_IRQ(); + + static uint64_t next_1hz_service_at; + static uint64_t next_telem_service_at; + static uint64_t next_flexdebug_at; + if (!done_startup) { + DroneCAN_Startup(); + done_startup = true; + set_rtc_backup_register(0, RTC_BKUP0_BOOTED); + } + + if (canstats.on_receive == 5) { + // indicate to bootloader that we were fully operational + set_rtc_backup_register(0, RTC_BKUP0_SIGNAL); + } + + 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; + } + + const uint64_t ts = micros64(); + + if (ts >= next_1hz_service_at) { + next_1hz_service_at += 1000000ULL; + process1HzTasks(ts); + } + if (eepromBuffer.can.telem_rate > 0 && ts >= next_telem_service_at) { + next_telem_service_at += 1000000ULL/eepromBuffer.can.telem_rate; + send_ESCStatus(); + } + if (eepromBuffer.can.debug_rate > 0 && ts >= next_flexdebug_at) { + next_flexdebug_at += 1000000ULL/eepromBuffer.can.debug_rate; + send_FlexDebug(); + } + + DroneCAN_processTxQueue(); + + if (canstats.last_raw_command_us != 0 && ts - canstats.last_raw_command_us > 250000ULL) { + /* + we have stopped getting CAN RawCommand, zero input + */ + canstats.last_raw_command_us = 0; + set_input(0); + } + if (ts - canstats.last_raw_command_us > TARGET_PERIOD_US) { + // ensure at least 1kHz signal is seen by main code + set_input(last_can_input); + canstats.last_raw_command_us = ts; + } + + sys_can_enable_IRQ(); + + // keep summed current for averaging + current.sum += actual_current; + current.count++; +} + +bool DroneCAN_active(void) +{ + return canstats.total_commands != 0; +} + +#endif // DRONECAN_SUPPORT diff --git a/Src/DroneCAN/DroneCAN.h b/Src/DroneCAN/DroneCAN.h new file mode 100644 index 00000000..d3dbfd42 --- /dev/null +++ b/Src/DroneCAN/DroneCAN.h @@ -0,0 +1,10 @@ +#pragma once + +#include + +#if DRONECAN_SUPPORT +void DroneCAN_Init(void); +void DroneCAN_update(); +bool DroneCAN_active(); + +#endif // DRONECAN_SUPPORT diff --git a/Src/DroneCAN/dsdl_generated/dronecan_msgs.h b/Src/DroneCAN/dsdl_generated/dronecan_msgs.h new file mode 100644 index 00000000..9df54132 --- /dev/null +++ b/Src/DroneCAN/dsdl_generated/dronecan_msgs.h @@ -0,0 +1,58 @@ +#pragma once +#include "dronecan.protocol.FlexDebug.h" +#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/Src/DroneCAN/dsdl_generated/include/dronecan.protocol.FlexDebug.h b/Src/DroneCAN/dsdl_generated/include/dronecan.protocol.FlexDebug.h new file mode 100644 index 00000000..351958b3 --- /dev/null +++ b/Src/DroneCAN/dsdl_generated/include/dronecan.protocol.FlexDebug.h @@ -0,0 +1,105 @@ +#pragma once +#include +#include +#include + + +#define DRONECAN_PROTOCOL_FLEXDEBUG_MAX_SIZE 258 +#define DRONECAN_PROTOCOL_FLEXDEBUG_SIGNATURE (0xECA60382FF038F39ULL) +#define DRONECAN_PROTOCOL_FLEXDEBUG_ID 16371 + +#define DRONECAN_PROTOCOL_FLEXDEBUG_RESERVATION_SIZE 10 +#define DRONECAN_PROTOCOL_FLEXDEBUG_AM32_RESERVE_START 100 + +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) +class dronecan_protocol_FlexDebug_cxx_iface; +#endif + +struct dronecan_protocol_FlexDebug { +#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS) + using cxx_iface = dronecan_protocol_FlexDebug_cxx_iface; +#endif + uint16_t id; + struct { uint8_t len; uint8_t data[255]; }u8; +}; + +#ifdef __cplusplus +extern "C" +{ +#endif + +uint32_t dronecan_protocol_FlexDebug_encode(struct dronecan_protocol_FlexDebug* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +); +bool dronecan_protocol_FlexDebug_decode(const CanardRxTransfer* transfer, struct dronecan_protocol_FlexDebug* msg); + +#if defined(CANARD_DSDLC_INTERNAL) +static inline void _dronecan_protocol_FlexDebug_encode(uint8_t* buffer, uint32_t* bit_ofs, struct dronecan_protocol_FlexDebug* msg, bool tao); +static inline bool _dronecan_protocol_FlexDebug_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct dronecan_protocol_FlexDebug* msg, bool tao); +void _dronecan_protocol_FlexDebug_encode(uint8_t* buffer, uint32_t* bit_ofs, struct dronecan_protocol_FlexDebug* msg, bool tao) { + (void)buffer; + (void)bit_ofs; + (void)msg; + (void)tao; + + canardEncodeScalar(buffer, *bit_ofs, 16, &msg->id); + *bit_ofs += 16; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + const uint8_t u8_len = msg->u8.len > 255 ? 255 : msg->u8.len; +#pragma GCC diagnostic pop + if (!tao) { + canardEncodeScalar(buffer, *bit_ofs, 8, &u8_len); + *bit_ofs += 8; + } + for (size_t i=0; i < u8_len; i++) { + canardEncodeScalar(buffer, *bit_ofs, 8, &msg->u8.data[i]); + *bit_ofs += 8; + } +} + +/* + decode dronecan_protocol_FlexDebug, return true on failure, false on success +*/ +bool _dronecan_protocol_FlexDebug_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct dronecan_protocol_FlexDebug* msg, bool tao) { + (void)transfer; + (void)bit_ofs; + (void)msg; + (void)tao; + canardDecodeScalar(transfer, *bit_ofs, 16, false, &msg->id); + *bit_ofs += 16; + + if (!tao) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->u8.len); + *bit_ofs += 8; + } else { + msg->u8.len = ((transfer->payload_len*8)-*bit_ofs)/8; + } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wtype-limits" + if (msg->u8.len > 255) { + return true; /* invalid value */ + } +#pragma GCC diagnostic pop + for (size_t i=0; i < msg->u8.len; i++) { + canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->u8.data[i]); + *bit_ofs += 8; + } + + return false; /* success */ +} +#endif +#ifdef CANARD_DSDLC_TEST_BUILD +struct dronecan_protocol_FlexDebug sample_dronecan_protocol_FlexDebug_msg(void); +#endif +#ifdef __cplusplus +} // extern "C" + +#ifdef DRONECAN_CXX_WRAPPERS +#include +BROADCAST_MESSAGE_CXX_IFACE(dronecan_protocol_FlexDebug, DRONECAN_PROTOCOL_FLEXDEBUG_ID, DRONECAN_PROTOCOL_FLEXDEBUG_SIGNATURE, DRONECAN_PROTOCOL_FLEXDEBUG_MAX_SIZE); +#endif +#endif diff --git a/Src/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.RPMCommand.h b/Src/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.RPMCommand.h new file mode 100644 index 00000000..b66bbc65 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.RawCommand.h b/Src/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.RawCommand.h new file mode 100644 index 00000000..8c1cc56b --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.Status.h b/Src/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.Status.h new file mode 100644 index 00000000..cef7bb64 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.StatusExtended.h b/Src/DroneCAN/dsdl_generated/include/uavcan.equipment.esc.StatusExtended.h new file mode 100644 index 00000000..bbf9d4ef --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.equipment.safety.ArmingStatus.h b/Src/DroneCAN/dsdl_generated/include/uavcan.equipment.safety.ArmingStatus.h new file mode 100644 index 00000000..d6232ae2 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo.h new file mode 100644 index 00000000..242c1bfe --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo_req.h new file mode 100644 index 00000000..c778974a --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.GetNodeInfo_res.h new file mode 100644 index 00000000..0fe1abf8 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.HardwareVersion.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.HardwareVersion.h new file mode 100644 index 00000000..a3d14b3e --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.NodeStatus.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.NodeStatus.h new file mode 100644 index 00000000..854469dd --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode.h new file mode 100644 index 00000000..db56f6f5 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode_req.h new file mode 100644 index 00000000..953302b7 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.RestartNode_res.h new file mode 100644 index 00000000..fe653f86 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.SoftwareVersion.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.SoftwareVersion.h new file mode 100644 index 00000000..c965cc0c --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.KeyValue.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.KeyValue.h new file mode 100644 index 00000000..acd1aa23 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.LogLevel.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.LogLevel.h new file mode 100644 index 00000000..237b8a34 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.LogMessage.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.debug.LogMessage.h new file mode 100644 index 00000000..034ba674 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.Allocation.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.Allocation.h new file mode 100644 index 00000000..b68f930c --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries.h new file mode 100644 index 00000000..a3ad5688 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.h new file mode 100644 index 00000000..0676005f --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.h new file mode 100644 index 00000000..bd99a0ac --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.Discovery.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.Discovery.h new file mode 100644 index 00000000..8596b5eb --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.Entry.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.Entry.h new file mode 100644 index 00000000..bbb05d1b --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote.h new file mode 100644 index 00000000..8a4da271 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote_req.h new file mode 100644 index 00000000..c51d4420 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.dynamic_node_id.server.RequestVote_res.h new file mode 100644 index 00000000..a1e79cac --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate.h new file mode 100644 index 00000000..ab0678e6 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate_req.h new file mode 100644 index 00000000..7e012776 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.BeginFirmwareUpdate_res.h new file mode 100644 index 00000000..510920d4 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete.h new file mode 100644 index 00000000..f248e181 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete_req.h new file mode 100644 index 00000000..2de184e0 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Delete_res.h new file mode 100644 index 00000000..28e2d740 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.EntryType.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.EntryType.h new file mode 100644 index 00000000..ae475bc6 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Error.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Error.h new file mode 100644 index 00000000..f5f6176b --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo.h new file mode 100644 index 00000000..f04fe6fd --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo_req.h new file mode 100644 index 00000000..46532417 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetDirectoryEntryInfo_res.h new file mode 100644 index 00000000..ad9432dc --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo.h new file mode 100644 index 00000000..96ef7506 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo_req.h new file mode 100644 index 00000000..b629fc3e --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.GetInfo_res.h new file mode 100644 index 00000000..cc408fcf --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Path.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Path.h new file mode 100644 index 00000000..025cfb1f --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read.h new file mode 100644 index 00000000..8d0d55e7 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read_req.h new file mode 100644 index 00000000..d2978a6a --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Read_res.h new file mode 100644 index 00000000..f2a814e4 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write.h new file mode 100644 index 00000000..348e174c --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write_req.h new file mode 100644 index 00000000..022a9da8 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.file.Write_res.h new file mode 100644 index 00000000..76049df9 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.Empty.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.Empty.h new file mode 100644 index 00000000..e05acccc --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode.h new file mode 100644 index 00000000..a15c5af2 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode_req.h new file mode 100644 index 00000000..d01e3fa1 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.ExecuteOpcode_res.h new file mode 100644 index 00000000..3b6a85d0 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet.h new file mode 100644 index 00000000..21ae8cb5 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet_req.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet_req.h new file mode 100644 index 00000000..108a4fec --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet_res.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.GetSet_res.h new file mode 100644 index 00000000..0e29be83 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.NumericValue.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.NumericValue.h new file mode 100644 index 00000000..462f1da8 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.Value.h b/Src/DroneCAN/dsdl_generated/include/uavcan.protocol.param.Value.h new file mode 100644 index 00000000..a46b3ea0 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/dronecan.protocol.FlexDebug.c b/Src/DroneCAN/dsdl_generated/src/dronecan.protocol.FlexDebug.c new file mode 100644 index 00000000..942b85d0 --- /dev/null +++ b/Src/DroneCAN/dsdl_generated/src/dronecan.protocol.FlexDebug.c @@ -0,0 +1,68 @@ +#define CANARD_DSDLC_INTERNAL +#include +#include + +#ifdef CANARD_DSDLC_TEST_BUILD +#include +#endif + +uint32_t dronecan_protocol_FlexDebug_encode(struct dronecan_protocol_FlexDebug* msg, uint8_t* buffer +#if CANARD_ENABLE_TAO_OPTION + , bool tao +#endif +) { + uint32_t bit_ofs = 0; + memset(buffer, 0, DRONECAN_PROTOCOL_FLEXDEBUG_MAX_SIZE); + _dronecan_protocol_FlexDebug_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 dronecan_protocol_FlexDebug_decode(const CanardRxTransfer* transfer, struct dronecan_protocol_FlexDebug* msg) { +#if CANARD_ENABLE_TAO_OPTION + if (transfer->tao && (transfer->payload_len > DRONECAN_PROTOCOL_FLEXDEBUG_MAX_SIZE)) { + return true; /* invalid payload length */ + } +#endif + uint32_t bit_ofs = 0; + if (_dronecan_protocol_FlexDebug_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 dronecan_protocol_FlexDebug sample_dronecan_protocol_FlexDebug_msg(void) { + struct dronecan_protocol_FlexDebug msg; + + msg.id = (uint16_t)random_bitlen_unsigned_val(16); + msg.u8.len = (uint8_t)random_range_unsigned_val(0, 255); + for (size_t i=0; i < msg.u8.len; i++) { + msg.u8.data[i] = (uint8_t)random_bitlen_unsigned_val(8); + } + return msg; +} +#endif diff --git a/Src/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.RPMCommand.c b/Src/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.RPMCommand.c new file mode 100644 index 00000000..c6c12491 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.RawCommand.c b/Src/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.RawCommand.c new file mode 100644 index 00000000..40e6e1ff --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.Status.c b/Src/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.Status.c new file mode 100644 index 00000000..3a7d8530 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.StatusExtended.c b/Src/DroneCAN/dsdl_generated/src/uavcan.equipment.esc.StatusExtended.c new file mode 100644 index 00000000..46dbac5b --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.equipment.safety.ArmingStatus.c b/Src/DroneCAN/dsdl_generated/src/uavcan.equipment.safety.ArmingStatus.c new file mode 100644 index 00000000..e5f4b6be --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.GetNodeInfo_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.GetNodeInfo_req.c new file mode 100644 index 00000000..f10b60bb --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.GetNodeInfo_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.GetNodeInfo_res.c new file mode 100644 index 00000000..bdfd1af3 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.HardwareVersion.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.HardwareVersion.c new file mode 100644 index 00000000..ead23919 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.NodeStatus.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.NodeStatus.c new file mode 100644 index 00000000..6d5ece0d --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.RestartNode_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.RestartNode_req.c new file mode 100644 index 00000000..19b13a4a --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.RestartNode_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.RestartNode_res.c new file mode 100644 index 00000000..42d5105a --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.SoftwareVersion.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.SoftwareVersion.c new file mode 100644 index 00000000..6fe34196 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.KeyValue.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.KeyValue.c new file mode 100644 index 00000000..006796d5 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.LogLevel.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.LogLevel.c new file mode 100644 index 00000000..9259de44 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.LogMessage.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.debug.LogMessage.c new file mode 100644 index 00000000..85e2cd58 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.Allocation.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.Allocation.c new file mode 100644 index 00000000..7029c2cf --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.c new file mode 100644 index 00000000..1a88f2a8 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.c new file mode 100644 index 00000000..ffb13308 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.Discovery.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.Discovery.c new file mode 100644 index 00000000..c5a53997 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.Entry.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.Entry.c new file mode 100644 index 00000000..9766f42f --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.RequestVote_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.RequestVote_req.c new file mode 100644 index 00000000..5bf5c2b1 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.RequestVote_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.dynamic_node_id.server.RequestVote_res.c new file mode 100644 index 00000000..f4e35e74 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.BeginFirmwareUpdate_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.BeginFirmwareUpdate_req.c new file mode 100644 index 00000000..fa7f4b86 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.BeginFirmwareUpdate_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.BeginFirmwareUpdate_res.c new file mode 100644 index 00000000..898feaf5 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Delete_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Delete_req.c new file mode 100644 index 00000000..43f9414d --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Delete_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Delete_res.c new file mode 100644 index 00000000..37508d2d --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.EntryType.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.EntryType.c new file mode 100644 index 00000000..971bc078 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Error.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Error.c new file mode 100644 index 00000000..c3c2a2b2 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetDirectoryEntryInfo_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetDirectoryEntryInfo_req.c new file mode 100644 index 00000000..deeb8f17 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetDirectoryEntryInfo_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetDirectoryEntryInfo_res.c new file mode 100644 index 00000000..67c41158 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetInfo_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetInfo_req.c new file mode 100644 index 00000000..161917fb --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetInfo_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.GetInfo_res.c new file mode 100644 index 00000000..c250739f --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Path.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Path.c new file mode 100644 index 00000000..a6857f94 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Read_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Read_req.c new file mode 100644 index 00000000..f57e4360 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Read_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Read_res.c new file mode 100644 index 00000000..b7cdf92d --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Write_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Write_req.c new file mode 100644 index 00000000..78ead570 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Write_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.file.Write_res.c new file mode 100644 index 00000000..2b434abf --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.Empty.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.Empty.c new file mode 100644 index 00000000..245e7aa7 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.ExecuteOpcode_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.ExecuteOpcode_req.c new file mode 100644 index 00000000..173bba3c --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.ExecuteOpcode_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.ExecuteOpcode_res.c new file mode 100644 index 00000000..bed38ecd --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.GetSet_req.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.GetSet_req.c new file mode 100644 index 00000000..dbbb2d5b --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.GetSet_res.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.GetSet_res.c new file mode 100644 index 00000000..ca0676f4 --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.NumericValue.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.NumericValue.c new file mode 100644 index 00000000..439d816f --- /dev/null +++ b/Src/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/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.Value.c b/Src/DroneCAN/dsdl_generated/src/uavcan.protocol.param.Value.c new file mode 100644 index 00000000..b8ad2646 --- /dev/null +++ b/Src/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/Src/DroneCAN/filter.c b/Src/DroneCAN/filter.c new file mode 100644 index 00000000..668d28d0 --- /dev/null +++ b/Src/DroneCAN/filter.c @@ -0,0 +1,72 @@ +/* + a 2 pole filter applied to RawCommand to provide a configurable + acceleration filter + + Based on ArduPilot LowPassFilter2p.cpp + */ + +#include + +struct Filter2P { + float cutoff_freq; + float sample_freq; + float a1; + float a2; + float b0; + float b1; + float b2; + + float _delay_element_1; + float _delay_element_2; +}; + +static struct Filter2P filter; + +#define MIN(a,b) ((a)<(b)?(a):(b)) + +static void Filter2P_setup(float sample_freq, float cutoff_freq) +{ + // Keep well under Nyquist limit + filter.cutoff_freq = MIN(cutoff_freq, sample_freq * 0.4); + filter.sample_freq = sample_freq; + + const float fr = filter.sample_freq / filter.cutoff_freq; + const float fr_scaled = M_PI/fr; + const float ohm = tanf(fr_scaled); + const float c = 1.0f+2.0f*cosf(M_PI/4.0f)*ohm + ohm*ohm; + + filter.b0 = ohm*ohm/c; + filter.b1 = 2.0f*filter.b0; + filter.b2 = filter.b0; + filter.a1 = 2.0f*(ohm*ohm-1.0f)/c; + filter.a2 = (1.0f-2.0f*cosf(M_PI/4.0f)*ohm+ohm*ohm)/c; +} + +float Filter2P_apply(const float sample, float cutoff_freq, float sample_freq) +{ + if (cutoff_freq <= 0 || sample_freq <= 0) { + // passthru + return sample; + } + + if (filter.cutoff_freq != cutoff_freq || filter.sample_freq != sample_freq) { + Filter2P_setup(sample_freq, cutoff_freq); + filter._delay_element_1 = filter._delay_element_2 = sample * (1.0 / (1 + filter.a1 + filter.a2)); + } + + const float delay_element_0 = sample - filter._delay_element_1 * filter.a1 - filter._delay_element_2 * filter.a2; + const float output = delay_element_0 * filter.b0 + filter._delay_element_1 * filter.b1 + filter._delay_element_2 * filter.b2; + + filter._delay_element_2 = filter._delay_element_1; + filter._delay_element_1 = delay_element_0; + + return output; +} + +/* + unfortunately the maths libraries have an abort() linkage + */ +void abort(void) +{ + __builtin_unreachable(); +} diff --git a/Src/DroneCAN/filter.h b/Src/DroneCAN/filter.h new file mode 100644 index 00000000..8fdc8f93 --- /dev/null +++ b/Src/DroneCAN/filter.h @@ -0,0 +1,7 @@ +/* + a 2 pole filter applied to RawCommand to provide a configurable + acceleration filter + */ +#pragma once + +float Filter2P_apply(const float sample, float cutoff_freq, float sample_rate); diff --git a/Src/DroneCAN/libcanard/LICENSE b/Src/DroneCAN/libcanard/LICENSE new file mode 100644 index 00000000..9c6ac2ed --- /dev/null +++ b/Src/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/Src/DroneCAN/libcanard/README.md b/Src/DroneCAN/libcanard/README.md new file mode 100644 index 00000000..49120253 --- /dev/null +++ b/Src/DroneCAN/libcanard/README.md @@ -0,0 +1,4 @@ +# Libcanard + +This is a subset of +https://github.com/dronecan/libcanard diff --git a/Src/DroneCAN/libcanard/canard.c b/Src/DroneCAN/libcanard/canard.c new file mode 100644 index 00000000..5a27deea --- /dev/null +++ b/Src/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/Src/DroneCAN/libcanard/canard.h b/Src/DroneCAN/libcanard/canard.h new file mode 100644 index 00000000..78b738ad --- /dev/null +++ b/Src/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/Src/DroneCAN/libcanard/canard_internals.h b/Src/DroneCAN/libcanard/canard_internals.h new file mode 100644 index 00000000..c147c941 --- /dev/null +++ b/Src/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/Src/DroneCAN/libcanard/drivers/stm32/README.md b/Src/DroneCAN/libcanard/drivers/stm32/README.md new file mode 100644 index 00000000..db53b250 --- /dev/null +++ b/Src/DroneCAN/libcanard/drivers/stm32/README.md @@ -0,0 +1,54 @@ +# Libcanard Driver for STM32 Microcontrollers + +This is a compact and simple driver for STM32 microcontrollers. +It has no dependencies besides a tiny part of the standard C library, +and can be used with virtually any operating system or on bare metal +(so far it has been tested at least with ChibiOS). + +In theory, the entire family of STM32 should be supported by this driver, +since they all share the same CAN controller IP known as bxCAN. +So far this driver has been tested at least with the following MCU: + +* STM32F091 +* STM32F105 - both CAN1 and CAN2 +* STM32F446 +* STM32F303 - Only CAN1 verified +* Please extend this list if you used it with other MCU. + +## Features + +* Proper handling of the TX queue prevents inner priority inversion. +* Dependency free, works with any OS and on bare metal. +* Compact, suitable for ROM and RAM limited applications (e.g. bootloaders). +* Does not use IRQ and critical sections at all. +* Non-blocking API. +* Supports both CAN1 and CAN2, but only one at a time via a compile time switch. +* Supports hardware acceptance filters. +* Supports proper CAN bus timing configuration in a user friendly way. + +## Caveats + +Some design trade-offs have been made in order to provide the above features. + +* The RX FIFO is only 3 CAN frames deep, +since this is the depth provided by the CAN hardware. +In order to avoid frame loss due to RX overrun, +the following measures should be adopted: + * Use hardware acceptance filters - the driver +provides a convenient API to configure them. + * Read the queue at least every 3x minimum frame transmission intervals. +* The driver does not permit concurrent access from different threads of execution. +* The clocks of the CAN peripheral must be enabled by the application +before the driver is initialized. +The driver cannot do that because this logic is not uniform across the STM32 family. + +Note that it is possible to invoke the driver's API functions from IRQ context, +provided that the application takes care about proper guarding with critical sections. +This approach allows the application to read the RX queue from an external CAN IRQ handler. + +## How to Use + +The driver is so simple its entire documentation is defined in the header file. +Please do endeavor to read it. + +[Use code search to find real life usage examples using the keyword `canard_stm32`](https://github.com/search?q=canard_stm32&type=Code&utf8=%E2%9C%93). diff --git a/Src/DroneCAN/libcanard/drivers/stm32/_internal_bxcan.h b/Src/DroneCAN/libcanard/drivers/stm32/_internal_bxcan.h new file mode 100644 index 00000000..13dd7b59 --- /dev/null +++ b/Src/DroneCAN/libcanard/drivers/stm32/_internal_bxcan.h @@ -0,0 +1,222 @@ +/* + * Copyright (c) 2017 UAVCAN Team + * + * Distributed under the MIT License, available in the file LICENSE. + * + * Author: Pavel Kirienko + */ + +#ifndef CANARD_STM32_BXCAN_H +#define CANARD_STM32_BXCAN_H + +#include + + +typedef struct +{ + volatile uint32_t TIR; + volatile uint32_t TDTR; + volatile uint32_t TDLR; + volatile uint32_t TDHR; +} CanardSTM32TxMailboxType; + +typedef struct +{ + volatile uint32_t RIR; + volatile uint32_t RDTR; + volatile uint32_t RDLR; + volatile uint32_t RDHR; +} CanardSTM32RxMailboxType; + +typedef struct +{ + volatile uint32_t FR1; + volatile uint32_t FR2; +} CanardSTM32FilterRegisterType; + +typedef struct +{ + volatile uint32_t MCR; ///< CAN master control register 0x000 + volatile uint32_t MSR; ///< CAN master status register 0x004 + volatile uint32_t TSR; ///< CAN transmit status register 0x008 + volatile uint32_t RF0R; ///< CAN receive FIFO 0 register 0x00C + volatile uint32_t RF1R; ///< CAN receive FIFO 1 register 0x010 + volatile uint32_t IER; ///< CAN interrupt enable register 0x014 + volatile uint32_t ESR; ///< CAN error status register 0x018 + volatile uint32_t BTR; ///< CAN bit timing register 0x01C + const uint32_t RESERVED0[88]; ///< Reserved 0x020-0x17F + CanardSTM32TxMailboxType TxMailbox[3]; ///< CAN Tx MailBox 0x180-0x1AC + CanardSTM32RxMailboxType RxMailbox[2]; ///< CAN FIFO MailBox 0x1B0-0x1CC + const uint32_t RESERVED1[12]; ///< Reserved 0x1D0-0x1FF + volatile uint32_t FMR; ///< CAN filter master register 0x200 + volatile uint32_t FM1R; ///< CAN filter mode register 0x204 + const uint32_t RESERVED2; ///< Reserved 0x208 + volatile uint32_t FS1R; ///< CAN filter scale register 0x20C + const uint32_t RESERVED3; ///< Reserved 0x210 + volatile uint32_t FFA1R; ///< CAN filter FIFO assignment register 0x214 + const uint32_t RESERVED4; ///< Reserved 0x218 + volatile uint32_t FA1R; ///< CAN filter activation register 0x21C + const uint32_t RESERVED5[8]; ///< Reserved 0x220-0x23F + CanardSTM32FilterRegisterType FilterRegister[28]; ///< CAN Filter Register 0x240-0x31C +} CanardSTM32CANType; + +/** + * CANx instances + */ +#define CANARD_STM32_CAN1 ((volatile CanardSTM32CANType*)0x40006400U) +#define CANARD_STM32_CAN2 ((volatile CanardSTM32CANType*)0x40006800U) + +// CAN master control register + +#define CANARD_STM32_CAN_MCR_INRQ (1U << 0U) // Bit 0: Initialization Request +#define CANARD_STM32_CAN_MCR_SLEEP (1U << 1U) // Bit 1: Sleep Mode Request +#define CANARD_STM32_CAN_MCR_TXFP (1U << 2U) // Bit 2: Transmit FIFO Priority +#define CANARD_STM32_CAN_MCR_RFLM (1U << 3U) // Bit 3: Receive FIFO Locked Mode +#define CANARD_STM32_CAN_MCR_NART (1U << 4U) // Bit 4: No Automatic Retransmission +#define CANARD_STM32_CAN_MCR_AWUM (1U << 5U) // Bit 5: Automatic Wakeup Mode +#define CANARD_STM32_CAN_MCR_ABOM (1U << 6U) // Bit 6: Automatic Bus-Off Management +#define CANARD_STM32_CAN_MCR_TTCM (1U << 7U) // Bit 7: Time Triggered Communication Mode Enable +#define CANARD_STM32_CAN_MCR_RESET (1U << 15U) // Bit 15: bxCAN software master reset +#define CANARD_STM32_CAN_MCR_DBF (1U << 16U) // Bit 16: Debug freeze + +// CAN master status register + +#define CANARD_STM32_CAN_MSR_INAK (1U << 0U) // Bit 0: Initialization Acknowledge +#define CANARD_STM32_CAN_MSR_SLAK (1U << 1U) // Bit 1: Sleep Acknowledge +#define CANARD_STM32_CAN_MSR_ERRI (1U << 2U) // Bit 2: Error Interrupt +#define CANARD_STM32_CAN_MSR_WKUI (1U << 3U) // Bit 3: Wakeup Interrupt +#define CANARD_STM32_CAN_MSR_SLAKI (1U << 4U) // Bit 4: Sleep acknowledge interrupt +#define CANARD_STM32_CAN_MSR_TXM (1U << 8U) // Bit 8: Transmit Mode +#define CANARD_STM32_CAN_MSR_RXM (1U << 9U) // Bit 9: Receive Mode +#define CANARD_STM32_CAN_MSR_SAMP (1U << 10U) // Bit 10: Last Sample Point +#define CANARD_STM32_CAN_MSR_RX (1U << 11U) // Bit 11: CAN Rx Signal + +// CAN transmit status register + +#define CANARD_STM32_CAN_TSR_RQCP0 (1U << 0U) // Bit 0: Request Completed Mailbox 0 +#define CANARD_STM32_CAN_TSR_TXOK0 (1U << 1U) // Bit 1 : Transmission OK of Mailbox 0 +#define CANARD_STM32_CAN_TSR_ALST0 (1U << 2U) // Bit 2 : Arbitration Lost for Mailbox 0 +#define CANARD_STM32_CAN_TSR_TERR0 (1U << 3U) // Bit 3 : Transmission Error of Mailbox 0 +#define CANARD_STM32_CAN_TSR_ABRQ0 (1U << 7U) // Bit 7 : Abort Request for Mailbox 0 +#define CANARD_STM32_CAN_TSR_RQCP1 (1U << 8U) // Bit 8 : Request Completed Mailbox 1 +#define CANARD_STM32_CAN_TSR_TXOK1 (1U << 9U) // Bit 9 : Transmission OK of Mailbox 1 +#define CANARD_STM32_CAN_TSR_ALST1 (1U << 10U) // Bit 10 : Arbitration Lost for Mailbox 1 +#define CANARD_STM32_CAN_TSR_TERR1 (1U << 11U) // Bit 11 : Transmission Error of Mailbox 1 +#define CANARD_STM32_CAN_TSR_ABRQ1 (1U << 15U) // Bit 15 : Abort Request for Mailbox 1 +#define CANARD_STM32_CAN_TSR_RQCP2 (1U << 16U) // Bit 16 : Request Completed Mailbox 2 +#define CANARD_STM32_CAN_TSR_TXOK2 (1U << 17U) // Bit 17 : Transmission OK of Mailbox 2 +#define CANARD_STM32_CAN_TSR_ALST2 (1U << 18U) // Bit 18: Arbitration Lost for Mailbox 2 +#define CANARD_STM32_CAN_TSR_TERR2 (1U << 19U) // Bit 19: Transmission Error of Mailbox 2 +#define CANARD_STM32_CAN_TSR_ABRQ2 (1U << 23U) // Bit 23: Abort Request for Mailbox 2 +#define CANARD_STM32_CAN_TSR_CODE_SHIFT (24U) // Bits 25-24: Mailbox Code +#define CANARD_STM32_CAN_TSR_CODE_MASK (3U << CANARD_STM32_CAN_TSR_CODE_SHIFT) +#define CANARD_STM32_CAN_TSR_TME0 (1U << 26U) // Bit 26: Transmit Mailbox 0 Empty +#define CANARD_STM32_CAN_TSR_TME1 (1U << 27U) // Bit 27: Transmit Mailbox 1 Empty +#define CANARD_STM32_CAN_TSR_TME2 (1U << 28U) // Bit 28: Transmit Mailbox 2 Empty +#define CANARD_STM32_CAN_TSR_LOW0 (1U << 29U) // Bit 29: Lowest Priority Flag for Mailbox 0 +#define CANARD_STM32_CAN_TSR_LOW1 (1U << 30U) // Bit 30: Lowest Priority Flag for Mailbox 1 +#define CANARD_STM32_CAN_TSR_LOW2 (1U << 31U) // Bit 31: Lowest Priority Flag for Mailbox 2 + +// CAN receive FIFO 0/1 registers + +#define CANARD_STM32_CAN_RFR_FMP_SHIFT (0U) // Bits 1-0: FIFO Message Pending +#define CANARD_STM32_CAN_RFR_FMP_MASK (3U << CANARD_STM32_CAN_RFR_FMP_SHIFT) +#define CANARD_STM32_CAN_RFR_FULL (1U << 3U) // Bit 3: FIFO 0 Full +#define CANARD_STM32_CAN_RFR_FOVR (1U << 4U) // Bit 4: FIFO 0 Overrun +#define CANARD_STM32_CAN_RFR_RFOM (1U << 5U) // Bit 5: Release FIFO 0 Output Mailbox + +// CAN interrupt enable register + +#define CANARD_STM32_CAN_IER_TMEIE (1U << 0U) // Bit 0: Transmit Mailbox Empty Interrupt Enable +#define CANARD_STM32_CAN_IER_FMPIE0 (1U << 1U) // Bit 1: FIFO Message Pending Interrupt Enable +#define CANARD_STM32_CAN_IER_FFIE0 (1U << 2U) // Bit 2: FIFO Full Interrupt Enable +#define CANARD_STM32_CAN_IER_FOVIE0 (1U << 3U) // Bit 3: FIFO Overrun Interrupt Enable +#define CANARD_STM32_CAN_IER_FMPIE1 (1U << 4U) // Bit 4: FIFO Message Pending Interrupt Enable +#define CANARD_STM32_CAN_IER_FFIE1 (1U << 5U) // Bit 5: FIFO Full Interrupt Enable +#define CANARD_STM32_CAN_IER_FOVIE1 (1U << 6U) // Bit 6: FIFO Overrun Interrupt Enable +#define CANARD_STM32_CAN_IER_EWGIE (1U << 8U) // Bit 8: Error Warning Interrupt Enable +#define CANARD_STM32_CAN_IER_EPVIE (1U << 9U) // Bit 9: Error Passive Interrupt Enable +#define CANARD_STM32_CAN_IER_BOFIE (1U << 10U) // Bit 10: Bus-Off Interrupt Enable +#define CANARD_STM32_CAN_IER_LECIE (1U << 11U) // Bit 11: Last Error Code Interrupt Enable +#define CANARD_STM32_CAN_IER_ERRIE (1U << 15U) // Bit 15: Error Interrupt Enable +#define CANARD_STM32_CAN_IER_WKUIE (1U << 16U) // Bit 16: Wakeup Interrupt Enable +#define CANARD_STM32_CAN_IER_SLKIE (1U << 17U) // Bit 17: Sleep Interrupt Enable + +// CAN error status register + +#define CANARD_STM32_CAN_ESR_EWGF (1U << 0U) // Bit 0: Error Warning Flag +#define CANARD_STM32_CAN_ESR_EPVF (1U << 1U) // Bit 1: Error Passive Flag +#define CANARD_STM32_CAN_ESR_BOFF (1U << 2U) // Bit 2: Bus-Off Flag +#define CANARD_STM32_CAN_ESR_LEC_SHIFT (4U) // Bits 6-4: Last Error Code +#define CANARD_STM32_CAN_ESR_LEC_MASK (7U << CANARD_STM32_CAN_ESR_LEC_SHIFT) +#define CANARD_STM32_CAN_ESR_NOERROR (0U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 000: No Error +#define CANARD_STM32_CAN_ESR_STUFFERROR (1U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 001: Stuff Error +#define CANARD_STM32_CAN_ESR_FORMERROR (2U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 010: Form Error +#define CANARD_STM32_CAN_ESR_ACKERROR (3U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 011: Acknowledgment Error +#define CANARD_STM32_CAN_ESR_BRECERROR (4U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 100: Bit recessive Error +#define CANARD_STM32_CAN_ESR_BDOMERROR (5U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 101: Bit dominant Error +#define CANARD_STM32_CAN_ESR_CRCERRPR (6U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 110: CRC Error +#define CANARD_STM32_CAN_ESR_SWERROR (7U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 111: Set by software +#define CANARD_STM32_CAN_ESR_TEC_SHIFT (16U) // Bits 23-16: LS byte of the 9-bit Transmit Error Counter +#define CANARD_STM32_CAN_ESR_TEC_MASK (0xFFU << CANARD_STM32_CAN_ESR_TEC_SHIFT) +#define CANARD_STM32_CAN_ESR_REC_SHIFT (24U) // Bits 31-24: Receive Error Counter +#define CANARD_STM32_CAN_ESR_REC_MASK (0xFFU << CANARD_STM32_CAN_ESR_REC_SHIFT) + +// CAN bit timing register + +#define CANARD_STM32_CAN_BTR_BRP_SHIFT (0U) // Bits 9-0: Baud Rate Prescaler +#define CANARD_STM32_CAN_BTR_BRP_MASK (0x03FFU << CANARD_STM32_CAN_BTR_BRP_SHIFT) +#define CANARD_STM32_CAN_BTR_TS1_SHIFT (16U) // Bits 19-16: Time Segment 1 +#define CANARD_STM32_CAN_BTR_TS1_MASK (0x0FU << CANARD_STM32_CAN_BTR_TS1_SHIFT) +#define CANARD_STM32_CAN_BTR_TS2_SHIFT (20U) // Bits 22-20: Time Segment 2 +#define CANARD_STM32_CAN_BTR_TS2_MASK (7U << CANARD_STM32_CAN_BTR_TS2_SHIFT) +#define CANARD_STM32_CAN_BTR_SJW_SHIFT (24U) // Bits 25-24: Resynchronization Jump Width +#define CANARD_STM32_CAN_BTR_SJW_MASK (3U << CANARD_STM32_CAN_BTR_SJW_SHIFT) +#define CANARD_STM32_CAN_BTR_LBKM (1U << 30U) // Bit 30: Loop Back Mode (Debug); +#define CANARD_STM32_CAN_BTR_SILM (1U << 31U) // Bit 31: Silent Mode (Debug); + +#define CANARD_STM32_CAN_BTR_BRP_MAX (1024U) // Maximum BTR value (without decrement); +#define CANARD_STM32_CAN_BTR_TSEG1_MAX (16U) // Maximum TSEG1 value (without decrement); +#define CANARD_STM32_CAN_BTR_TSEG2_MAX (8U) // Maximum TSEG2 value (without decrement); + +// TX mailbox identifier register + +#define CANARD_STM32_CAN_TIR_TXRQ (1U << 0U) // Bit 0: Transmit Mailbox Request +#define CANARD_STM32_CAN_TIR_RTR (1U << 1U) // Bit 1: Remote Transmission Request +#define CANARD_STM32_CAN_TIR_IDE (1U << 2U) // Bit 2: Identifier Extension +#define CANARD_STM32_CAN_TIR_EXID_SHIFT (3U) // Bit 3-31: Extended Identifier +#define CANARD_STM32_CAN_TIR_EXID_MASK (0x1FFFFFFFU << CANARD_STM32_CAN_TIR_EXID_SHIFT) +#define CANARD_STM32_CAN_TIR_STID_SHIFT (21U) // Bits 21-31: Standard Identifier +#define CANARD_STM32_CAN_TIR_STID_MASK (0x07FFU << CANARD_STM32_CAN_TIR_STID_SHIFT) + +// Mailbox data length control and time stamp register + +#define CANARD_STM32_CAN_TDTR_DLC_SHIFT (0U) // Bits 3:0: Data Length Code +#define CANARD_STM32_CAN_TDTR_DLC_MASK (0x0FU << CANARD_STM32_CAN_TDTR_DLC_SHIFT) +#define CANARD_STM32_CAN_TDTR_TGT (1U << 8U) // Bit 8: Transmit Global Time +#define CANARD_STM32_CAN_TDTR_TIME_SHIFT (16U) // Bits 31:16: Message Time Stamp +#define CANARD_STM32_CAN_TDTR_TIME_MASK (0xFFFFU << CANARD_STM32_CAN_TDTR_TIME_SHIFT) + +// Rx FIFO mailbox identifier register + +#define CANARD_STM32_CAN_RIR_RTR (1U << 1U) // Bit 1: Remote Transmission Request +#define CANARD_STM32_CAN_RIR_IDE (1U << 2U) // Bit 2: Identifier Extension +#define CANARD_STM32_CAN_RIR_EXID_SHIFT (3U) // Bit 3-31: Extended Identifier +#define CANARD_STM32_CAN_RIR_EXID_MASK (0x1FFFFFFFU << CANARD_STM32_CAN_RIR_EXID_SHIFT) +#define CANARD_STM32_CAN_RIR_STID_SHIFT (21U) // Bits 21-31: Standard Identifier +#define CANARD_STM32_CAN_RIR_STID_MASK (0x07FFU << CANARD_STM32_CAN_RIR_STID_SHIFT) + +// Receive FIFO mailbox data length control and time stamp register + +#define CANARD_STM32_CAN_RDTR_DLC_SHIFT (0U) // Bits 3:0: Data Length Code +#define CANARD_STM32_CAN_RDTR_DLC_MASK (0x0FU << CANARD_STM32_CAN_RDTR_DLC_SHIFT) +#define CANARD_STM32_CAN_RDTR_FM_SHIFT (8U) // Bits 15-8: Filter Match Index +#define CANARD_STM32_CAN_RDTR_FM_MASK (0xFFU << CANARD_STM32_CAN_RDTR_FM_SHIFT) +#define CANARD_STM32_CAN_RDTR_TIME_SHIFT (16U) // Bits 31:16: Message Time Stamp +#define CANARD_STM32_CAN_RDTR_TIME_MASK (0xFFFFU << CANARD_STM32_CAN_RDTR_TIME_SHIFT) + +// CAN filter master register + +#define CANARD_STM32_CAN_FMR_FINIT (1U << 0U) // Bit 0: Filter Init Mode + +#endif // CANARD_STM32_BXCAN_H diff --git a/Src/DroneCAN/libcanard/drivers/stm32/canard_stm32.c b/Src/DroneCAN/libcanard/drivers/stm32/canard_stm32.c new file mode 100644 index 00000000..9ffbf383 --- /dev/null +++ b/Src/DroneCAN/libcanard/drivers/stm32/canard_stm32.c @@ -0,0 +1,568 @@ +/* + * Copyright (c) 2017 UAVCAN Team + * + * Distributed under the MIT License, available in the file LICENSE. + * + * Author: Pavel Kirienko + */ + +#include "canard_stm32.h" +#include "_internal_bxcan.h" +#include + + +#if CANARD_STM32_USE_CAN2 +# define BXCAN CANARD_STM32_CAN2 +#else +# define BXCAN CANARD_STM32_CAN1 +#endif + +/* + * State variables + */ +static CanardSTM32Stats g_stats; + +static bool g_abort_tx_on_error = false; + + +static bool isFramePriorityHigher(uint32_t a, uint32_t b) +{ + const uint32_t clean_a = a & CANARD_CAN_EXT_ID_MASK; + const uint32_t clean_b = b & CANARD_CAN_EXT_ID_MASK; + + /* + * STD vs EXT - if 11 most significant bits are the same, EXT loses. + */ + const bool ext_a = (a & CANARD_CAN_FRAME_EFF) != 0; + const bool ext_b = (b & CANARD_CAN_FRAME_EFF) != 0; + if (ext_a != ext_b) + { + const uint32_t arb11_a = ext_a ? (clean_a >> 18U) : clean_a; + const uint32_t arb11_b = ext_b ? (clean_b >> 18U) : clean_b; + if (arb11_a != arb11_b) + { + return arb11_a < arb11_b; + } + else + { + return ext_b; + } + } + + /* + * RTR vs Data frame - if frame identifiers and frame types are the same, RTR loses. + */ + const bool rtr_a = (a & CANARD_CAN_FRAME_RTR) != 0; + const bool rtr_b = (b & CANARD_CAN_FRAME_RTR) != 0; + if ((clean_a == clean_b) && (rtr_a != rtr_b)) + { + return rtr_b; + } + + /* + * Plain ID arbitration - greater value loses. + */ + return clean_a < clean_b; +} + +/// Converts libcanard ID value into the bxCAN TX ID register format. +static uint32_t convertFrameIDCanardToRegister(const uint32_t id) +{ + uint32_t out = 0; + + if (id & CANARD_CAN_FRAME_EFF) + { + out = ((id & CANARD_CAN_EXT_ID_MASK) << 3U) | CANARD_STM32_CAN_TIR_IDE; + } + else + { + out = ((id & CANARD_CAN_STD_ID_MASK) << 21U); + } + + if (id & CANARD_CAN_FRAME_RTR) + { + out |= CANARD_STM32_CAN_TIR_RTR; + } + + return out; +} + +/// Converts bxCAN TX/RX (sic! both RX/TX are supported) ID register value into the libcanard ID format. +static uint32_t convertFrameIDRegisterToCanard(const uint32_t id) +{ +#if (CANARD_STM32_CAN_TIR_RTR != CANARD_STM32_CAN_RIR_RTR) ||\ + (CANARD_STM32_CAN_TIR_IDE != CANARD_STM32_CAN_RIR_IDE) +# error "RIR bits do not match TIR bits, TIR --> libcanard conversion is not possible" +#endif + + uint32_t out = 0; + + if ((id & CANARD_STM32_CAN_RIR_IDE) == 0) + { + out = (CANARD_CAN_STD_ID_MASK & (id >> 21U)); + } + else + { + out = (CANARD_CAN_EXT_ID_MASK & (id >> 3U)) | CANARD_CAN_FRAME_EFF; + } + + if ((id & CANARD_STM32_CAN_RIR_RTR) != 0) + { + out |= CANARD_CAN_FRAME_RTR; + } + + return out; +} + + +static bool waitMSRINAKBitStateChange(volatile const CanardSTM32CANType* const bxcan, const bool target_state) +{ + /** + * A properly functioning bus will exhibit 11 consecutive recessive bits at the end of every correct transmission, + * or while the bus is idle. The 11 consecutive recessive bits are made up of: + * 1 bit - acknowledgement delimiter + * 7 bit - end of frame bits + * 3 bit - inter frame space + * This adds up to 11; therefore, it is not really necessary to wait longer than a few frame TX intervals. + */ + static const uint16_t TimeoutMilliseconds = 1000; + + for (uint16_t wait_ack = 0; wait_ack < TimeoutMilliseconds; wait_ack++) + { + const bool state = (bxcan->MSR & CANARD_STM32_CAN_MSR_INAK) != 0; + if (state == target_state) + { + return true; + } + + // Sleep 1 millisecond + usleep(1000); // TODO: This function may be missing on some platforms + } + + return false; +} + + +static void processErrorStatus(void) +{ + /* + * Aborting TX transmissions if abort on error was requested + * Updating error counter + */ + const uint8_t lec = (uint8_t)((BXCAN->ESR & CANARD_STM32_CAN_ESR_LEC_MASK) >> CANARD_STM32_CAN_ESR_LEC_SHIFT); + + if (lec != 0) + { + BXCAN->ESR = 0; // This action does only affect the LEC bits, other bits are read only! + g_stats.error_count++; + + // Abort pending transmissions if auto abort on error is enabled, or if we're in bus off mode + if (g_abort_tx_on_error || (BXCAN->ESR & CANARD_STM32_CAN_ESR_BOFF)) + { + BXCAN->TSR = CANARD_STM32_CAN_TSR_ABRQ0 | CANARD_STM32_CAN_TSR_ABRQ1 | CANARD_STM32_CAN_TSR_ABRQ2; + } + } +} + + +int16_t canardSTM32Init(const CanardSTM32CANTimings* const timings, + const CanardSTM32IfaceMode iface_mode) +{ + /* + * Paranoia time. + */ + if ((iface_mode != CanardSTM32IfaceModeNormal) && + (iface_mode != CanardSTM32IfaceModeSilent) && + (iface_mode != CanardSTM32IfaceModeAutomaticTxAbortOnError)) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + if ((timings == NULL) || + (timings->bit_rate_prescaler < 1) || (timings->bit_rate_prescaler > 1024) || + (timings->max_resynchronization_jump_width < 1) || (timings->max_resynchronization_jump_width > 4) || + (timings->bit_segment_1 < 1) || (timings->bit_segment_1 > 16) || + (timings->bit_segment_2 < 1) || (timings->bit_segment_2 > 8)) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + /* + * Initial setup + */ + memset(&g_stats, 0, sizeof(g_stats)); + + g_abort_tx_on_error = (iface_mode == CanardSTM32IfaceModeAutomaticTxAbortOnError); + +#if CANARD_STM32_USE_CAN2 + // If we're using CAN2, we MUST initialize CAN1 first, because CAN2 is a slave to CAN1. + CANARD_STM32_CAN1->IER = 0; // We need no interrupts + CANARD_STM32_CAN1->MCR &= ~CANARD_STM32_CAN_MCR_SLEEP; // Exit sleep mode + CANARD_STM32_CAN1->MCR |= CANARD_STM32_CAN_MCR_INRQ; // Request init + + if (!waitMSRINAKBitStateChange(CANARD_STM32_CAN1, true)) // Wait for synchronization + { + CANARD_STM32_CAN1->MCR = CANARD_STM32_CAN_MCR_RESET; + return -CANARD_STM32_ERROR_MSR_INAK_NOT_SET; + } + // CAN1 will be left in the initialization mode forever, in this mode it does not affect the bus at all. +#endif + + BXCAN->IER = 0; // We need no interrupts + BXCAN->MCR &= ~CANARD_STM32_CAN_MCR_SLEEP; // Exit sleep mode + BXCAN->MCR |= CANARD_STM32_CAN_MCR_INRQ; // Request init + + if (!waitMSRINAKBitStateChange(BXCAN, true)) // Wait for synchronization + { + BXCAN->MCR = CANARD_STM32_CAN_MCR_RESET; + return -CANARD_STM32_ERROR_MSR_INAK_NOT_SET; + } + + /* + * Hardware initialization (the hardware has already confirmed initialization mode, see above) + */ + BXCAN->MCR = CANARD_STM32_CAN_MCR_ABOM | CANARD_STM32_CAN_MCR_AWUM | CANARD_STM32_CAN_MCR_INRQ; // RM page 648 + + BXCAN->BTR = (((timings->max_resynchronization_jump_width - 1U) & 3U) << 24U) | + (((timings->bit_segment_1 - 1U) & 15U) << 16U) | + (((timings->bit_segment_2 - 1U) & 7U) << 20U) | + ((timings->bit_rate_prescaler - 1U) & 1023U) | + ((iface_mode == CanardSTM32IfaceModeSilent) ? CANARD_STM32_CAN_BTR_SILM : 0); + + CANARD_ASSERT(0 == BXCAN->IER); // Making sure the iterrupts are indeed disabled + + BXCAN->MCR &= ~CANARD_STM32_CAN_MCR_INRQ; // Leave init mode + + if (!waitMSRINAKBitStateChange(BXCAN, false)) + { + BXCAN->MCR = CANARD_STM32_CAN_MCR_RESET; + return -CANARD_STM32_ERROR_MSR_INAK_NOT_CLEARED; + } + + /* + * Default filter configuration. Note that ALL filters are available ONLY via CAN1! + * CAN2 filters are offset by 14. + * We use 14 filters at most always which simplifies the code and ensures compatibility with all + * MCU within the STM32 family. + */ + { + uint32_t fmr = CANARD_STM32_CAN1->FMR & 0xFFFFC0F1U; + fmr |= CANARD_STM32_NUM_ACCEPTANCE_FILTERS << 8U; // CAN2 start bank = 14 (if CAN2 is present) + CANARD_STM32_CAN1->FMR = fmr | CANARD_STM32_CAN_FMR_FINIT; + } + + CANARD_ASSERT(((CANARD_STM32_CAN1->FMR >> 8U) & 0x3FU) == CANARD_STM32_NUM_ACCEPTANCE_FILTERS); + + CANARD_STM32_CAN1->FM1R = 0; // Indentifier Mask mode + CANARD_STM32_CAN1->FS1R = 0x0FFFFFFF; // All 32-bit + + // Filters are alternating between FIFO0 and FIFO1 in order to equalize the load. + // This will cause occasional priority inversion and frame reordering on reception, + // but that is acceptable for UAVCAN, and a majority of other protocols will tolerate + // this too, since there will be no reordering within the same CAN ID. + CANARD_STM32_CAN1->FFA1R = 0x0AAAAAAA; + +#if CANARD_STM32_USE_CAN2 + CANARD_STM32_CAN1->FilterRegister[CANARD_STM32_NUM_ACCEPTANCE_FILTERS].FR1 = 0; + CANARD_STM32_CAN1->FilterRegister[CANARD_STM32_NUM_ACCEPTANCE_FILTERS].FR2 = 0; + CANARD_STM32_CAN1->FA1R = (1 << CANARD_STM32_NUM_ACCEPTANCE_FILTERS); // One filter enabled +#else + CANARD_STM32_CAN1->FilterRegister[0].FR1 = 0; + CANARD_STM32_CAN1->FilterRegister[0].FR2 = 0; + CANARD_STM32_CAN1->FA1R = 1; // One filter enabled +#endif + + CANARD_STM32_CAN1->FMR &= ~CANARD_STM32_CAN_FMR_FINIT; // Leave initialization mode + + return 0; +} + + +int16_t canardSTM32Transmit(const CanardCANFrame* const frame) +{ + if (frame == NULL) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + if (frame->id & CANARD_CAN_FRAME_ERR) + { + return -CANARD_STM32_ERROR_UNSUPPORTED_FRAME_FORMAT; + } + + /* + * Handling error status might free up some slots through aborts + */ + processErrorStatus(); + + /* + * Seeking an empty slot, checking if priority inversion would occur if we enqueued now. + * We can always enqueue safely if all TX mailboxes are free and no transmissions are pending. + */ + uint8_t tx_mailbox = 0xFF; + + static const uint32_t AllTME = CANARD_STM32_CAN_TSR_TME0 | CANARD_STM32_CAN_TSR_TME1 | CANARD_STM32_CAN_TSR_TME2; + + if ((BXCAN->TSR & AllTME) != AllTME) // At least one TX mailbox is used, detailed check is needed + { + const bool tme[3] = + { + (BXCAN->TSR & CANARD_STM32_CAN_TSR_TME0) != 0, + (BXCAN->TSR & CANARD_STM32_CAN_TSR_TME1) != 0, + (BXCAN->TSR & CANARD_STM32_CAN_TSR_TME2) != 0 + }; + + for (uint8_t i = 0; i < 3; i++) + { + if (tme[i]) // This TX mailbox is free, we can use it + { + tx_mailbox = i; + } + else // This TX mailbox is pending, check for priority inversion + { + if (!isFramePriorityHigher(frame->id, convertFrameIDRegisterToCanard(BXCAN->TxMailbox[i].TIR))) + { + // There's a mailbox whose priority is higher or equal the priority of the new frame. + return 0; // Priority inversion would occur! Reject transmission. + } + } + } + + if (tx_mailbox == 0xFF) + { + /* + * All TX mailboxes are busy (this is highly unlikely); at the same time we know that there is no + * higher or equal priority frame that is currently pending. Therefore, priority inversion has + * just happend (sic!), because we can't enqueue the higher priority frame due to all TX mailboxes + * being busy. This scenario is extremely unlikely, because in order for it to happen, the application + * would need to transmit 4 (four) or more CAN frames with different CAN ID ordered from high ID to + * low ID nearly at the same time. For example: + * 1. 0x123 <-- Takes mailbox 0 (or any other) + * 2. 0x122 <-- Takes mailbox 2 (or any other) + * 3. 0x121 <-- Takes mailbox 1 (or any other) + * 4. 0x120 <-- INNER PRIORITY INVERSION HERE (only if all three TX mailboxes are still busy) + * This situation is even less likely to cause any noticeable disruptions on the CAN bus. Despite that, + * it is better to warn the developer about that during debugging, so we fire an assertion failure here. + * It is perfectly safe to remove it. + */ +#if CANARD_STM32_DEBUG_INNER_PRIORITY_INVERSION + CANARD_ASSERT(!"CAN PRIO INV"); +#endif + return 0; + } + } + else // All TX mailboxes are free, use first + { + tx_mailbox = 0; + } + + CANARD_ASSERT(tx_mailbox < 3); // Index check - the value must be correct here + + /* + * By this time we've proved that a priority inversion would not occur, and we've also found a free TX mailbox. + * Therefore it is safe to enqueue the frame now. + */ + volatile CanardSTM32TxMailboxType* const mb = &BXCAN->TxMailbox[tx_mailbox]; + + mb->TDTR = frame->data_len; // DLC equals data length except in CAN FD + + mb->TDHR = (((uint32_t)frame->data[7]) << 24U) | + (((uint32_t)frame->data[6]) << 16U) | + (((uint32_t)frame->data[5]) << 8U) | + (((uint32_t)frame->data[4]) << 0U); + mb->TDLR = (((uint32_t)frame->data[3]) << 24U) | + (((uint32_t)frame->data[2]) << 16U) | + (((uint32_t)frame->data[1]) << 8U) | + (((uint32_t)frame->data[0]) << 0U); + + mb->TIR = convertFrameIDCanardToRegister(frame->id) | CANARD_STM32_CAN_TIR_TXRQ; // Go. + + /* + * The frame is now enqueued and pending transmission. + */ + return 1; +} + + +int16_t canardSTM32Receive(CanardCANFrame* const out_frame) +{ + if (out_frame == NULL) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + static volatile uint32_t* const RFxR[2] = + { + &BXCAN->RF0R, + &BXCAN->RF1R + }; + + /* + * This function must be polled periodically, so we use this opportunity to do it. + */ + processErrorStatus(); + + /* + * Reading the TX FIFO + */ + for (uint_fast8_t i = 0; i < 2; i++) + { + volatile CanardSTM32RxMailboxType* const mb = &BXCAN->RxMailbox[i]; + + if (((*RFxR[i]) & CANARD_STM32_CAN_RFR_FMP_MASK) != 0) + { + if (*RFxR[i] & CANARD_STM32_CAN_RFR_FOVR) + { + g_stats.rx_overflow_count++; + } + + out_frame->id = convertFrameIDRegisterToCanard(mb->RIR); + + out_frame->data_len = (uint8_t)(mb->RDTR & CANARD_STM32_CAN_RDTR_DLC_MASK); + + // Caching to regular (non volatile) memory for faster reads + const uint32_t rdlr = mb->RDLR; + const uint32_t rdhr = mb->RDHR; + + out_frame->data[0] = (uint8_t)(0xFFU & (rdlr >> 0U)); + out_frame->data[1] = (uint8_t)(0xFFU & (rdlr >> 8U)); + out_frame->data[2] = (uint8_t)(0xFFU & (rdlr >> 16U)); + out_frame->data[3] = (uint8_t)(0xFFU & (rdlr >> 24U)); + out_frame->data[4] = (uint8_t)(0xFFU & (rdhr >> 0U)); + out_frame->data[5] = (uint8_t)(0xFFU & (rdhr >> 8U)); + out_frame->data[6] = (uint8_t)(0xFFU & (rdhr >> 16U)); + out_frame->data[7] = (uint8_t)(0xFFU & (rdhr >> 24U)); + + // Release FIFO entry we just read + *RFxR[i] = CANARD_STM32_CAN_RFR_RFOM | CANARD_STM32_CAN_RFR_FOVR | CANARD_STM32_CAN_RFR_FULL; + + // Reading successful + return 1; + } + } + + // No frames to read + return 0; +} + + +int16_t canardSTM32ConfigureAcceptanceFilters(const CanardSTM32AcceptanceFilterConfiguration* const filter_configs, + const uint8_t num_filter_configs) +{ + // Note that num_filter_configs = 0 is a valid configuration, which rejects all frames. + if ((filter_configs == NULL) || + (num_filter_configs > CANARD_STM32_NUM_ACCEPTANCE_FILTERS)) + { + return -CANARD_ERROR_INVALID_ARGUMENT; + } + + /* + * First we disable all filters. This may cause momentary RX frame losses, but the application + * should be able to tolerate that. + */ + CANARD_STM32_CAN1->FA1R = 0; + + /* + * Having filters disabled we can update the configuration. + * Register mapping: FR1 - ID, FR2 - Mask + */ + for (uint8_t i = 0; i < num_filter_configs; i++) + { + /* + * Converting the ID and the Mask into the representation that can be chewed by the hardware. + * If Mask asks us to accept both STDID and EXTID, we need to use EXT mode on the filter, + * otherwise it will reject all EXTID frames. This logic is not documented in the RM. + * + * The logic of the hardware acceptance filters can be described as follows: + * + * accepted = (received_id & filter_mask) == (filter_id & filter_mask) + * + * Where: + * - accepted - if true, the frame will be accepted by the filter. + * - received_id - the CAN ID of the received frame, either 11-bit or 29-bit, with extension bits + * marking extended frames, error frames, etc. + * - filter_id - the value of the filter ID register. + * - filter_mask - the value of the filter mask register. + * + * There are special bits that are not members of the CAN ID field: + * - EFF - set for extended frames (29-bit), cleared for standard frames (11-bit) + * - RTR - like above, indicates Remote Transmission Request frames. + * + * The following truth table summarizes the logic (where: FM - filter mask, FID - filter ID, RID - received + * frame ID, A - true if accepted, X - any state): + * + * FM FID RID A + * 0 X X 1 + * 1 0 0 1 + * 1 1 0 0 + * 1 0 1 0 + * 1 1 1 1 + * + * One would expect that for the purposes of hardware filtering, the special bits should be treated + * in the same way as the real ID bits. However, this is not the case with bxCAN. The following truth + * table has been determined empirically (this behavior was not documented as of 2017): + * + * FM FID RID A + * 0 0 0 1 + * 0 0 1 0 <-- frame rejected! + * 0 1 X 1 + * 1 0 0 1 + * 1 1 0 0 + * 1 0 1 0 + * 1 1 1 1 + */ + uint32_t id = 0; + uint32_t mask = 0; + + const CanardSTM32AcceptanceFilterConfiguration* const cfg = filter_configs + i; + + if ((cfg->id & CANARD_CAN_FRAME_EFF) || !(cfg->mask & CANARD_CAN_FRAME_EFF)) + { + id = (cfg->id & CANARD_CAN_EXT_ID_MASK) << 3U; + mask = (cfg->mask & CANARD_CAN_EXT_ID_MASK) << 3U; + id |= CANARD_STM32_CAN_RIR_IDE; + } + else + { + id = (cfg->id & CANARD_CAN_STD_ID_MASK) << 21U; + mask = (cfg->mask & CANARD_CAN_STD_ID_MASK) << 21U; + } + + if (cfg->id & CANARD_CAN_FRAME_RTR) + { + id |= CANARD_STM32_CAN_RIR_RTR; + } + + if (cfg->mask & CANARD_CAN_FRAME_EFF) + { + mask |= CANARD_STM32_CAN_RIR_IDE; + } + + if (cfg->mask & CANARD_CAN_FRAME_RTR) + { + mask |= CANARD_STM32_CAN_RIR_RTR; + } + + /* + * Applying the converted representation to the registers. + */ + const uint8_t filter_index = +#if CANARD_STM32_USE_CAN2 + (uint8_t)(i + CANARD_STM32_NUM_ACCEPTANCE_FILTERS); +#else + i; +#endif + CANARD_STM32_CAN1->FilterRegister[filter_index].FR1 = id; + CANARD_STM32_CAN1->FilterRegister[filter_index].FR2 = mask; + + CANARD_STM32_CAN1->FA1R |= 1U << filter_index; // Enable + } + + return 0; +} + + +CanardSTM32Stats canardSTM32GetStats(void) +{ + return g_stats; +} diff --git a/Src/DroneCAN/libcanard/drivers/stm32/canard_stm32.h b/Src/DroneCAN/libcanard/drivers/stm32/canard_stm32.h new file mode 100644 index 00000000..7b8414c3 --- /dev/null +++ b/Src/DroneCAN/libcanard/drivers/stm32/canard_stm32.h @@ -0,0 +1,318 @@ +/* + * Copyright (c) 2017 UAVCAN Team + * + * Distributed under the MIT License, available in the file LICENSE. + * + * Author: Pavel Kirienko + */ + +#ifndef CANARD_STM32_H +#define CANARD_STM32_H + +#include +#include // NOLINT + + +#ifdef __cplusplus +extern "C" +{ +#endif + +/** + * Set this build config macro to 1 to use CAN2 instead of CAN1, if available. + * Setting this parameter when CAN2 is not available may not be detected at compile time! + */ +#if !defined(CANARD_STM32_USE_CAN2) +# define CANARD_STM32_USE_CAN2 0 +#endif + +/** + * Trigger an assertion failure if inner priority inversion is detected at run time. + * This setting has no effect in release builds, where NDEBUG is defined. + */ +#if !defined(CANARD_STM32_DEBUG_INNER_PRIORITY_INVERSION) +# define CANARD_STM32_DEBUG_INNER_PRIORITY_INVERSION 1 +#endif + +/** + * Driver error codes. + * These values are returned negated from API functions that return int. + */ +#define CANARD_STM32_ERROR_UNSUPPORTED_BIT_RATE 1000 +#define CANARD_STM32_ERROR_MSR_INAK_NOT_SET 1001 +#define CANARD_STM32_ERROR_MSR_INAK_NOT_CLEARED 1002 +#define CANARD_STM32_ERROR_UNSUPPORTED_FRAME_FORMAT 1003 + +/** + * This is defined by the bxCAN hardware. + * Devices with only one CAN interface have 14 filters (e.g. F103). + * Devices with two CAN interfaces have 28 filters, which are shared between two interfaces (e.g. F105, F446). + * The filters are distributed between CAN1 and CAN2 by means of the CAN2 start filter bank selection, + * which is a number from 1 to 27 inclusive. Seeing as the start bank cannot be set to 0, CAN2 has one filter less + * to use. + */ +#define CANARD_STM32_NUM_ACCEPTANCE_FILTERS 14U + +/** + * The interface can be initialized in either of these modes. + * + * The Silent mode is useful for automatic CAN bit rate detection, where the interface is initialized at an + * arbitrarily guessed CAN bit rate (typically either 1 Mbps, 500 Kbps, 250 Kbps, or 125 Kbps, these are the + * standard values defined by the UAVCAN specification), and the bus is then listened for 1 second in order to + * determine whether the bit rate was guessed correctly. It is paramount to use the silent mode in this case so + * as to not interfere with ongoing communications on the bus if the guess was incorrect. + * + * The automatic TX abort on error mode should be used during dynamic node ID allocation. The reason for that + * is well explained in the UAVCAN specification, please read it. + * + * The normal mode should be used for all other use cases, particularly for the normal operation of the node, + * hence the name. + */ +typedef enum +{ + CanardSTM32IfaceModeNormal, //!< Normal mode + CanardSTM32IfaceModeSilent, //!< Do not affect the bus, only listen + CanardSTM32IfaceModeAutomaticTxAbortOnError //!< Abort pending TX if a bus error has occurred +} CanardSTM32IfaceMode; + +/** + * Interface statistics; these values can be queried using a dedicated API call. + */ +typedef struct +{ + uint64_t rx_overflow_count; + uint64_t error_count; +} CanardSTM32Stats; + +/** + * ID and Mask of a hardware acceptance filter. + * The ID and Mask fields support flags @ref CANARD_CAN_FRAME_EFF and @ref CANARD_CAN_FRAME_RTR. + */ +typedef struct +{ + uint32_t id; + uint32_t mask; +} CanardSTM32AcceptanceFilterConfiguration; + +/** + * These parameters define the timings of the CAN controller. + * Please refer to the documentation of the bxCAN macrocell for explanation. + * These values can be computed by the developed beforehand if ROM size is of a concern, + * or they can be computed at run time using the function defined below. + */ +typedef struct +{ + uint16_t bit_rate_prescaler; /// [1, 1024] + uint8_t bit_segment_1; /// [1, 16] + uint8_t bit_segment_2; /// [1, 8] + uint8_t max_resynchronization_jump_width; /// [1, 4] (recommended value is 1) +} CanardSTM32CANTimings; + +/** + * Initializes the CAN controller at the specified bit rate. + * The mode can be either normal, silent, or auto-abort on error; + * in silent mode the controller will be only listening, not affecting the state of the bus; + * in the auto abort mode the controller will cancel the pending transmissions if a bus error is encountered. + * The auto abort mode is needed for dynamic node ID allocation procedure; please refer to the UAVCAN specification + * for more information about this topic. + * + * This function can be invoked any number of times; every invocation re-initializes everything from scratch. + * + * WARNING: The clock of the CAN module must be enabled before this function is invoked! + * If CAN2 is used, CAN1 must be also enabled! + * + * WARNING: The driver is not thread-safe! + * It does not use IRQ or critical sections though, so it is safe to invoke its API functions from the + * IRQ context from the application. + * + * @retval 0 Success + * @retval negative Error + */ +int16_t canardSTM32Init(const CanardSTM32CANTimings* const timings, + const CanardSTM32IfaceMode iface_mode); + +/** + * Pushes one frame into the TX buffer, if there is space. + * Note that proper care is taken to ensure that no inner priority inversion is taking place. + * This function does never block. + * + * @retval 1 Transmitted successfully + * @retval 0 No space in the buffer + * @retval negative Error + */ +int16_t canardSTM32Transmit(const CanardCANFrame* const frame); + +/** + * Reads one frame from the hardware RX FIFO, unless all FIFO are empty. + * This function does never block. + * + * @retval 1 Read successfully + * @retval 0 The buffer is empty + * @retval negative Error + */ +int16_t canardSTM32Receive(CanardCANFrame* const out_frame); + +/** + * Sets up acceptance filters according to the provided list of ID and masks. + * Note that when the interface is reinitialized, hardware acceptance filters are reset. + * Also note that during filter reconfiguration, some RX frames may be lost. + * + * Setting zero filters will result in rejection of all frames. + * In order to accept all frames, set one filter with ID = Mask = 0, which is also the default configuration. + * + * @retval 0 Success + * @retval negative Error + */ +int16_t canardSTM32ConfigureAcceptanceFilters(const CanardSTM32AcceptanceFilterConfiguration* const filter_configs, + const uint8_t num_filter_configs); + +/** + * Returns the running interface statistics. + */ +CanardSTM32Stats canardSTM32GetStats(void); + +/** + * Given the rate of the clock supplied to the bxCAN macrocell (typically PCLK1) and the desired bit rate, + * this function iteratively solves for the best possible timing settings. The CAN bus timing parameters, + * such as the sample point location, the number of time quantas per bit, etc., are optimized according to the + * recommendations provided in the specifications of UAVCAN, DeviceNet, and CANOpen. + * + * Unless noted otherwise, all units are SI units; particularly, frequency is specified in hertz. + * + * The implementation is adapted from libuavcan. + * + * This function is defined in the header in order to encourage the linker to discard it if it is not used. + * + * @retval 0 Success + * @retval negative Solution could not be found for the provided inputs. + */ +static inline +int16_t canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, + const uint32_t target_bitrate, + CanardSTM32CANTimings* const out_timings) +{ + if (target_bitrate < 1000) + { + return -CANARD_STM32_ERROR_UNSUPPORTED_BIT_RATE; + } + + CANARD_ASSERT(out_timings != NULL); // NOLINT + memset(out_timings, 0, sizeof(*out_timings)); + + /* + * Hardware configuration + */ + static const uint8_t MaxBS1 = 16; + static const uint8_t MaxBS2 = 8; + + /* + * Ref. "Automatic Baudrate Detection in CANopen Networks", U. Koppe, MicroControl GmbH & Co. KG + * CAN in Automation, 2003 + * + * According to the source, optimal quanta per bit are: + * Bitrate Optimal Maximum + * 1000 kbps 8 10 + * 500 kbps 16 17 + * 250 kbps 16 17 + * 125 kbps 16 17 + */ + const uint8_t max_quanta_per_bit = (uint8_t)((target_bitrate >= 1000000) ? 10 : 17); // NOLINT + CANARD_ASSERT(max_quanta_per_bit <= (MaxBS1 + MaxBS2)); + + static const uint16_t MaxSamplePointLocationPermill = 900; + + /* + * Computing (prescaler * BS): + * BITRATE = 1 / (PRESCALER * (1 / PCLK) * (1 + BS1 + BS2)) -- See the Reference Manual + * BITRATE = PCLK / (PRESCALER * (1 + BS1 + BS2)) -- Simplified + * let: + * BS = 1 + BS1 + BS2 -- Number of time quanta per bit + * PRESCALER_BS = PRESCALER * BS + * ==> + * PRESCALER_BS = PCLK / BITRATE + */ + const uint32_t prescaler_bs = peripheral_clock_rate / target_bitrate; + + /* + * Searching for such prescaler value so that the number of quanta per bit is highest. + */ + uint8_t bs1_bs2_sum = (uint8_t)(max_quanta_per_bit - 1); // NOLINT + + while ((prescaler_bs % (1U + bs1_bs2_sum)) != 0) + { + if (bs1_bs2_sum <= 2) + { + return -CANARD_STM32_ERROR_UNSUPPORTED_BIT_RATE; // No solution + } + bs1_bs2_sum--; + } + + const uint32_t prescaler = prescaler_bs / (1U + bs1_bs2_sum); + if ((prescaler < 1U) || (prescaler > 1024U)) + { + return -CANARD_STM32_ERROR_UNSUPPORTED_BIT_RATE; // No solution + } + + /* + * Now we have a constraint: (BS1 + BS2) == bs1_bs2_sum. + * We need to find such values so that the sample point is as close as possible to the optimal value, + * which is 87.5%, which is 7/8. + * + * Solve[(1 + bs1)/(1 + bs1 + bs2) == 7/8, bs2] (* Where 7/8 is 0.875, the recommended sample point location *) + * {{bs2 -> (1 + bs1)/7}} + * + * Hence: + * bs2 = (1 + bs1) / 7 + * bs1 = (7 * bs1_bs2_sum - 1) / 8 + * + * Sample point location can be computed as follows: + * Sample point location = (1 + bs1) / (1 + bs1 + bs2) + * + * Since the optimal solution is so close to the maximum, we prepare two solutions, and then pick the best one: + * - With rounding to nearest + * - With rounding to zero + */ + uint8_t bs1 = (uint8_t)(((7 * bs1_bs2_sum - 1) + 4) / 8); // Trying rounding to nearest first // NOLINT + uint8_t bs2 = (uint8_t)(bs1_bs2_sum - bs1); // NOLINT + CANARD_ASSERT(bs1_bs2_sum > bs1); + + { + const uint16_t sample_point_permill = (uint16_t)(1000U * (1U + bs1) / (1U + bs1 + bs2)); // NOLINT + + if (sample_point_permill > MaxSamplePointLocationPermill) // Strictly more! + { + bs1 = (uint8_t)((7 * bs1_bs2_sum - 1) / 8); // Nope, too far; now rounding to zero + bs2 = (uint8_t)(bs1_bs2_sum - bs1); + } + } + + const bool valid = (bs1 >= 1) && (bs1 <= MaxBS1) && (bs2 >= 1) && (bs2 <= MaxBS2); + + /* + * Final validation + * Helpful Python: + * def sample_point_from_btr(x): + * assert 0b0011110010000000111111000000000 & x == 0 + * ts2,ts1,brp = (x>>20)&7, (x>>16)&15, x&511 + * return (1+ts1+1)/(1+ts1+1+ts2+1) + */ + if ((target_bitrate != (peripheral_clock_rate / (prescaler * (1U + bs1 + bs2)))) || + !valid) + { + // This actually means that the algorithm has a logic error, hence assert(0). + CANARD_ASSERT(0); // NOLINT + return -CANARD_STM32_ERROR_UNSUPPORTED_BIT_RATE; + } + + out_timings->bit_rate_prescaler = (uint16_t) prescaler; + out_timings->max_resynchronization_jump_width = 1; // One is recommended by UAVCAN, CANOpen, and DeviceNet + out_timings->bit_segment_1 = bs1; + out_timings->bit_segment_2 = bs2; + + return 0; +} + +#ifdef __cplusplus +} +#endif +#endif diff --git a/Src/DroneCAN/regenerate.sh b/Src/DroneCAN/regenerate.sh new file mode 100755 index 00000000..0542072a --- /dev/null +++ b/Src/DroneCAN/regenerate.sh @@ -0,0 +1,46 @@ +#!/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 dronecan.protocol.FlexDebug" + +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/Src/DroneCAN/scripts/AM32_debug_log.lua b/Src/DroneCAN/scripts/AM32_debug_log.lua new file mode 100644 index 00000000..730401e8 --- /dev/null +++ b/Src/DroneCAN/scripts/AM32_debug_log.lua @@ -0,0 +1,50 @@ +--[[ + ArduPilot lua script to log debug messages from AM32 DroneCAN + ESCs on the flight controller + + To install set SCR_ENABLE=1 and put this script in APM/SCRIPTS/ on + the microSD of the flight controller then restart the flight + controllr +--]] + +local ESC_BASE = 30 + +local AM32_DEBUG = 100 + +local last_tstamp = {} +local ts_zero = uint32_t(0) +local reported_version_error = false + +function log_AM32() + for i = 0, 3 do + local last_ts = last_tstamp[i] or ts_zero + tstamp_us, msg = DroneCAN_get_FlexDebug(0, ESC_BASE+i, AM32_DEBUG, last_ts) + if tstamp_us then + local dt = (tstamp_us - last_ts):tofloat()*1.0e-6 + version, commutation_interval, num_commands, num_input, rx_errors, rxframe_error, rx_ecode, auto_advance_level = string.unpack(">= 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(" + +/* + CAN statistics shared by low level and high level code + */ +struct CANStats { + uint32_t num_commands; + uint32_t num_input; + 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(); + +/* + 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/Src/DroneCAN/sys_can_at32.c b/Src/DroneCAN/sys_can_at32.c new file mode 100644 index 00000000..947a185a --- /dev/null +++ b/Src/DroneCAN/sys_can_at32.c @@ -0,0 +1,251 @@ +/* + sys_can.c - MCU specific CAN code for AT32 bxCAN + */ + +#include "targets.h" + +#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 + */ + } + } +} + +uint32_t get_rtc_backup_register(uint8_t idx) +{ + return ertc_bpr_data_read(idx); +} + +void set_rtc_backup_register(uint8_t idx, uint32_t value) +{ + ertc_bpr_data_write(idx, value); +} + +#endif // DRONECAN_SUPPORT && defined(ARTERY) + diff --git a/Src/DroneCAN/sys_can_stm32.c b/Src/DroneCAN/sys_can_stm32.c new file mode 100644 index 00000000..665c7169 --- /dev/null +++ b/Src/DroneCAN/sys_can_stm32.c @@ -0,0 +1,243 @@ +/* + sys_can.c - MCU specific CAN code for STM32 bxCAN + */ + +#include "targets.h" + +#if DRONECAN_SUPPORT && defined(MCU_L431) + +#include "sys_can.h" +#include +#include <_internal_bxcan.h> +#include "functions.h" + +#define BXCAN CANARD_STM32_CAN1 + +// #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 *)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); +} + +/* + canned when a mailbox has a pending incoming frame + */ +static void handleTxMailboxInterrupt(uint8_t mbox, bool txok) +{ + DroneCAN_processTxQueue(); +} + +/* + check for error state + */ +static void pollErrorFlagsFromISR() +{ + const uint8_t lec = (uint8_t)((BXCAN->ESR & CANARD_STM32_CAN_ESR_LEC_MASK) >> CANARD_STM32_CAN_ESR_LEC_SHIFT); + if (lec != 0) { + canstats.esr = BXCAN->ESR; // Record error status + BXCAN->ESR = 0; + } +} + +/* + handle all TX interrupts + */ +static void handleTxInterrupt(void) +{ + canstats.num_tx_interrupts++; + + // TXOK == false means that there was a hardware failure + if (BXCAN->TSR & CANARD_STM32_CAN_TSR_RQCP0) { + const bool txok = BXCAN->TSR & CANARD_STM32_CAN_TSR_TXOK0; + BXCAN->TSR = CANARD_STM32_CAN_TSR_RQCP0; + handleTxMailboxInterrupt(0, txok); + } + if (BXCAN->TSR & CANARD_STM32_CAN_TSR_RQCP1) { + const bool txok = BXCAN->TSR & CANARD_STM32_CAN_TSR_TXOK1; + BXCAN->TSR = CANARD_STM32_CAN_TSR_RQCP1; + handleTxMailboxInterrupt(1, txok); + } + if (BXCAN->TSR & CANARD_STM32_CAN_TSR_RQCP2) { + const bool txok = BXCAN->TSR & CANARD_STM32_CAN_TSR_TXOK2; + BXCAN->TSR = CANARD_STM32_CAN_TSR_RQCP2; + handleTxMailboxInterrupt(2, txok); + } + + pollErrorFlagsFromISR(); +} + +/* + handle all RX interrupts + */ +static void handleRxInterrupt(uint8_t fifo_index) +{ + canstats.num_rx_interrupts++; + + volatile uint32_t* const rfr_reg = (fifo_index == 0) ? &BXCAN->RF0R : &BXCAN->RF1R; + if ((*rfr_reg & CANARD_STM32_CAN_RFR_FMP_MASK) == 0) { + return; + } + + /* + * Register overflow as a hardware error + */ + if ((*rfr_reg & CANARD_STM32_CAN_RFR_FOVR) != 0) { + canstats.rx_errors++; + } + + DroneCAN_receiveFrame(); + + pollErrorFlagsFromISR(); +} + +/* + 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 canardSTM32Transmit(txf); +} + +/* + 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) +{ + return canardSTM32Receive(rx_frame); +} + +/* + disable CAN IRQs + */ +void sys_can_disable_IRQ(void) +{ + NVIC_DisableIRQ(CAN1_RX0_IRQn); + NVIC_DisableIRQ(CAN1_RX1_IRQn); + NVIC_DisableIRQ(CAN1_TX_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") + +/* + 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.Pull = LL_GPIO_PULL_NO; + GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = 9; // AF9==CAN + LL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + LL_RCC_ClocksTypeDef Clocks; + LL_RCC_GetSystemClocksFreq(&Clocks); + + /* + work out timing for 1MBps CAN + */ + CanardSTM32CANTimings timings; + +#if 0 + // use this to get timings for a new board + canardSTM32ComputeCANTimings(Clocks.PCLK1_Frequency, 1000000, &timings); +#else + switch (Clocks.PCLK1_Frequency) { + case 80000000UL: + timings.bit_rate_prescaler = 8; + timings.bit_segment_1 = 8; + timings.bit_segment_2 = 1; + timings.max_resynchronization_jump_width = 1; + break; + default: + // need to port to this board + while (true) { + delayMicros(1000); + } + break; + } +#endif + + canardSTM32Init(&timings, CanardSTM32IfaceModeNormal); + + /* + 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); + BXCAN->IER = CANARD_STM32_CAN_IER_FMPIE0 | CANARD_STM32_CAN_IER_FMPIE1 | CANARD_STM32_CAN_IER_TMEIE; +} + +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/Src/dshot.c b/Src/dshot.c index 0a3562ae..ffea460e 100644 --- a/Src/dshot.c +++ b/Src/dshot.c @@ -11,6 +11,9 @@ #include "functions.h" #include "sounds.h" #include "targets.h" +#if DRONECAN_SUPPORT +#include "DroneCAN/DroneCAN.h" +#endif int dpulse[16] = { 0 }; @@ -95,6 +98,12 @@ void computeDshotDMA() if (EDT_ARM_ENABLE == 1) { EDT_ARMED = 0; } +#if DRONECAN_SUPPORT + if (DroneCAN_active()) { + // allow DroneCAN to override DShot input + return; + } +#endif newinput = 0; dshotcommand = 0; command_count = 0; diff --git a/Src/main.c b/Src/main.c index 412142a4..a7a6d2c9 100644 --- a/Src/main.c +++ b/Src/main.c @@ -240,6 +240,10 @@ an settings option) #include "crsf.h" #endif +#if DRONECAN_SUPPORT +#include "DroneCAN/DroneCAN.h" +#endif + #include void zcfoundroutine(void); @@ -296,16 +300,8 @@ fastPID stallPid = { // 1khz loop time .output_limit = 50000 }; -enum inputType { - AUTO_IN, - DSHOT_IN, - SERVO_IN, - SERIAL_IN, - EDTARM, -}; - EEprom_t eepromBuffer; -uint32_t eeprom_address = EEPROM_START_ADD; +uint32_t eeprom_address = EEPROM_START_ADD; char set_hysteris = 0; uint16_t prop_brake_duty_cycle = 0; uint16_t ledcounter = 0; @@ -606,7 +602,7 @@ float doPidCalculations(struct fastPID* pidnow, int actual, int target) void loadEEpromSettings() { - //*eepromBuffer = *(EEprom_t*)(eeprom_address); + //*eepromBuffer = *(EEprom_t*)(eeprom_address); read_flash_bin(eepromBuffer.buffer, eeprom_address, sizeof(eepromBuffer.buffer)); if (eepromBuffer.advance_level > 3) { @@ -731,7 +727,7 @@ void loadEEpromSettings() break; case SERIAL_IN: break; - case EDTARM: + case EDTARM_IN: EDT_ARM_ENABLE = 1; EDT_ARMED = 0; dshot = 1; @@ -2176,6 +2172,9 @@ int main(void) #ifdef BRUSHED_MODE runBrushedLoop(); +#endif +#if DRONECAN_SUPPORT + DroneCAN_update(); #endif } } diff --git a/f415makefile.mk b/f415makefile.mk index 78cb6f91..73c60aa6 100644 --- a/f415makefile.mk +++ b/f415makefile.mk @@ -8,7 +8,7 @@ TARGETS_$(MCU) := $(call get_targets,$(MCU)) HAL_FOLDER_$(MCU) := $(HAL_FOLDER)/$(MCU_LC) MCU_$(MCU) := -mcpu=cortex-m4 -mthumb -LDSCRIPT_$(MCU) := $(wildcard $(HAL_FOLDER_$(MCU))/*.ld) +LDSCRIPT_$(MCU) := $(HAL_FOLDER_$(MCU))/ldscript.ld SRC_BASE_DIR_$(MCU) := \ $(HAL_FOLDER_$(MCU))/Startup \ @@ -28,3 +28,18 @@ CFLAGS_$(MCU) += \ -DUSE_STDPERIPH_DRIVER SRC_$(MCU) := $(foreach dir,$(SRC_DIR_$(MCU)),$(wildcard $(dir)/*.[cs])) + + +# optional CAN support +CFLAGS_CAN_$(MCU) = \ + -ISrc/DroneCAN \ + -ISrc/DroneCAN/libcanard \ + -ISrc/DroneCAN/dsdl_generated/include + +SRC_DIR_CAN_$(MCU) = Src/DroneCAN \ + Src/DroneCAN/dsdl_generated/src \ + Src/DroneCAN/libcanard + +SRC_CAN_$(MCU) := $(foreach dir,$(SRC_DIR_CAN_$(MCU)),$(wildcard $(dir)/*.[cs])) + +LDSCRIPT_CAN_$(MCU) := $(HAL_FOLDER_$(MCU))/ldscript_CAN.ld diff --git a/l431makefile.mk b/l431makefile.mk index ca2bfa49..473b0292 100644 --- a/l431makefile.mk +++ b/l431makefile.mk @@ -6,7 +6,8 @@ TARGETS_$(MCU) := $(call get_targets,$(MCU)) HAL_FOLDER_$(MCU) := $(HAL_FOLDER)/$(call lc,$(MCU)) MCU_$(MCU) := -mcpu=cortex-m4 -mthumb -LDSCRIPT_$(MCU) := $(wildcard $(HAL_FOLDER_$(MCU))/*.ld) + +LDSCRIPT_$(MCU) := $(HAL_FOLDER_$(MCU))/ldscript.ld SRC_BASE_DIR_$(MCU) := \ $(HAL_FOLDER_$(MCU))/Startup/gcc \ @@ -23,17 +24,33 @@ CFLAGS_$(MCU) := \ -I$(HAL_FOLDER_$(MCU))/Drivers/CMSIS/Device/ST/STM32L4xx/Include CFLAGS_$(MCU) += \ - -DHSE_VALUE=8000000 \ -D$(PART) \ -DHSE_STARTUP_TIMEOUT=100 \ -DLSE_STARTUP_TIMEOUT=5000 \ - -DLSE_VALUE=32768 \ -DDATA_CACHE_ENABLE=1 \ -DINSTRUCTION_CACHE_ENABLE=0 \ -DVDD_VALUE=3300 \ -DLSI_VALUE=32000 \ -DHSI_VALUE=16000000 \ -DUSE_FULL_LL_DRIVER \ - -DPREFETCH_ENABLE=1 + -DPREFETCH_ENABLE=1 \ + -mfloat-abi=hard + SRC_$(MCU) := $(foreach dir,$(SRC_DIR_$(MCU)),$(wildcard $(dir)/*.[cs])) + +# optional CAN support +CFLAGS_CAN_$(MCU) = \ + -ISrc/DroneCAN \ + -ISrc/DroneCAN/libcanard \ + -ISrc/DroneCAN/libcanard/drivers/stm32 \ + -ISrc/DroneCAN/dsdl_generated/include + +SRC_DIR_CAN_$(MCU) = Src/DroneCAN \ + Src/DroneCAN/dsdl_generated/src \ + Src/DroneCAN/libcanard \ + Src/DroneCAN/libcanard/drivers/stm32 + +SRC_CAN_$(MCU) := $(foreach dir,$(SRC_DIR_CAN_$(MCU)),$(wildcard $(dir)/*.[cs])) + +LDSCRIPT_CAN_$(MCU) := $(HAL_FOLDER_$(MCU))/ldscript_CAN.ld