Pārlūkot izejas kodu

1、增加DRONEcan
2、增加吊运模块

z8359531l 2 mēneši atpakaļ
vecāks
revīzija
dab91f851a
46 mainītis faili ar 5858 papildinājumiem un 952 dzēšanām
  1. 1 1
      .vscode/c_cpp_properties.json
  2. 1 1
      .vscode/launch.json
  3. 6 2
      Core/Src/main.c
  4. 2 3
      MDK-ARM/RTE/_V9_PMU2_302CC/RTE_Components.h
  5. 16 17
      MDK-ARM/V9_PMU2_302CC.uvguix.zl835
  6. 2 7
      MDK-ARM/V9_PMU2_302CC.uvoptx
  7. 2 1
      MDK-ARM/V9_PMU2_302CC.uvprojx
  8. 4 1
      Makefile
  9. 737 0
      uav_can/user_inc/canard.h
  10. 201 0
      uav_can/user_inc/canard_internals.h
  11. 104 0
      uav_can/user_inc/dronecan.h
  12. 26 0
      uav_can/user_inc/dronecan_id_alloc.h
  13. 65 0
      uav_can/user_inc/drv_vkweigher_vls300.h
  14. 14 0
      uav_can/user_inc/vkweigher.FuseBreak.h
  15. 115 0
      uav_can/user_inc/vkweigher.FuseBreak_req.h
  16. 123 0
      uav_can/user_inc/vkweigher.FuseBreak_res.h
  17. 14 0
      uav_can/user_inc/vkweigher.Version.h
  18. 138 0
      uav_can/user_inc/vkweigher.Version_req.h
  19. 155 0
      uav_can/user_inc/vkweigher.Version_res.h
  20. 14 0
      uav_can/user_inc/vkweigher.WeigherCalib.h
  21. 115 0
      uav_can/user_inc/vkweigher.WeigherCalib_req.h
  22. 123 0
      uav_can/user_inc/vkweigher.WeigherCalib_res.h
  23. 341 0
      uav_can/user_inc/vkweigher.WeigherStatus.h
  24. 1960 0
      uav_can/user_src/canard.c
  25. 251 0
      uav_can/user_src/dronecan.c
  26. 567 0
      uav_can/user_src/drv_vkweigher_vls300.c
  27. 81 0
      uav_can/user_src/vkweigher.FuseBreak_req.c
  28. 79 0
      uav_can/user_src/vkweigher.FuseBreak_res.c
  29. 89 0
      uav_can/user_src/vkweigher.Version_req.c
  30. 95 0
      uav_can/user_src/vkweigher.Version_res.c
  31. 81 0
      uav_can/user_src/vkweigher.WeigherCalib_req.c
  32. 79 0
      uav_can/user_src/vkweigher.WeigherCalib_res.c
  33. 159 0
      uav_can/user_src/vkweigher.WeigherStatus.c
  34. 0 236
      user_inc/soft_hd_water_pump.h
  35. 2 3
      user_inc/soft_p_2_c.h
  36. 20 0
      user_inc/soft_seed_device.h
  37. 1 0
      user_inc/soft_timer.h
  38. 4 1
      user_inc/soft_version.h
  39. 3 1
      user_src/soft_can.c
  40. 0 638
      user_src/soft_hd_water_pump.c
  41. 7 2
      user_src/soft_p_2_c.c
  42. 47 14
      user_src/soft_seed_device.c
  43. 3 0
      user_src/soft_test.c
  44. 1 0
      user_src/soft_timer.c
  45. 8 0
      user_src/soft_version.c
  46. 2 24
      user_src/soft_water_device.c

+ 1 - 1
.vscode/c_cpp_properties.json

@@ -12,7 +12,7 @@
             "cStandard": "c11",
             "cppStandard": "c++17",
             "intelliSenseMode": "gcc-x64",
-            "compilerPath": "D:/zhou/vscodestm32/CUBEIDE/STM32CubeIDE_2.0.0/STM32CubeIDE/plugins/com.st.stm32cube.ide.mcu.externaltools.gnu-tools-for-stm32.13.3.rel1.win32_1.0.100.202509120712/tools/bin/arm-none-eabi-gcc.exe"
+            "compilerPath": "D:/arm-gcc/bin/arm-none-eabi-gcc.exe"
         }
     ],
     "version": 4

+ 1 - 1
.vscode/launch.json

@@ -16,7 +16,7 @@
             "servertype": "jlink",
             "device": "STM32F302CC",
             "interface": "swd",
-            "serverpath": "D:/JLINKK/JLink_V832/JLinkGDBServerCL.exe" 
+            "serverpath": "E:/j-flash-7.56b/JLinkGDBServerCL.exe",
         }
     ]
 }

+ 6 - 2
Core/Src/main.c

@@ -54,6 +54,7 @@
 #include "stdio.h"
 #include "soft_update.h"
 #include "can_debug.h"
+#include "dronecan.h"
 
 
 /* USER CODE END Includes */
@@ -96,11 +97,11 @@ void SystemClock_Config(void);
   */
 int main(void)
 {
-
+ 
   /* USER CODE BEGIN 1 */
   SCB->VTOR = FLASH_BASE | 0x8007800; //偏移
   /* USER CODE END 1 */
-
+  
   /* MCU Configuration--------------------------------------------------------*/
 
   /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
@@ -198,7 +199,10 @@ int main(void)
     Vk_Update_Device_Protocol();
 #endif 
     
+    //串口发送
     send_uartfifo_msg();
+    //dronecan发送
+    //dronecan_tx_processing(); //test
     //CAN DEBUG
     if(planep.Candebug_flag == true)
     {

+ 2 - 3
MDK-ARM/RTE/_V9_PMU2_302CC/RTE_Components.h

@@ -1,7 +1,6 @@
-
 /*
- * Auto generated Run-Time-Environment Configuration File
- *      *** Do not modify ! ***
+ * UVISION generated file: DO NOT EDIT!
+ * Generated by: uVision version 5.42.0.0
  *
  * Project: 'V9_PMU2_302CC' 
  * Target:  'V9_PMU2_302CC' 

Failā izmaiņas netiks attēlotas, jo tās ir par lielu
+ 16 - 17
MDK-ARM/V9_PMU2_302CC.uvguix.zl835


+ 2 - 7
MDK-ARM/V9_PMU2_302CC.uvoptx

@@ -132,15 +132,10 @@
           <Key>ARMDBGFLAGS</Key>
           <Name></Name>
         </SetRegEntry>
-        <SetRegEntry>
-          <Number>0</Number>
-          <Key>DLGUARM</Key>
-          <Name>?</Name>
-        </SetRegEntry>
         <SetRegEntry>
           <Number>0</Number>
           <Key>JL2CM3</Key>
-          <Name>-U69404644 -O78 -S2 -ZTIFSpeedSel5000 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -N00("ARM CoreSight SW-DP") -D00(2BA01477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO7 -FD20000000 -FC1000 -FN1 -FF0STM32F3xx_256.FLM -FS08000000 -FL040000 -FP0($$Device:STM32F302CCTx$CMSIS\Flash\STM32F3xx_256.FLM)</Name>
+          <Name>-U69406358 -O78 -S2 -ZTIFSpeedSel5000 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -N00("ARM CoreSight SW-DP") -D00(2BA01477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8004 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO15 -FD20000000 -FC1000 -FN1 -FF0STM32F3xx_256.FLM -FS08007800 -FL040000 -FP0($$Device:STM32F302CCTx$CMSIS\Flash\STM32F3xx_256.FLM)</Name>
         </SetRegEntry>
         <SetRegEntry>
           <Number>0</Number>
@@ -230,7 +225,7 @@
 
   <Group>
     <GroupName>Application/MDK-ARM</GroupName>
-    <tvExp>0</tvExp>
+    <tvExp>1</tvExp>
     <tvExpOptDlg>0</tvExpOptDlg>
     <cbSel>0</cbSel>
     <RteFlg>0</RteFlg>

+ 2 - 1
MDK-ARM/V9_PMU2_302CC.uvprojx

@@ -139,7 +139,7 @@
           </Flash1>
           <bUseTDR>1</bUseTDR>
           <Flash2>BIN\UL2V8M.DLL</Flash2>
-          <Flash3></Flash3>
+          <Flash3>"" ()</Flash3>
           <Flash4></Flash4>
           <pFcarmOut></pFcarmOut>
           <pFcarmGrp></pFcarmGrp>
@@ -187,6 +187,7 @@
             <RvdsVP>2</RvdsVP>
             <RvdsMve>0</RvdsMve>
             <RvdsCdeCp>0</RvdsCdeCp>
+            <nBranchProt>0</nBranchProt>
             <hadIRAM2>0</hadIRAM2>
             <hadIROM2>0</hadIROM2>
             <StupSel>8</StupSel>

+ 4 - 1
Makefile

@@ -70,9 +70,11 @@ Core/Src/system_stm32f3xx.c
 
 # USER SOURCES
 USER_SOURCES += $(wildcard user_src/*.c)
+OPEN_PROTOCOL += $(wildcard uav_can/user_src/*.c)
 
 C_SOURCES = $(STD_LIB) 
 C_SOURCES += $(USER_SOURCES) 
+C_SOURCES += $(OPEN_PROTOCOL) 
 
 
 # ASM sources
@@ -139,7 +141,8 @@ C_INCLUDES =  \
 -IDrivers/STM32F3xx_HAL_Driver/Inc/Legacy \
 -IDrivers/CMSIS/Device/ST/STM32F3xx/Include \
 -IDrivers/CMSIS/Include \
--Iuser_inc
+-Iuser_inc \
+-Iuav_can/user_inc
 
 
 # compile gcc flags

+ 737 - 0
uav_can/user_inc/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 <stdint.h>
+#include <stddef.h>
+#include <stdbool.h>
+#include <assert.h>
+
+/// 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

+ 201 - 0
uav_can/user_inc/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

+ 104 - 0
uav_can/user_inc/dronecan.h

@@ -0,0 +1,104 @@
+#pragma once
+
+#include "dronecan_id_alloc.h"
+#include "canard.h"
+#include <stdint.h>
+#include "soft_can.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#define LOCK 1
+#define UNLOCK 0
+/* The default local node id. */
+#define DRONECAN_CANARD_DEFAULT_LOCAL_NODE_ID DRONECAN_FMU_NODE_ID
+
+/* The size of the memory pool for the Canard library. */
+#define DRONECAN_CANARD_MEMORY_POOL_SIZE 2048
+
+#define DRONECAN_CANARD_IFACE1_MASK (1 << 0)
+#define DRONECAN_CANARD_IFACE2_MASK (1 << 1)
+#define DRONECAN_CANARD_IFACE_MAX_NUM 2
+
+/** The dronecan instance. */
+struct dronecan {
+  /* canard 对象 */
+  CanardInstance *_canard_ins;
+
+  /* canard 库内存池 */
+  uint8_t *_canard_memory_pool;
+
+  /* can 接口 */
+  //rt_device_t _can_iface[DRONECAN_CANARD_IFACE_MAX_NUM];
+
+  //rt_mutex_t _lock;
+
+  /* 定时器, 用于定时广播 node status */
+  //rt_timer_t _timer;
+
+  /* 时间戳, 调用 canardCleanupStaleTransfers */
+  uint32_t _cleanup_timestamp;
+
+  /* 发送消息更新回调钩子函数 */
+  void (*_tx_update_hook)(struct dronecan *dcan);
+
+  uint32_t _re_tx_cnt;   /**< redo tx count */
+  uint32_t _tx_succ_cnt; /**< tx success count */
+  uint32_t _tx_fail_cnt; /**< tx fail count */
+};
+
+/**
+ * @brief init dronecan instance
+ *
+ * @param can_dev can device
+ * @return int 0 success, else failed
+ */
+void dronecan_init(void);
+
+/**
+ * @brief dronecan 接收回调, 当 can 接口收到 can 消息后调用此函数
+ *
+ * @param msg can message
+ * @param iface_id  interface id, if can1 then 0, if can2 then 1, etc
+ * @return int 0-not handled, 1-handled
+ */
+int dronecan_rx_callback(CAN_RxHeaderTypeDef Rxhead,uint8_t data[]);
+
+void dronecan_tx_processing(void);
+
+/**
+ * @brief dronecan 发送广播消息
+ *
+ * @param dcan
+ * @param tx_transfer
+ * @return int
+ */
+int dronecan_broadcast(struct dronecan *dcan, CanardTxTransfer *tx_transfer);
+
+/**
+ * @brief dronecan 发送请求或应答消息
+ *
+ * @param dcan
+ * @param dest_id 目标节点 id
+ * @param tx_transfer
+ * @return int
+ */
+int dronecan_request_or_respond(uint8_t dest_id,
+                                CanardTxTransfer *tx_transfer);
+
+/**
+ * @brief dronecan 注册 tx_hook 回调函数
+ *   当有数据需要通过dronecan 发送时, tx_hook 回调函数会被调用
+ *
+ * @param fun 回调函数
+ * @return int RT_EOK 为成功, 其它为失败
+ */
+int dronecan_tx_hook_register(void (*fun)(struct dronecan *dcan));
+
+void dronecan_lock();
+void dronecan_unlock();
+
+#ifdef __cplusplus
+}
+#endif

+ 26 - 0
uav_can/user_inc/dronecan_id_alloc.h

@@ -0,0 +1,26 @@
+#pragma once
+
+
+
+#define DRONECAN_ESC1_NODE_ID 1
+#define DRONECAN_ESC2_NODE_ID 2
+#define DRONECAN_ESC3_NODE_ID 3
+#define DRONECAN_ESC4_NODE_ID 4
+#define DRONECAN_ESC5_NODE_ID 5
+#define DRONECAN_ESC6_NODE_ID 6
+#define DRONECAN_ESC7_NODE_ID 7
+#define DRONECAN_ESC8_NODE_ID 8
+#define DRONECAN_ESC9_NODE_ID 9
+#define DRONECAN_ESC10_NODE_ID 10
+#define DRONECAN_ESC11_NODE_ID 11
+#define DRONECAN_ESC12_NODE_ID 12
+#define DRONECAN_ESC13_NODE_ID 13
+#define DRONECAN_ESC14_NODE_ID 14
+#define DRONECAN_ESC15_NODE_ID 15
+#define DRONECAN_ESC16_NODE_ID 16
+
+#define DRONECAN_FMU_NODE_ID 20
+
+#define DRONECAN_WEIGHER_NODE_ID 52
+
+#define DRONECAN_PARACHUTE_NODE_ID 99

+ 65 - 0
uav_can/user_inc/drv_vkweigher_vls300.h

@@ -0,0 +1,65 @@
+#pragma once
+
+#include "canard.h"
+
+
+#ifdef __cplusplus
+extern "C" {
+#endif // __cplusplus
+
+#define VK_WEIGHER_VLS300_DEV_NAME "weigher"
+
+int vkWeigher_Vls300_OnRecieved(CanardInstance *canardIns,
+                                CanardRxTransfer *transfer);
+
+                                struct _weigher_status {
+  uint32_t timestamp;  /* [ms] 数据更新时间戳 */
+  uint32_t weight;     /* g */
+  uint16_t weight_dot; /* g/min */
+  uint16_t status;
+  float gyro[3]; /* rad/s */
+  float acce[3]; /* m/s^2 */
+  float Q[4];    /* 姿态四元数 */
+};
+
+
+struct _weigher_version {
+  uint32_t timestamp;
+  uint8_t fw_ver[16];
+  uint32_t SN_num;
+};
+
+struct vk_weigher_vls300 {
+  // struct weigher_device weigher_dev;
+  // rt_device_t can_dev;
+
+  CanardInstance *canard;
+  uint8_t iface_mask;
+
+  bool data_got;
+  struct _weigher_status status_data;
+  struct _weigher_version version;
+
+  // rt_event_t _event;
+  uint16_t _fw_update_send_pack_num; // 从1开始
+  const char *_fw_file_name;
+};
+
+
+enum {
+  VLS300_EVENT_GOT_FW_UPDATE_START_ACK = 1,
+  VLS300_EVENT_GOT_FW_UPDATE_INFO_ACK = (1 << 1),
+  VLS300_EVENT_GOT_FW_UPDATE_DATA_ACK = (1 << 2),
+};
+
+extern struct vk_weigher_vls300 _vk_vls300;
+
+bool vkWeigher_Vls300_shouldAcceptTransfer(const CanardInstance *ins,
+                                           uint64_t *out_data_type_signature,
+                                           uint16_t data_type_id,
+                                           CanardTransferType transfer_type,
+                                           uint8_t source_node_id);
+uint8_t vklift_weight_calibrate(uint32_t weight);
+#ifdef __cplusplus
+}
+#endif // __cplusplus

+ 14 - 0
uav_can/user_inc/vkweigher.FuseBreak.h

@@ -0,0 +1,14 @@
+
+
+#pragma once
+#include <vkweigher.FuseBreak_req.h>
+#include <vkweigher.FuseBreak_res.h>
+
+#define VKWEIGHER_FUSEBREAK_ID 235
+#define VKWEIGHER_FUSEBREAK_SIGNATURE (0xAB0D626FEAA1A2E0ULL)
+
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+#include <canard/cxx_wrappers.h>
+SERVICE_MESSAGE_CXX_IFACE(vkweigher_FuseBreak, VKWEIGHER_FUSEBREAK_ID, VKWEIGHER_FUSEBREAK_SIGNATURE, VKWEIGHER_FUSEBREAK_REQUEST_MAX_SIZE, VKWEIGHER_FUSEBREAK_RESPONSE_MAX_SIZE);
+#endif

+ 115 - 0
uav_can/user_inc/vkweigher.FuseBreak_req.h

@@ -0,0 +1,115 @@
+
+#pragma once
+#include <stdbool.h>
+#include <stdint.h>
+#include <canard.h>
+
+
+
+
+#define VKWEIGHER_FUSEBREAK_REQUEST_MAX_SIZE 1
+#define VKWEIGHER_FUSEBREAK_REQUEST_SIGNATURE (0xAB0D626FEAA1A2E0ULL)
+
+#define VKWEIGHER_FUSEBREAK_REQUEST_ID 235
+
+
+
+
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+class vkweigher_FuseBreak_cxx_iface;
+#endif
+
+
+struct vkweigher_FuseBreakRequest {
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+    using cxx_iface = vkweigher_FuseBreak_cxx_iface;
+#endif
+
+
+
+
+    uint8_t break_cmd;
+
+
+
+};
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+uint32_t vkweigher_FuseBreakRequest_encode(struct vkweigher_FuseBreakRequest* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+);
+bool vkweigher_FuseBreakRequest_decode(const CanardRxTransfer* transfer, struct vkweigher_FuseBreakRequest* msg);
+
+#if defined(CANARD_DSDLC_INTERNAL)
+
+static inline void _vkweigher_FuseBreakRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_FuseBreakRequest* msg, bool tao);
+static inline bool _vkweigher_FuseBreakRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_FuseBreakRequest* msg, bool tao);
+void _vkweigher_FuseBreakRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_FuseBreakRequest* msg, bool tao) {
+
+    (void)buffer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 8, &msg->break_cmd);
+
+    *bit_ofs += 8;
+
+
+
+
+
+}
+
+/*
+ decode vkweigher_FuseBreakRequest, return true on failure, false on success
+*/
+bool _vkweigher_FuseBreakRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_FuseBreakRequest* msg, bool tao) {
+
+    (void)transfer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->break_cmd);
+
+    *bit_ofs += 8;
+
+
+
+
+
+    return false; /* success */
+
+}
+#endif
+#ifdef CANARD_DSDLC_TEST_BUILD
+struct vkweigher_FuseBreakRequest sample_vkweigher_FuseBreakRequest_msg(void);
+#endif
+#ifdef __cplusplus
+} // extern "C"
+
+#ifdef DRONECAN_CXX_WRAPPERS
+#include <canard/cxx_wrappers.h>
+
+
+
+#endif
+#endif

+ 123 - 0
uav_can/user_inc/vkweigher.FuseBreak_res.h

@@ -0,0 +1,123 @@
+
+#pragma once
+#include <stdbool.h>
+#include <stdint.h>
+#include <canard.h>
+
+
+
+
+#define VKWEIGHER_FUSEBREAK_RESPONSE_MAX_SIZE 1
+#define VKWEIGHER_FUSEBREAK_RESPONSE_SIGNATURE (0xAB0D626FEAA1A2E0ULL)
+
+#define VKWEIGHER_FUSEBREAK_RESPONSE_ID 235
+
+
+
+#define VKWEIGHER_FUSEBREAK_RESPONSE_RESULT_SUCCESS 1
+
+#define VKWEIGHER_FUSEBREAK_RESPONSE_RESULT_REJECTED 0
+
+#define VKWEIGHER_FUSEBREAK_RESPONSE_RESULT_FAILED -1
+
+
+
+
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+class vkweigher_FuseBreak_cxx_iface;
+#endif
+
+
+struct vkweigher_FuseBreakResponse {
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+    using cxx_iface = vkweigher_FuseBreak_cxx_iface;
+#endif
+
+
+
+
+    int8_t result;
+
+
+
+};
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+uint32_t vkweigher_FuseBreakResponse_encode(struct vkweigher_FuseBreakResponse* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+);
+bool vkweigher_FuseBreakResponse_decode(const CanardRxTransfer* transfer, struct vkweigher_FuseBreakResponse* msg);
+
+#if defined(CANARD_DSDLC_INTERNAL)
+
+static inline void _vkweigher_FuseBreakResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_FuseBreakResponse* msg, bool tao);
+static inline bool _vkweigher_FuseBreakResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_FuseBreakResponse* msg, bool tao);
+void _vkweigher_FuseBreakResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_FuseBreakResponse* msg, bool tao) {
+
+    (void)buffer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 8, &msg->result);
+
+    *bit_ofs += 8;
+
+
+
+
+
+}
+
+/*
+ decode vkweigher_FuseBreakResponse, return true on failure, false on success
+*/
+bool _vkweigher_FuseBreakResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_FuseBreakResponse* msg, bool tao) {
+
+    (void)transfer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 8, true, &msg->result);
+
+    *bit_ofs += 8;
+
+
+
+
+
+    return false; /* success */
+
+}
+#endif
+#ifdef CANARD_DSDLC_TEST_BUILD
+struct vkweigher_FuseBreakResponse sample_vkweigher_FuseBreakResponse_msg(void);
+#endif
+#ifdef __cplusplus
+} // extern "C"
+
+#ifdef DRONECAN_CXX_WRAPPERS
+#include <canard/cxx_wrappers.h>
+
+
+
+#endif
+#endif

+ 14 - 0
uav_can/user_inc/vkweigher.Version.h

@@ -0,0 +1,14 @@
+
+
+#pragma once
+#include <vkweigher.Version_req.h>
+#include <vkweigher.Version_res.h>
+
+#define VKWEIGHER_VERSION_ID 233
+#define VKWEIGHER_VERSION_SIGNATURE (0xE51B5A9BD0C35CCCULL)
+
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+#include <canard/cxx_wrappers.h>
+SERVICE_MESSAGE_CXX_IFACE(vkweigher_Version, VKWEIGHER_VERSION_ID, VKWEIGHER_VERSION_SIGNATURE, VKWEIGHER_VERSION_REQUEST_MAX_SIZE, VKWEIGHER_VERSION_RESPONSE_MAX_SIZE);
+#endif

+ 138 - 0
uav_can/user_inc/vkweigher.Version_req.h

@@ -0,0 +1,138 @@
+
+#pragma once
+#include <stdbool.h>
+#include <stdint.h>
+#include <canard.h>
+
+
+
+
+#define VKWEIGHER_VERSION_REQUEST_MAX_SIZE 5
+#define VKWEIGHER_VERSION_REQUEST_SIGNATURE (0xE51B5A9BD0C35CCCULL)
+
+#define VKWEIGHER_VERSION_REQUEST_ID 233
+
+
+
+
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+class vkweigher_Version_cxx_iface;
+#endif
+
+
+struct vkweigher_VersionRequest {
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+    using cxx_iface = vkweigher_Version_cxx_iface;
+#endif
+
+
+
+
+    uint8_t cmd;
+
+
+
+    uint32_t SN_num;
+
+
+
+};
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+uint32_t vkweigher_VersionRequest_encode(struct vkweigher_VersionRequest* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+);
+bool vkweigher_VersionRequest_decode(const CanardRxTransfer* transfer, struct vkweigher_VersionRequest* msg);
+
+#if defined(CANARD_DSDLC_INTERNAL)
+
+static inline void _vkweigher_VersionRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_VersionRequest* msg, bool tao);
+static inline bool _vkweigher_VersionRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_VersionRequest* msg, bool tao);
+void _vkweigher_VersionRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_VersionRequest* msg, bool tao) {
+
+    (void)buffer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 8, &msg->cmd);
+
+    *bit_ofs += 8;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 32, &msg->SN_num);
+
+    *bit_ofs += 32;
+
+
+
+
+
+}
+
+/*
+ decode vkweigher_VersionRequest, return true on failure, false on success
+*/
+bool _vkweigher_VersionRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_VersionRequest* msg, bool tao) {
+
+    (void)transfer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->cmd);
+
+    *bit_ofs += 8;
+
+
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->SN_num);
+
+    *bit_ofs += 32;
+
+
+
+
+
+    return false; /* success */
+
+}
+#endif
+#ifdef CANARD_DSDLC_TEST_BUILD
+struct vkweigher_VersionRequest sample_vkweigher_VersionRequest_msg(void);
+#endif
+#ifdef __cplusplus
+} // extern "C"
+
+#ifdef DRONECAN_CXX_WRAPPERS
+#include <canard/cxx_wrappers.h>
+
+
+
+#endif
+#endif

+ 155 - 0
uav_can/user_inc/vkweigher.Version_res.h

@@ -0,0 +1,155 @@
+
+#pragma once
+#include <stdbool.h>
+#include <stdint.h>
+#include <canard.h>
+
+
+
+
+#define VKWEIGHER_VERSION_RESPONSE_MAX_SIZE 20
+#define VKWEIGHER_VERSION_RESPONSE_SIGNATURE (0xE51B5A9BD0C35CCCULL)
+
+#define VKWEIGHER_VERSION_RESPONSE_ID 233
+
+
+
+
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+class vkweigher_Version_cxx_iface;
+#endif
+
+
+struct vkweigher_VersionResponse {
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+    using cxx_iface = vkweigher_Version_cxx_iface;
+#endif
+
+
+
+
+    int8_t fw_ver[16];
+
+
+
+    uint32_t SN_num;
+
+
+
+};
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+uint32_t vkweigher_VersionResponse_encode(struct vkweigher_VersionResponse* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+);
+bool vkweigher_VersionResponse_decode(const CanardRxTransfer* transfer, struct vkweigher_VersionResponse* msg);
+
+#if defined(CANARD_DSDLC_INTERNAL)
+
+static inline void _vkweigher_VersionResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_VersionResponse* msg, bool tao);
+static inline bool _vkweigher_VersionResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_VersionResponse* msg, bool tao);
+void _vkweigher_VersionResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_VersionResponse* msg, bool tao) {
+
+    (void)buffer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+
+    for (size_t i=0; i < 16; i++) {
+
+
+
+
+        canardEncodeScalar(buffer, *bit_ofs, 8, &msg->fw_ver[i]);
+
+        *bit_ofs += 8;
+
+
+    }
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 32, &msg->SN_num);
+
+    *bit_ofs += 32;
+
+
+
+
+
+}
+
+/*
+ decode vkweigher_VersionResponse, return true on failure, false on success
+*/
+bool _vkweigher_VersionResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_VersionResponse* msg, bool tao) {
+
+    (void)transfer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+    for (size_t i=0; i < 16; i++) {
+
+
+
+
+        canardDecodeScalar(transfer, *bit_ofs, 8, true, &msg->fw_ver[i]);
+
+        *bit_ofs += 8;
+
+
+    }
+
+
+
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->SN_num);
+
+    *bit_ofs += 32;
+
+
+
+
+
+    return false; /* success */
+
+}
+#endif
+#ifdef CANARD_DSDLC_TEST_BUILD
+struct vkweigher_VersionResponse sample_vkweigher_VersionResponse_msg(void);
+#endif
+#ifdef __cplusplus
+} // extern "C"
+
+#ifdef DRONECAN_CXX_WRAPPERS
+#include <canard/cxx_wrappers.h>
+
+
+
+#endif
+#endif

+ 14 - 0
uav_can/user_inc/vkweigher.WeigherCalib.h

@@ -0,0 +1,14 @@
+
+
+#pragma once
+#include <vkweigher.WeigherCalib_req.h>
+#include <vkweigher.WeigherCalib_res.h>
+
+#define VKWEIGHER_WEIGHERCALIB_ID 234
+#define VKWEIGHER_WEIGHERCALIB_SIGNATURE (0x4F91F98EF50104C7ULL)
+
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+#include <canard/cxx_wrappers.h>
+SERVICE_MESSAGE_CXX_IFACE(vkweigher_WeigherCalib, VKWEIGHER_WEIGHERCALIB_ID, VKWEIGHER_WEIGHERCALIB_SIGNATURE, VKWEIGHER_WEIGHERCALIB_REQUEST_MAX_SIZE, VKWEIGHER_WEIGHERCALIB_RESPONSE_MAX_SIZE);
+#endif

+ 115 - 0
uav_can/user_inc/vkweigher.WeigherCalib_req.h

@@ -0,0 +1,115 @@
+
+#pragma once
+#include <stdbool.h>
+#include <stdint.h>
+#include <canard.h>
+
+
+
+
+#define VKWEIGHER_WEIGHERCALIB_REQUEST_MAX_SIZE 4
+#define VKWEIGHER_WEIGHERCALIB_REQUEST_SIGNATURE (0x4F91F98EF50104C7ULL)
+
+#define VKWEIGHER_WEIGHERCALIB_REQUEST_ID 234
+
+
+
+
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+class vkweigher_WeigherCalib_cxx_iface;
+#endif
+
+
+struct vkweigher_WeigherCalibRequest {
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+    using cxx_iface = vkweigher_WeigherCalib_cxx_iface;
+#endif
+
+
+
+
+    uint32_t weight;
+
+
+
+};
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+uint32_t vkweigher_WeigherCalibRequest_encode(struct vkweigher_WeigherCalibRequest* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+);
+bool vkweigher_WeigherCalibRequest_decode(const CanardRxTransfer* transfer, struct vkweigher_WeigherCalibRequest* msg);
+
+#if defined(CANARD_DSDLC_INTERNAL)
+
+static inline void _vkweigher_WeigherCalibRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_WeigherCalibRequest* msg, bool tao);
+static inline bool _vkweigher_WeigherCalibRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_WeigherCalibRequest* msg, bool tao);
+void _vkweigher_WeigherCalibRequest_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_WeigherCalibRequest* msg, bool tao) {
+
+    (void)buffer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 32, &msg->weight);
+
+    *bit_ofs += 32;
+
+
+
+
+
+}
+
+/*
+ decode vkweigher_WeigherCalibRequest, return true on failure, false on success
+*/
+bool _vkweigher_WeigherCalibRequest_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_WeigherCalibRequest* msg, bool tao) {
+
+    (void)transfer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->weight);
+
+    *bit_ofs += 32;
+
+
+
+
+
+    return false; /* success */
+
+}
+#endif
+#ifdef CANARD_DSDLC_TEST_BUILD
+struct vkweigher_WeigherCalibRequest sample_vkweigher_WeigherCalibRequest_msg(void);
+#endif
+#ifdef __cplusplus
+} // extern "C"
+
+#ifdef DRONECAN_CXX_WRAPPERS
+#include <canard/cxx_wrappers.h>
+
+
+
+#endif
+#endif

+ 123 - 0
uav_can/user_inc/vkweigher.WeigherCalib_res.h

@@ -0,0 +1,123 @@
+
+#pragma once
+#include <stdbool.h>
+#include <stdint.h>
+#include <canard.h>
+
+
+
+
+#define VKWEIGHER_WEIGHERCALIB_RESPONSE_MAX_SIZE 1
+#define VKWEIGHER_WEIGHERCALIB_RESPONSE_SIGNATURE (0x4F91F98EF50104C7ULL)
+
+#define VKWEIGHER_WEIGHERCALIB_RESPONSE_ID 234
+
+
+
+#define VKWEIGHER_WEIGHERCALIB_RESPONSE_RESULT_SUCCESS 1
+
+#define VKWEIGHER_WEIGHERCALIB_RESPONSE_RESULT_REJECTED 0
+
+#define VKWEIGHER_WEIGHERCALIB_RESPONSE_RESULT_FAILED -1
+
+
+
+
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+class vkweigher_WeigherCalib_cxx_iface;
+#endif
+
+
+struct vkweigher_WeigherCalibResponse {
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+    using cxx_iface = vkweigher_WeigherCalib_cxx_iface;
+#endif
+
+
+
+
+    int8_t result;
+
+
+
+};
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+uint32_t vkweigher_WeigherCalibResponse_encode(struct vkweigher_WeigherCalibResponse* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+);
+bool vkweigher_WeigherCalibResponse_decode(const CanardRxTransfer* transfer, struct vkweigher_WeigherCalibResponse* msg);
+
+#if defined(CANARD_DSDLC_INTERNAL)
+
+static inline void _vkweigher_WeigherCalibResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_WeigherCalibResponse* msg, bool tao);
+static inline bool _vkweigher_WeigherCalibResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_WeigherCalibResponse* msg, bool tao);
+void _vkweigher_WeigherCalibResponse_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_WeigherCalibResponse* msg, bool tao) {
+
+    (void)buffer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 8, &msg->result);
+
+    *bit_ofs += 8;
+
+
+
+
+
+}
+
+/*
+ decode vkweigher_WeigherCalibResponse, return true on failure, false on success
+*/
+bool _vkweigher_WeigherCalibResponse_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_WeigherCalibResponse* msg, bool tao) {
+
+    (void)transfer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 8, true, &msg->result);
+
+    *bit_ofs += 8;
+
+
+
+
+
+    return false; /* success */
+
+}
+#endif
+#ifdef CANARD_DSDLC_TEST_BUILD
+struct vkweigher_WeigherCalibResponse sample_vkweigher_WeigherCalibResponse_msg(void);
+#endif
+#ifdef __cplusplus
+} // extern "C"
+
+#ifdef DRONECAN_CXX_WRAPPERS
+#include <canard/cxx_wrappers.h>
+
+
+
+#endif
+#endif

+ 341 - 0
uav_can/user_inc/vkweigher.WeigherStatus.h

@@ -0,0 +1,341 @@
+
+#pragma once
+#include <stdbool.h>
+#include <stdint.h>
+#include <canard.h>
+
+
+
+
+#define VKWEIGHER_WEIGHERSTATUS_MAX_SIZE 35
+#define VKWEIGHER_WEIGHERSTATUS_SIGNATURE (0x5B77380AAF093557ULL)
+
+#define VKWEIGHER_WEIGHERSTATUS_ID 52000
+
+
+
+
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+class vkweigher_WeigherStatus_cxx_iface;
+#endif
+
+
+struct vkweigher_WeigherStatus {
+
+#if defined(__cplusplus) && defined(DRONECAN_CXX_WRAPPERS)
+    using cxx_iface = vkweigher_WeigherStatus_cxx_iface;
+#endif
+
+
+
+
+    uint32_t weight;
+
+
+
+    uint16_t rate;
+
+
+
+    uint8_t status;
+
+
+
+    int16_t gx;
+
+
+
+    int16_t gy;
+
+
+
+    int16_t gz;
+
+
+
+    int16_t ax;
+
+
+
+    int16_t ay;
+
+
+
+    int16_t az;
+
+
+
+    float Q[4];
+
+
+
+};
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+uint32_t vkweigher_WeigherStatus_encode(struct vkweigher_WeigherStatus* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+);
+bool vkweigher_WeigherStatus_decode(const CanardRxTransfer* transfer, struct vkweigher_WeigherStatus* msg);
+
+#if defined(CANARD_DSDLC_INTERNAL)
+
+static inline void _vkweigher_WeigherStatus_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_WeigherStatus* msg, bool tao);
+static inline bool _vkweigher_WeigherStatus_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_WeigherStatus* msg, bool tao);
+void _vkweigher_WeigherStatus_encode(uint8_t* buffer, uint32_t* bit_ofs, struct vkweigher_WeigherStatus* msg, bool tao) {
+
+    (void)buffer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 32, &msg->weight);
+
+    *bit_ofs += 32;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 16, &msg->rate);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 8, &msg->status);
+
+    *bit_ofs += 8;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 16, &msg->gx);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 16, &msg->gy);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 16, &msg->gz);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 16, &msg->ax);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 16, &msg->ay);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+    canardEncodeScalar(buffer, *bit_ofs, 16, &msg->az);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+    for (size_t i=0; i < 4; i++) {
+
+
+
+
+        canardEncodeScalar(buffer, *bit_ofs, 32, &msg->Q[i]);
+
+        *bit_ofs += 32;
+
+
+    }
+
+
+
+
+
+}
+
+/*
+ decode vkweigher_WeigherStatus, return true on failure, false on success
+*/
+bool _vkweigher_WeigherStatus_decode(const CanardRxTransfer* transfer, uint32_t* bit_ofs, struct vkweigher_WeigherStatus* msg, bool tao) {
+
+    (void)transfer;
+    (void)bit_ofs;
+    (void)msg;
+    (void)tao;
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 32, false, &msg->weight);
+
+    *bit_ofs += 32;
+
+
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 16, false, &msg->rate);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 8, false, &msg->status);
+
+    *bit_ofs += 8;
+
+
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 16, true, &msg->gx);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 16, true, &msg->gy);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 16, true, &msg->gz);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 16, true, &msg->ax);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 16, true, &msg->ay);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+
+    canardDecodeScalar(transfer, *bit_ofs, 16, true, &msg->az);
+
+    *bit_ofs += 16;
+
+
+
+
+
+
+
+    for (size_t i=0; i < 4; i++) {
+
+
+
+
+        canardDecodeScalar(transfer, *bit_ofs, 32, true, &msg->Q[i]);
+
+        *bit_ofs += 32;
+
+
+    }
+
+
+
+
+
+
+    return false; /* success */
+
+}
+#endif
+#ifdef CANARD_DSDLC_TEST_BUILD
+struct vkweigher_WeigherStatus sample_vkweigher_WeigherStatus_msg(void);
+#endif
+#ifdef __cplusplus
+} // extern "C"
+
+#ifdef DRONECAN_CXX_WRAPPERS
+#include <canard/cxx_wrappers.h>
+
+
+BROADCAST_MESSAGE_CXX_IFACE(vkweigher_WeigherStatus, VKWEIGHER_WEIGHERSTATUS_ID, VKWEIGHER_WEIGHERSTATUS_SIGNATURE, VKWEIGHER_WEIGHERSTATUS_MAX_SIZE);
+
+
+#endif
+#endif

+ 1960 - 0
uav_can/user_src/canard.c

@@ -0,0 +1,1960 @@
+/*
+ * 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 <string.h>
+
+
+#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; i<padding; i++) {
+                crc = crcAddByte(crc, empty);
+            }
+        }
+#endif
+    }
+    return crc;
+}
+
+int16_t canardRequestOrRespond(CanardInstance* ins,
+                               uint8_t destination_node_id,
+                               uint64_t data_type_signature,
+                               uint8_t data_type_id,
+                               uint8_t* inout_transfer_id,
+                               uint8_t priority,
+                               CanardRequestResponse kind,
+                               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
+)
+{
+    CanardTxTransfer transfer_object = {
+        .data_type_signature = data_type_signature,
+        .data_type_id = data_type_id,
+        .inout_transfer_id = inout_transfer_id,
+        .priority = priority,
+        .transfer_type = kind == CanardRequest ? CanardTransferTypeRequest : CanardTransferTypeResponse,
+        .payload = 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 canardRequestOrRespondObj(ins, destination_node_id, &transfer_object);
+}
+
+int16_t canardRequestOrRespondObj(CanardInstance* ins, uint8_t destination_node_id, 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;
+    }
+    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)
+	{
+	    // we should return -CANARD_ERROR_RX_NOT_WANTED for
+	    // non-start frames where we have rejected the start of
+	    // transfer.  doing it here avoids calling the potentially
+	    // expensive should_accept() on every frame in messages we
+	    // will be accepting
+	    if (!ins->should_accept(ins, &data_type_signature, data_type_id, transfer_type, source_node_id)) {
+		return -CANARD_ERROR_RX_NOT_WANTED;
+	    }
+	    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<std_byte_length; i++)
+        {
+            temp |= (((uint64_t)storage.bytes[i] & 0xFFU) << (8*i));
+        }
+        storage.u64 = temp;
+    }
+#endif
+
+    /*
+     * Extending the sign bit if needed. I miss templates.
+     * Note that we operate on unsigned values in order to avoid undefined behaviors.
+     */
+    if (value_is_signed && (std_byte_length * 8 != bit_length))
+    {
+        if (bit_length <= 8)
+        {
+            if ((storage.u8 & (1U << (bit_length - 1U))) != 0)                           // If the sign bit is set...
+            {
+                storage.u8 |= (uint8_t) 0xFFU & (uint8_t) ~((1U << bit_length) - 1U);   // ...set all bits above it.
+            }
+        }
+        else if (bit_length <= 16)
+        {
+            if ((storage.u16 & (1U << (bit_length - 1U))) != 0)
+            {
+                storage.u16 |= (uint16_t) 0xFFFFU & (uint16_t) ~((1U << bit_length) - 1U);
+            }
+        }
+        else if (bit_length <= 32)
+        {
+            if ((storage.u32 & (((uint32_t) 1) << (bit_length - 1U))) != 0)
+            {
+                storage.u32 |= (uint32_t) 0xFFFFFFFFUL & (uint32_t) ~((((uint32_t) 1) << bit_length) - 1U);
+            }
+        }
+        else if (bit_length < 64)   // Strictly less, this is not a typo
+        {
+            if ((storage.u64 & (((uint64_t) 1) << (bit_length - 1U))) != 0)
+            {
+                storage.u64 |= (uint64_t) 0xFFFFFFFFFFFFFFFFULL & (uint64_t) ~((((uint64_t) 1) << bit_length) - 1U);
+            }
+        }
+        else
+        {
+            CANARD_ASSERT(false);
+            return -CANARD_ERROR_INTERNAL;
+        }
+    }
+
+    /*
+     * Copying the result out.
+     */
+    if (value_is_signed)
+    {
+        if      (bit_length <= 8)   { *( (int8_t*) out_value) = storage.s8;  }
+        else if (bit_length <= 16)  { *((int16_t*) out_value) = storage.s16; }
+        else if (bit_length <= 32)  { *((int32_t*) out_value) = storage.s32; }
+        else if (bit_length <= 64)  { *((int64_t*) out_value) = storage.s64; }
+        else
+        {
+            CANARD_ASSERT(false);
+            return -CANARD_ERROR_INTERNAL;
+        }
+    }
+    else
+    {
+        if      (bit_length == 1)   { *(    (bool*) out_value) = storage.boolean; }
+        else if (bit_length <= 8)   { *( (uint8_t*) out_value) = storage.u8;  }
+        else if (bit_length <= 16)  { *((uint16_t*) out_value) = storage.u16; }
+        else if (bit_length <= 32)  { *((uint32_t*) out_value) = storage.u32; }
+        else if (bit_length <= 64)  { *((uint64_t*) out_value) = storage.u64; }
+        else
+        {
+            CANARD_ASSERT(false);
+            return -CANARD_ERROR_INTERNAL;
+        }
+    }
+
+    CANARD_ASSERT(result <= bit_length);
+    CANARD_ASSERT(result > 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<std_byte_length; i++)
+        {
+            storage.bytes[i] = (temp >> (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;
+
+        /*
+          see if we are going to be able to allocate enough blocks for
+          this transfer. If not then stop now, otherwise we will end
+          up doing a partial (corrupt) transfer which will just make
+          the situation worse as it will waste bus bandwidth
+         */
+        const uint16_t total_bytes = transfer->payload_len + 2; // including CRC
+        const uint8_t bytes_per_frame = frame_max_data_len-1; // sot/eot byte consumes one byte
+        const uint16_t frames_needed = (total_bytes + (bytes_per_frame-1)) / bytes_per_frame;
+        const uint16_t blocks_available = ins->allocator.statistics.capacity_blocks - ins->allocator.statistics.current_usage_blocks;
+        if (blocks_available < frames_needed) {
+            return -CANARD_ERROR_OUT_OF_MEMORY;
+        }
+
+        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;
+            }
+
+            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
+}

+ 251 - 0
uav_can/user_src/dronecan.c

@@ -0,0 +1,251 @@
+#include "dronecan.h"
+#include "drv_vkweigher_vls300.h"
+#include <string.h>
+#include "soft_timer.h"
+static struct dronecan __dronecan = {0};
+
+uint8_t memory_pool[DRONECAN_CANARD_MEMORY_POOL_SIZE] = {0};
+CanardInstance canard_ins;
+
+bool dronecan_lock_status = false;
+void dronecan_lock() {
+  dronecan_lock_status = 1;
+}
+void dronecan_unlock() {
+  dronecan_lock_status = 0;
+}
+
+
+int dronecan_request_or_respond(uint8_t dest_id,
+                                CanardTxTransfer *tx_transfer) {
+  int ret = 0;
+
+  if (dronecan_lock_status == UNLOCK) {
+    dronecan_lock();
+    ret = canardRequestOrRespondObj(&canard_ins, dest_id, tx_transfer);
+    dronecan_unlock();
+  }
+
+  return ret;
+}
+
+
+static void onTransferReceived(CanardInstance *ins,
+                               CanardRxTransfer *transfer) {
+
+  // if (flyfire_onRecieved(ins, transfer)) {
+  //   return;
+  // } else if (hbwEscOnRecieved(ins, transfer)) {
+  //   return;
+  // } else if (sinemotorEscOnRecieved(ins, transfer)) {
+  //   return;
+  // } else if (tmotorEscOnRecieved(ins, transfer)) {
+  //   return;
+  // } else if (uavcanEscOnRecieved(ins, transfer)) {
+  //   return;
+  // } else 
+  if (vkWeigher_Vls300_OnRecieved(ins, transfer)) {
+    return;
+  }
+}
+
+static bool shouldAcceptTransfer(const CanardInstance *ins,
+                                 uint64_t *out_data_type_signature,
+                                 uint16_t data_type_id,
+                                 CanardTransferType transfer_type,
+                                 uint8_t source_node_id) {
+
+  // /* 火萤降落伞相关消息 */
+  // if (flyfireShouldAcceptTransfer(ins, out_data_type_signature, data_type_id,
+  //                                 transfer_type, source_node_id)) {
+  //   return true;
+  // }
+
+  // /* 好盈电调相关消息 */
+  // if (hbwEscShouldAcceptTransfer(ins, out_data_type_signature, data_type_id,
+  //                                transfer_type, source_node_id)) {
+  //   return true;
+  // }
+
+  // /* 弦动电调相关消息 */
+  // if (sinemotorEscShouldAcceptTransfer(ins, out_data_type_signature,
+  //                                      data_type_id, transfer_type,
+  //                                      source_node_id)) {
+  //   return true;
+  // }
+
+  // /* tmotor电调相关消息 */
+  // if (tmotorEscShouldAcceptTransfer(ins, out_data_type_signature, data_type_id,
+  //                                   transfer_type, source_node_id)) {
+  //   return true;
+  // }
+
+  // /* uavcan电调相关消息 */
+  // if (uavcanEscShouldAcceptTransfer(ins, out_data_type_signature, data_type_id,
+  //                                   transfer_type, source_node_id)) {
+  //   return true;
+  // }
+
+  /* dronecan weigher 称重器相关消息 */
+  if (vkWeigher_Vls300_shouldAcceptTransfer(ins, out_data_type_signature,
+                                            data_type_id, transfer_type,
+                                            source_node_id)) {
+    return true;
+  }
+
+  return false;
+}
+
+// static void send_node_status(struct dronecan *dcan) {
+//   static uint8_t transfer_id = 0;
+
+//   struct uavcan_protocol_NodeStatus msg;
+
+//   uint8_t buffer[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE] = {0};
+
+//   msg.uptime_sec = systime_now_ms() / 1000;
+//   msg.sub_mode = 0;
+//   msg.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL;
+//   msg.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK;
+
+//   uint32_t len = uavcan_protocol_NodeStatus_encode(&msg, buffer);
+
+//   CanardTxTransfer tx_transfer = {
+//       .data_type_signature = UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE,
+//       .data_type_id = UAVCAN_PROTOCOL_NODESTATUS_ID,
+//       .inout_transfer_id = &transfer_id,
+//       .priority = CANARD_TRANSFER_PRIORITY_MEDIUM,
+//       .transfer_type = CanardTransferTypeBroadcast,
+//       .payload = buffer,
+//       .payload_len = len,
+//       .iface_mask = 0xff, /* 发送到所有接口 */
+//   };
+
+//   dronecan_broadcast(dcan, &tx_transfer);
+// }
+
+void dronecan_tx_processing(void) {
+
+  struct dronecan *dcan = &__dronecan;
+
+  // Transmit the frames in the queue.
+  while (1) {
+    CanardCANFrame tx_frame = {0};
+
+    CanardCANFrame *tx_frame_p = NULL;
+    if( dronecan_lock_status == UNLOCK )
+    {
+      dronecan_lock();
+      tx_frame_p = canardPeekTxQueue(&canard_ins);
+      if (tx_frame_p == NULL) 
+      {
+        /* 没有发送消息, 结束发送 */
+        dronecan_unlock();
+        break;
+      }
+    }
+    else
+    {
+      break;
+    }
+    
+    /* 将消息拷贝出来 */
+    memcpy(&tx_frame, tx_frame_p, sizeof(tx_frame));
+    canardPopTxQueue(&canard_ins);
+    dronecan_unlock(dcan);
+    /* 通过 can 接口发送消息 */ 
+
+    can_send_msg_normal(tx_frame.data, tx_frame.data_len, tx_frame.id);
+
+  }
+
+  static int clear_time = 0;
+  /* 每秒清理一次 canard 过期消息 */
+  if( HAL_GetTick() - clear_time > 1000 )
+  {
+    if( dronecan_lock_status == UNLOCK )
+    {
+      clear_time = HAL_GetTick();
+      dronecan_lock();
+      canardCleanupStaleTransfers(&canard_ins, Get_Systimer_Us());
+      dronecan_unlock();
+    }
+  }
+}
+
+/**
+ * @brief dronecan 回调函数, 当 can 接口接收到消息时调用
+ *
+ * @param msg can 消息
+ * @param iface_id can 接口 id, 用于管理多个不同 can 接口
+ * @return int 1-是 dronecan 消息, 0-不是 dronecan 消息
+ */
+int dronecan_rx_callback(CAN_RxHeaderTypeDef Rxhead,uint8_t data[]) {
+  int ret = 0;
+
+  CanardCANFrame rx_frame = {0};
+  rx_frame.id = Rxhead.ExtId;
+  if (Rxhead.IDE == CAN_ID_EXT) {
+    rx_frame.id |= CANARD_CAN_FRAME_EFF;
+  }
+  if (Rxhead.RTR == CAN_RTR_REMOTE) {
+    rx_frame.id |= CANARD_CAN_FRAME_RTR;
+  }
+  rx_frame.data_len = Rxhead.DLC;
+
+  memcpy(rx_frame.data, &data[0], Rxhead.DLC);
+  uint64_t timestamp = Get_Systimer_Us();
+
+  int16_t res;
+  if(dronecan_lock_status == UNLOCK)
+  {
+    dronecan_lock();
+    res = canardHandleRxFrame(&canard_ins, &rx_frame, timestamp);
+    dronecan_unlock();
+  }
+
+  if (res == CANARD_OK) {
+    ret = 1;
+  }
+
+  return ret;
+}
+
+// static void timer_out_cb(void *arg) {
+//   if (arg) {
+//     struct dronecan *dcan = arg;
+//     send_node_status(dcan);
+//   }
+// }
+
+
+void dronecan_init(void) {
+
+  struct dronecan *dcan = &__dronecan;
+  canardInit(&canard_ins, &memory_pool,
+             DRONECAN_CANARD_MEMORY_POOL_SIZE, onTransferReceived,
+             shouldAcceptTransfer, dcan);
+  canardSetLocalNodeID(&canard_ins,
+                       DRONECAN_CANARD_DEFAULT_LOCAL_NODE_ID);
+
+}
+
+/**
+ * @brief dronecan 发送广播消息
+ *
+ * @param dcan dronecan 对象
+ * @param tx_transfer 发送消息对象
+ * @return int 发送到 canard 发送队列的消息计数
+ */
+int dronecan_broadcast(struct dronecan *dcan, CanardTxTransfer *tx_transfer) {
+  int ret = 0;
+
+  if (dronecan_lock_status == UNLOCK) {
+    dronecan_lock();
+    ret = canardBroadcastObj(&canard_ins, tx_transfer);
+    dronecan_unlock();
+  }
+
+  return ret;
+}
+

+ 567 - 0
uav_can/user_src/drv_vkweigher_vls300.c

@@ -0,0 +1,567 @@
+#include "drv_vkweigher_vls300.h"
+#include "dronecan.h"
+#include "sys/time.h"
+#include <fcntl.h>
+#include <stdint.h>
+#include <stdio.h>
+#include <sys/stat.h>
+#include <sys/types.h>
+#include <unistd.h>
+#include "vkweigher.Version_res.h"
+#include "vkweigher.WeigherStatus.h"
+#include "vkweigher.WeigherCalib_req.h"
+#include "vkweigher.WeigherCalib_res.h"
+#include "vkweigher.FuseBreak_req.h"
+#include "vkweigher.FuseBreak_res.h"
+#include "vkweigher.Version_req.h"
+#include "soft_timer.h"
+#include "string.h"
+#include "soft_seed_device.h"
+
+struct vk_weigher_vls300 _vk_vls300;
+
+// static rt_size_t read_data(rt_device_t dev, weigher_data_t *data) {
+
+//   struct weigher_device *weigher =
+//       rt_container_of(dev, struct weigher_device, parent);
+
+//   struct vk_weigher_vls300 *vls300 =
+//       rt_container_of(weigher, struct vk_weigher_vls300, weigher_dev);
+
+//   rt_size_t size = 0;
+
+//   rt_enter_critical();
+//   if (vls300->status_data.timestamp > 0 && vls300->data_got == RT_TRUE) {
+//     vls300->data_got = RT_FALSE;
+//     data->timestamp_ms = vls300->status_data.timestamp;
+//     data->weight = vls300->status_data.weight;
+//     data->weight_dot = vls300->status_data.weight_dot;
+//     data->ucode[0] = vls300->status_data.status;
+//     data->ucode[1] = vls300->status_data.status >> 8;
+
+//     for (int i = 0; i < 3; ++i) {
+//       data->acce[i] = vls300->status_data.acce[i];
+//       data->gyro[i] = vls300->status_data.gyro[i];
+//     }
+
+//     for (int i = 0; i < 4; ++i) {
+//       data->Q[i] = vls300->status_data.Q[i];
+//     }
+//     size = sizeof(weigher_data_t);
+//   }
+//   rt_exit_critical();
+
+//   return size;
+// }
+
+// static rt_ssize_t read_version(rt_device_t dev, weigher_version_t *version) {
+//   RT_ASSERT(dev != RT_NULL);
+//   RT_ASSERT(version != RT_NULL);
+
+//   struct weigher_device *weigher =
+//       rt_container_of(dev, struct weigher_device, parent);
+
+//   struct vk_weigher_vls300 *vls300 =
+//       rt_container_of(weigher, struct vk_weigher_vls300, weigher_dev);
+
+//   rt_ssize_t size = 0;
+
+//   rt_enter_critical();
+//   if (vls300->version.timestamp > 0) {
+//     version->timestamp_ms = vls300->version.timestamp;
+//     rt_snprintf(version->sn_num, sizeof(version->sn_num), "%u",
+//                 vls300->version.SN_num);
+//     rt_strncpy(version->fw_ver, (char *)vls300->version.fw_ver,
+//                sizeof(version->fw_ver));
+//     rt_strncpy(version->hw_ver, "VLS300", sizeof(version->hw_ver));
+//     rt_strncpy(version->manufactory, "VKFLY", sizeof(version->manufactory));
+//     size = sizeof(weigher_version_t);
+//   }
+//   rt_exit_critical();
+
+//   return size;
+// }
+
+// uint8_t vklift_weight_calibrate(uint32_t weight) 
+// {
+//   static uint8_t transfer_id = 0;
+
+//   struct vkweigher_WeigherCalibRequest msg = {0};
+//   msg.weight = weight;
+
+//   uint8_t buffer[VKWEIGHER_WEIGHERCALIB_REQUEST_MAX_SIZE] = {0};
+//   memcpy(buffer,&msg.weight,sizeof(msg.weight));
+//   uint8_t len = vkweigher_WeigherCalibRequest_encode(&msg, buffer);
+//   CanardTxTransfer tranxfer = {
+//       .inout_transfer_id = &transfer_id,
+//       .transfer_type = CanardTransferTypeRequest,
+//       .data_type_id = VKWEIGHER_WEIGHERCALIB_REQUEST_ID,
+//       .data_type_signature = VKWEIGHER_WEIGHERCALIB_REQUEST_SIGNATURE,
+//       .priority = CANARD_TRANSFER_PRIORITY_LOW,
+//       .payload = buffer,
+//       .payload_len = len,
+//   };
+
+//    dronecan_request_or_respond(DRONECAN_WEIGHER_NODE_ID, &tranxfer);
+
+//   return 1;
+// }
+
+// static rt_err_t fuse_prot(rt_device_t dev, void *args) {
+
+//   RT_ASSERT(dev != RT_NULL);
+
+//   struct weigher_device *weigher =
+//       rt_container_of(dev, struct weigher_device, parent);
+
+//   struct vk_weigher_vls300 *vls300 =
+//       rt_container_of(weigher, struct vk_weigher_vls300, weigher_dev);
+
+//   static uint8_t transfer_id = 0;
+
+//   struct vkweigher_FuseBreakRequest msg = {0};
+//   msg.break_cmd = *(uint8_t *)args;
+
+//   uint8_t buffer[VKWEIGHER_FUSEBREAK_REQUEST_MAX_SIZE] = {0};
+//   uint8_t len = vkweigher_FuseBreakRequest_encode(&msg, buffer);
+
+//   if (vls300->canard != RT_NULL) {
+//     CanardTxTransfer tranxfer = {
+//         .inout_transfer_id = &transfer_id,
+//         .transfer_type = CanardTransferTypeRequest,
+//         .data_type_id = VKWEIGHER_FUSEBREAK_REQUEST_ID,
+//         .data_type_signature = VKWEIGHER_FUSEBREAK_REQUEST_SIGNATURE,
+//         .priority = CANARD_TRANSFER_PRIORITY_MEDIUM,
+//         .payload = buffer,
+//         .payload_len = len,
+//         .iface_mask = vls300->iface_mask,
+//     };
+//     struct dronecan *dcan = (struct dronecan *)vls300->canard->user_reference;
+//     dronecan_request_or_respond(DRONECAN_WEIGHER_NODE_ID, &tranxfer);
+//   }
+
+//   return RT_EOK;
+// }
+
+// static rt_err_t factory_reset(rt_device_t dev, void *args) { return RT_EOK; }
+
+// static rt_err_t set_sn(rt_device_t dev, uint32_t SN) {
+//   RT_ASSERT(dev != RT_NULL);
+//   RT_ASSERT(data != RT_NULL);
+
+//   static uint8_t transfer_id = 0;
+
+//   struct weigher_device *weigher =
+//       rt_container_of(dev, struct weigher_device, parent);
+
+//   struct vk_weigher_vls300 *vls300 =
+//       rt_container_of(weigher, struct vk_weigher_vls300, weigher_dev);
+
+//   struct vkweigher_VersionRequest msg = {0};
+//   msg.cmd = 1;
+//   msg.SN_num = SN;
+
+//   uint8_t buffer[VKWEIGHER_VERSION_REQUEST_MAX_SIZE] = {0};
+
+//   uint8_t len = vkweigher_VersionRequest_encode(&msg, buffer);
+
+//   CanardTxTransfer tranxfer = {
+//       .inout_transfer_id = &transfer_id,
+//       .transfer_type = CanardTransferTypeRequest,
+//       .data_type_id = VKWEIGHER_VERSION_REQUEST_ID,
+//       .data_type_signature = VKWEIGHER_VERSION_REQUEST_SIGNATURE,
+//       .priority = CANARD_TRANSFER_PRIORITY_LOW,
+//       .payload = buffer,
+//       .payload_len = len,
+//       .iface_mask = vls300->iface_mask,
+//   };
+//   struct dronecan *dcan = (struct dronecan *)vls300->canard->user_reference;
+//   dronecan_request_or_respond(DRONECAN_WEIGHER_NODE_ID, &tranxfer);
+
+//   return RT_EOK;
+// }
+static void req_version(struct vk_weigher_vls300 *vls300) {
+
+  static uint8_t transfer_id = 0;
+  if (vls300->canard != NULL) {
+    struct vkweigher_VersionRequest msg = {0};
+    msg.cmd = 0;
+
+    uint8_t buffer[VKWEIGHER_VERSION_REQUEST_MAX_SIZE] = {0};
+
+    uint8_t len = vkweigher_VersionRequest_encode(&msg, buffer);
+
+    CanardTxTransfer tranxfer = {
+        .inout_transfer_id = &transfer_id,
+        .transfer_type = CanardTransferTypeRequest,
+        .data_type_id = VKWEIGHER_VERSION_REQUEST_ID,
+        .data_type_signature = VKWEIGHER_VERSION_REQUEST_SIGNATURE,
+        .priority = CANARD_TRANSFER_PRIORITY_LOW,
+        .payload = buffer,
+        .payload_len = len,
+    };
+    dronecan_request_or_respond(DRONECAN_WEIGHER_NODE_ID, &tranxfer);
+  }
+}
+
+
+// static void handle_fw_update(CanardRxTransfer *transfer) {
+//   RT_ASSERT(transfer != RT_NULL);
+//   if (transfer->transfer_type == CanardTransferTypeRequest) {
+//     switch (transfer->data_type_id) {
+//     case UAVCAN_PROTOCOL_FILE_GETINFO_REQUEST_ID: {
+//       /* 处理固件信息请求 */
+//       struct uavcan_protocol_file_GetInfoRequest req = {0};
+//       if (!uavcan_protocol_file_GetInfoRequest_decode(transfer, &req)) {
+//         if (rt_strncmp((char *)req.path.path.data, "VLS300.bin",
+//                        req.path.path.len) == 0) {
+//           rt_event_send(_vk_vls300->_event,
+//                         VLS300_EVENT_GOT_FW_UPDATE_INFO_ACK);
+//         }
+//       }
+//     } break;
+//     case UAVCAN_PROTOCOL_FILE_READ_REQUEST_ID: {
+//       /* 处理固件数据读取请求 */
+//       rt_event_send(_vk_vls300->_event, VLS300_EVENT_GOT_FW_UPDATE_DATA_ACK);
+//     } break;
+//     default:
+//       break;
+//     }
+//   } else if (transfer->transfer_type == CanardTransferTypeResponse) {
+//     switch (transfer->data_type_id) {
+//     case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ID: {
+//       rt_event_send(_vk_vls300->_event, VLS300_EVENT_GOT_FW_UPDATE_START_ACK);
+//     } break;
+//     default:
+//       break;
+//     }
+//   }
+// };
+
+int vkWeigher_Vls300_OnRecieved(CanardInstance *canardIns,
+                                CanardRxTransfer *transfer) {
+
+  int ret = 0;
+
+  if (transfer->transfer_type == CanardTransferTypeBroadcast) {
+    /* weigher 广播帧 */
+    switch (transfer->data_type_id) {
+
+    case VKWEIGHER_WEIGHERSTATUS_ID: {
+      struct vkweigher_WeigherStatus status = {0};
+      if (!vkweigher_WeigherStatus_decode(transfer, &status)) {
+
+          Dev.Lift_Weight_Link.connect_status = COMP_NORMAL;
+          Dev.Lift_Weight_Link.recv_time = HAL_GetTick();
+          Dev.Lift_Weight.facid = FAC_VK;
+
+          _vk_vls300.data_got = true;
+          _vk_vls300.status_data.timestamp = Get_Systimer_Us();
+          _vk_vls300.status_data.weight = status.weight;
+          _vk_vls300.status_data.weight_dot = status.rate;
+          _vk_vls300.status_data.status = status.status;
+          _vk_vls300.status_data.acce[0] = status.ax;
+          _vk_vls300.status_data.acce[1] = status.ay;
+          _vk_vls300.status_data.acce[2] = status.az;
+          _vk_vls300.status_data.gyro[0] = status.gx;
+          _vk_vls300.status_data.gyro[1] = status.gy;
+          _vk_vls300.status_data.gyro[2] = status.gz;
+
+          for (int i = 0; i < 4; i++) {
+            _vk_vls300.status_data.Q[i] = status.Q[i];
+          }
+
+
+        /* 若未收到版本信息, 则主动请求一次版本信息 */
+        if (_vk_vls300.version.timestamp == 0) {
+          req_version(&_vk_vls300);
+        }
+      }
+      ret = 1;
+    } break;
+
+    default:
+      break;
+    }
+  } else if (transfer->transfer_type == CanardTransferTypeResponse) {
+    /* weigher 应答帧 */
+    switch (transfer->data_type_id) {
+
+    case VKWEIGHER_VERSION_RESPONSE_ID: {
+      struct vkweigher_VersionResponse msg = {0};
+      if (!vkweigher_VersionResponse_decode(transfer, &msg)) {
+        /* 收到 version 消息回令 */
+          _vk_vls300.version.timestamp = Get_Systimer_Us();
+          memcpy(_vk_vls300.version.fw_ver, msg.fw_ver, sizeof(msg.fw_ver));
+          _vk_vls300.version.SN_num = msg.SN_num;
+
+      }
+      ret = 1;
+    } break;
+
+    case VKWEIGHER_FUSEBREAK_RESPONSE_ID: {
+      struct vkweigher_FuseBreakResponse msg = {0};
+      if (!vkweigher_FuseBreakResponse_decode(transfer, &msg)) {
+        /* 收到 fuse break 消息回令 */
+      }
+      ret = 1;
+    } break;
+
+    case VKWEIGHER_WEIGHERCALIB_RESPONSE_ID: {
+      struct vkweigher_WeigherCalibResponse msg = {0};
+      if (!vkweigher_WeigherCalibResponse_decode(transfer, &msg)) {
+        /* 收到 calibrate 消息回令 */
+      }
+      ret = 1;
+    } break;
+
+    // case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ID:
+    // case UAVCAN_PROTOCOL_FILE_GETINFO_REQUEST_ID:
+    // case UAVCAN_PROTOCOL_FILE_READ_REQUEST_ID:
+    //   handle_fw_update(transfer);
+    //   break;
+
+    default:
+      break;
+    }
+  }
+
+  return ret;
+}
+
+bool vkWeigher_Vls300_shouldAcceptTransfer(const CanardInstance *ins,
+                                           uint64_t *out_data_type_signature,
+                                           uint16_t data_type_id,
+                                           CanardTransferType transfer_type,
+                                           uint8_t source_node_id) {
+
+  bool ret = false;
+
+  if (data_type_id == VKWEIGHER_WEIGHERSTATUS_ID &&
+      transfer_type == CanardTransferTypeBroadcast) {
+    *out_data_type_signature = VKWEIGHER_WEIGHERSTATUS_SIGNATURE;
+    ret = true;
+  } else if (data_type_id == VKWEIGHER_VERSION_RESPONSE_ID &&
+             transfer_type == CanardTransferTypeResponse) {
+    *out_data_type_signature = VKWEIGHER_VERSION_RESPONSE_SIGNATURE;
+    ret = true;
+  } else if (data_type_id == VKWEIGHER_FUSEBREAK_RESPONSE_ID &&
+             transfer_type == CanardTransferTypeResponse) {
+    *out_data_type_signature = VKWEIGHER_FUSEBREAK_RESPONSE_SIGNATURE;
+    ret = true;
+  } else if (data_type_id == VKWEIGHER_WEIGHERCALIB_RESPONSE_ID &&
+             transfer_type == CanardTransferTypeResponse) {
+    *out_data_type_signature = VKWEIGHER_WEIGHERCALIB_RESPONSE_SIGNATURE;
+    ret = true;
+  }
+  // } else if (data_type_id ==
+  //                UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ID &&
+  //            (transfer_type == CanardTransferTypeResponse)) {
+  //   *out_data_type_signature =
+  //       UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_SIGNATURE;
+  //   ret = true;
+  // } else if (data_type_id == UAVCAN_PROTOCOL_FILE_GETINFO_REQUEST_ID &&
+  //            transfer_type == CanardTransferTypeRequest) {
+  //   *out_data_type_signature = UAVCAN_PROTOCOL_FILE_GETINFO_REQUEST_SIGNATURE;
+  //   ret = true;
+  // } else if (data_type_id == UAVCAN_PROTOCOL_FILE_READ_REQUEST_ID &&
+  //            transfer_type == CanardTransferTypeRequest) {
+  //   *out_data_type_signature = UAVCAN_PROTOCOL_FILE_READ_REQUEST_SIGNATURE;
+  //   ret = true;
+  // }
+
+  return ret;
+}
+
+// static void fw_update_start(struct vk_weigher_vls300 *vls300,
+//                             CanardInstance *canardIns) {
+//   /* 发送升级开始 */
+//   struct uavcan_protocol_file_BeginFirmwareUpdateRequest req = {0};
+//   uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_REQUEST_MAX_SIZE] = {
+//       0};
+//   static uint8_t transfer_id = 0;
+
+//   req.source_node_id = DRONECAN_FMU_NODE_ID;
+//   req.image_file_remote_path.path.len = rt_strlen("VLS300.bin");
+//   rt_memcpy((char *)req.image_file_remote_path.path.data, "VLS300.bin",
+//             req.image_file_remote_path.path.len);
+
+//   uint32_t len =
+//       uavcan_protocol_file_BeginFirmwareUpdateRequest_encode(&req, buffer);
+
+//   CanardTxTransfer tx_transfer = {
+//       .data_type_signature =
+//           UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_REQUEST_SIGNATURE,
+//       .data_type_id = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_REQUEST_ID,
+//       .inout_transfer_id = &transfer_id,
+//       .priority = CANARD_TRANSFER_PRIORITY_MEDIUM,
+//       .transfer_type = CanardTransferTypeRequest,
+//       .payload = buffer,
+//       .payload_len = len,
+//   };
+//   struct dronecan *dcan = (struct dronecan *)canardIns->user_reference;
+//   dronecan_request_or_respond(DRONECAN_FMU_NODE_ID, &tx_transfer);
+// }
+
+// static void fw_update_send_info(struct vk_weigher_vls300 *vls300,
+//                                 uint32_t fw_size, CanardInstance *canardIns) {
+//   /* 发送升级信息 */
+//   struct uavcan_protocol_file_GetInfoResponse res = {0};
+//   static uint8_t transfer_id = 0;
+//   uint8_t buffer[UAVCAN_PROTOCOL_FILE_GETINFO_RESPONSE_MAX_SIZE] = {0};
+
+//   res.size = fw_size;
+//   res.error.value = UAVCAN_PROTOCOL_FILE_ERROR_OK;
+
+//   uint32_t len = uavcan_protocol_file_GetInfoResponse_encode(&res, buffer);
+//   CanardTxTransfer tx_transfer = {
+//       .data_type_signature = UAVCAN_PROTOCOL_FILE_GETINFO_RESPONSE_SIGNATURE,
+//       .data_type_id = UAVCAN_PROTOCOL_FILE_GETINFO_RESPONSE_ID,
+//       .inout_transfer_id = &transfer_id,
+//       .priority = CANARD_TRANSFER_PRIORITY_MEDIUM,
+//       .transfer_type = CanardTransferTypeResponse,
+//       .payload = buffer,
+//       .payload_len = len,
+//   };
+//   struct dronecan *dcan = (struct dronecan *)canardIns->user_reference;
+//   dronecan_request_or_respond(DRONECAN_FMU_NODE_ID, &tx_transfer);
+// }
+
+// static void fw_update_data(struct vk_weigher_vls300 *vls300, uint16_t pack_num,
+//                            const uint8_t data[128 + 2]) {
+//   //   send_data_to_vkgps(vls300, _MSGID_MCTOGPS_UPDATE_DATA, data, 128 + 4);
+// }
+
+// static int do_fw_update(struct vk_weigher_vls300 *vls300,
+//                         const char *fw_file_name, CanardInstance *canardIns,
+//                         CanardRxTransfer *transfer) {
+//   RT_ASSERT(vls300 != RT_NULL);
+//   RT_ASSERT(fw_file_name != RT_NULL);
+//   const uint32_t PACK_BYTES_LEN = 128;
+//   uint8_t buff[PACK_BYTES_LEN + 2];
+//   /* 获取fd文件的大小 */
+//   struct stat stat;
+//   uint32_t fw_byte_size = 0;
+//   int fd = open(fw_file_name, O_RDONLY);
+
+//   if (fd < 0) {
+//     LOG_E("open file %s failed!", fw_file_name);
+//     return -1;
+//   }
+
+//   if (fstat(fd, &stat) == 0) {
+//     fw_byte_size = stat.st_size;
+//   } else {
+//     /* 固件文件描述符异常 */
+//     close(fd);
+//     return -1;
+//   }
+
+//   uint8_t retry_cnt = 0;
+//   uint32_t event;
+//   uint16_t send_pack_num = 0;
+//   off_t fd_offset = 0;
+
+//   /* 发送升级开始 */
+//   do {
+//     LOG_D("send fw update sta.");
+//     fw_update_start(vls300, vls300->canard);
+//     rt_err_t ret =
+//         rt_event_recv(vls300->_event, VLS300_EVENT_GOT_FW_UPDATE_START_ACK,
+//                       RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR, 1000, &event);
+//     /* 等待升级开始回令 */
+//     if (RT_EOK == ret && (event & VLS300_EVENT_GOT_FW_UPDATE_START_ACK)) {
+//       /* 收到升级开始回令 */
+//       LOG_D("got update sta ack.");
+//       rt_thread_mdelay(200);
+//       send_pack_num = 1;
+//       break;
+
+//     } else {
+//       retry_cnt++;
+//       /* 升级开始失败 */
+//       rt_thread_mdelay(200);
+//       if (retry_cnt >= 5) {
+//         LOG_E("update sta retry failed!");
+//         close(fd);
+//         return -1;
+//       }
+//     }
+//   } while (1);
+
+//   /* 发送升级数据信息 */
+//   do {
+//     fw_update_send_info(vls300, fw_byte_size, vls300->canard);
+//     rt_err_t ret =
+//         rt_event_recv(vls300->_event, VLS300_EVENT_GOT_FW_UPDATE_INFO_ACK,
+//                       RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR, 500, &event);
+
+//     if (ret == RT_EOK && (event & VLS300_EVENT_GOT_FW_UPDATE_INFO_ACK)) {
+//       /* 收到回令, 升级结束 */
+//       LOG_D("got update end ack.");
+//       break;
+//     } else {
+//       /* 超时次未有回令, 升级结束失败 */
+//       retry_cnt++;
+//       if (retry_cnt >= 5) {
+//         LOG_E("gps_id %d: update end ack retry failed!");
+//         close(fd);
+//         return -4;
+//       }
+//     };
+//   } while (1);
+
+//   /* 发送升级数据 */
+//   do {
+//     lseek(fd, fd_offset, SEEK_SET);
+//     rt_memcpy(buff, &send_pack_num, 2);
+//     uint16_t read_len = read(fd, buff + 2, PACK_BYTES_LEN);
+//     LOG_D("send fw update data, pack number %d.", send_pack_num);
+//     fw_update_data(vls300, send_pack_num, buff);
+//     vls300->_fw_update_send_pack_num = send_pack_num;
+//     rt_err_t ret =
+//         rt_event_recv(vls300->_event, VLS300_EVENT_GOT_FW_UPDATE_DATA_ACK,
+//                       RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR, 500, &event);
+//     if (RT_EOK == ret && (event & VLS300_EVENT_GOT_FW_UPDATE_DATA_ACK)) {
+//       /* 接收到升级数据回令 */
+//       fd_offset += read_len;
+//       send_pack_num += 1;
+//       if (fd_offset >= fw_byte_size) {
+//         break;
+//       }
+//     } else {
+//       retry_cnt++;
+//       if (retry_cnt >= 5) {
+//         LOG_E("update data retry failed!");
+//         close(fd);
+//         return -3;
+//       }
+//     }
+//   } while (1);
+
+//   close(fd);
+//   return 0;
+// }
+
+// static void vk_vls300_fw_update_entry(void *arg) {
+
+//   struct vk_weigher_vls300 *vls300 = (struct vk_weigher_vls300 *)arg;
+
+//   do_fw_update(vls300, vls300->_fw_file_name, vls300->canard, RT_NULL);
+// }
+
+// int vls300_fw_update(const char *fw_file_name) {
+//   /* 检查固件文件是否存在 */
+//   if (access(fw_file_name, F_OK) != 0) {
+//     return -1;
+//   }
+
+//   _vk_vls300->_fw_file_name = fw_file_name;
+
+//   rt_thread_t tid =
+//       rt_thread_create("VK_VLS300_FW_UPDATE", vk_vls300_fw_update_entry,
+//                        _vk_vls300, 2048, 15, 5);
+//   rt_thread_startup(tid);
+
+//   return 0;
+// }

+ 81 - 0
uav_can/user_src/vkweigher.FuseBreak_req.c

@@ -0,0 +1,81 @@
+
+
+#define CANARD_DSDLC_INTERNAL
+#include <vkweigher.FuseBreak_req.h>
+
+#include <vkweigher.FuseBreak_res.h>
+
+#include <string.h>
+
+#ifdef CANARD_DSDLC_TEST_BUILD
+#include <test_helpers.h>
+#endif
+
+uint32_t vkweigher_FuseBreakRequest_encode(struct vkweigher_FuseBreakRequest* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+) {
+    uint32_t bit_ofs = 0;
+    memset(buffer, 0, VKWEIGHER_FUSEBREAK_REQUEST_MAX_SIZE);
+    _vkweigher_FuseBreakRequest_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 vkweigher_FuseBreakRequest_decode(const CanardRxTransfer* transfer, struct vkweigher_FuseBreakRequest* msg) {
+#if CANARD_ENABLE_TAO_OPTION
+    if (transfer->tao && (transfer->payload_len > VKWEIGHER_FUSEBREAK_REQUEST_MAX_SIZE)) {
+        return true; /* invalid payload length */
+    }
+#endif
+    uint32_t bit_ofs = 0;
+    if (_vkweigher_FuseBreakRequest_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 vkweigher_FuseBreakRequest sample_vkweigher_FuseBreakRequest_msg(void) {
+
+    struct vkweigher_FuseBreakRequest msg;
+
+
+
+
+
+
+    msg.break_cmd = (uint8_t)random_bitlen_unsigned_val(8);
+
+
+
+
+
+    return msg;
+
+}
+#endif

+ 79 - 0
uav_can/user_src/vkweigher.FuseBreak_res.c

@@ -0,0 +1,79 @@
+
+
+#define CANARD_DSDLC_INTERNAL
+#include <vkweigher.FuseBreak_res.h>
+
+#include <string.h>
+
+#ifdef CANARD_DSDLC_TEST_BUILD
+#include <test_helpers.h>
+#endif
+
+uint32_t vkweigher_FuseBreakResponse_encode(struct vkweigher_FuseBreakResponse* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+) {
+    uint32_t bit_ofs = 0;
+    memset(buffer, 0, VKWEIGHER_FUSEBREAK_RESPONSE_MAX_SIZE);
+    _vkweigher_FuseBreakResponse_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 vkweigher_FuseBreakResponse_decode(const CanardRxTransfer* transfer, struct vkweigher_FuseBreakResponse* msg) {
+#if CANARD_ENABLE_TAO_OPTION
+    if (transfer->tao && (transfer->payload_len > VKWEIGHER_FUSEBREAK_RESPONSE_MAX_SIZE)) {
+        return true; /* invalid payload length */
+    }
+#endif
+    uint32_t bit_ofs = 0;
+    if (_vkweigher_FuseBreakResponse_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 vkweigher_FuseBreakResponse sample_vkweigher_FuseBreakResponse_msg(void) {
+
+    struct vkweigher_FuseBreakResponse msg;
+
+
+
+
+
+
+    msg.result = (int8_t)random_bitlen_signed_val(8);
+
+
+
+
+
+    return msg;
+
+}
+#endif

+ 89 - 0
uav_can/user_src/vkweigher.Version_req.c

@@ -0,0 +1,89 @@
+
+
+#define CANARD_DSDLC_INTERNAL
+#include <vkweigher.Version_req.h>
+
+#include <vkweigher.Version_res.h>
+
+#include <string.h>
+
+#ifdef CANARD_DSDLC_TEST_BUILD
+#include <test_helpers.h>
+#endif
+
+uint32_t vkweigher_VersionRequest_encode(struct vkweigher_VersionRequest* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+) {
+    uint32_t bit_ofs = 0;
+    memset(buffer, 0, VKWEIGHER_VERSION_REQUEST_MAX_SIZE);
+    _vkweigher_VersionRequest_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 vkweigher_VersionRequest_decode(const CanardRxTransfer* transfer, struct vkweigher_VersionRequest* msg) {
+#if CANARD_ENABLE_TAO_OPTION
+    if (transfer->tao && (transfer->payload_len > VKWEIGHER_VERSION_REQUEST_MAX_SIZE)) {
+        return true; /* invalid payload length */
+    }
+#endif
+    uint32_t bit_ofs = 0;
+    if (_vkweigher_VersionRequest_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 vkweigher_VersionRequest sample_vkweigher_VersionRequest_msg(void) {
+
+    struct vkweigher_VersionRequest msg;
+
+
+
+
+
+
+    msg.cmd = (uint8_t)random_bitlen_unsigned_val(8);
+
+
+
+
+
+
+
+    msg.SN_num = (uint32_t)random_bitlen_unsigned_val(32);
+
+
+
+
+
+    return msg;
+
+}
+#endif

+ 95 - 0
uav_can/user_src/vkweigher.Version_res.c

@@ -0,0 +1,95 @@
+
+
+#define CANARD_DSDLC_INTERNAL
+#include <vkweigher.Version_res.h>
+
+#include <string.h>
+
+#ifdef CANARD_DSDLC_TEST_BUILD
+#include <test_helpers.h>
+#endif
+
+uint32_t vkweigher_VersionResponse_encode(struct vkweigher_VersionResponse* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+) {
+    uint32_t bit_ofs = 0;
+    memset(buffer, 0, VKWEIGHER_VERSION_RESPONSE_MAX_SIZE);
+    _vkweigher_VersionResponse_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 vkweigher_VersionResponse_decode(const CanardRxTransfer* transfer, struct vkweigher_VersionResponse* msg) {
+#if CANARD_ENABLE_TAO_OPTION
+    if (transfer->tao && (transfer->payload_len > VKWEIGHER_VERSION_RESPONSE_MAX_SIZE)) {
+        return true; /* invalid payload length */
+    }
+#endif
+    uint32_t bit_ofs = 0;
+    if (_vkweigher_VersionResponse_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 vkweigher_VersionResponse sample_vkweigher_VersionResponse_msg(void) {
+
+    struct vkweigher_VersionResponse msg;
+
+
+
+
+
+
+    for (size_t i=0; i < 16; i++) {
+
+
+
+
+        msg.fw_ver[i] = (int8_t)random_bitlen_signed_val(8);
+
+
+
+    }
+
+
+
+
+
+
+    msg.SN_num = (uint32_t)random_bitlen_unsigned_val(32);
+
+
+
+
+
+    return msg;
+
+}
+#endif

+ 81 - 0
uav_can/user_src/vkweigher.WeigherCalib_req.c

@@ -0,0 +1,81 @@
+
+
+#define CANARD_DSDLC_INTERNAL
+#include <vkweigher.WeigherCalib_req.h>
+
+#include <vkweigher.WeigherCalib_res.h>
+
+#include <string.h>
+
+#ifdef CANARD_DSDLC_TEST_BUILD
+#include <test_helpers.h>
+#endif
+
+uint32_t vkweigher_WeigherCalibRequest_encode(struct vkweigher_WeigherCalibRequest* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+) {
+    uint32_t bit_ofs = 0;
+    memset(buffer, 0, VKWEIGHER_WEIGHERCALIB_REQUEST_MAX_SIZE);
+    _vkweigher_WeigherCalibRequest_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 vkweigher_WeigherCalibRequest_decode(const CanardRxTransfer* transfer, struct vkweigher_WeigherCalibRequest* msg) {
+#if CANARD_ENABLE_TAO_OPTION
+    if (transfer->tao && (transfer->payload_len > VKWEIGHER_WEIGHERCALIB_REQUEST_MAX_SIZE)) {
+        return true; /* invalid payload length */
+    }
+#endif
+    uint32_t bit_ofs = 0;
+    if (_vkweigher_WeigherCalibRequest_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 vkweigher_WeigherCalibRequest sample_vkweigher_WeigherCalibRequest_msg(void) {
+
+    struct vkweigher_WeigherCalibRequest msg;
+
+
+
+
+
+
+    msg.weight = (uint32_t)random_bitlen_unsigned_val(32);
+
+
+
+
+
+    return msg;
+
+}
+#endif

+ 79 - 0
uav_can/user_src/vkweigher.WeigherCalib_res.c

@@ -0,0 +1,79 @@
+
+
+#define CANARD_DSDLC_INTERNAL
+#include <vkweigher.WeigherCalib_res.h>
+
+#include <string.h>
+
+#ifdef CANARD_DSDLC_TEST_BUILD
+#include <test_helpers.h>
+#endif
+
+uint32_t vkweigher_WeigherCalibResponse_encode(struct vkweigher_WeigherCalibResponse* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+) {
+    uint32_t bit_ofs = 0;
+    memset(buffer, 0, VKWEIGHER_WEIGHERCALIB_RESPONSE_MAX_SIZE);
+    _vkweigher_WeigherCalibResponse_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 vkweigher_WeigherCalibResponse_decode(const CanardRxTransfer* transfer, struct vkweigher_WeigherCalibResponse* msg) {
+#if CANARD_ENABLE_TAO_OPTION
+    if (transfer->tao && (transfer->payload_len > VKWEIGHER_WEIGHERCALIB_RESPONSE_MAX_SIZE)) {
+        return true; /* invalid payload length */
+    }
+#endif
+    uint32_t bit_ofs = 0;
+    if (_vkweigher_WeigherCalibResponse_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 vkweigher_WeigherCalibResponse sample_vkweigher_WeigherCalibResponse_msg(void) {
+
+    struct vkweigher_WeigherCalibResponse msg;
+
+
+
+
+
+
+    msg.result = (int8_t)random_bitlen_signed_val(8);
+
+
+
+
+
+    return msg;
+
+}
+#endif

+ 159 - 0
uav_can/user_src/vkweigher.WeigherStatus.c

@@ -0,0 +1,159 @@
+
+
+#define CANARD_DSDLC_INTERNAL
+#include <vkweigher.WeigherStatus.h>
+
+#include <string.h>
+
+#ifdef CANARD_DSDLC_TEST_BUILD
+#include <test_helpers.h>
+#endif
+
+uint32_t vkweigher_WeigherStatus_encode(struct vkweigher_WeigherStatus* msg, uint8_t* buffer
+#if CANARD_ENABLE_TAO_OPTION
+    , bool tao
+#endif
+) {
+    uint32_t bit_ofs = 0;
+    memset(buffer, 0, VKWEIGHER_WEIGHERSTATUS_MAX_SIZE);
+    _vkweigher_WeigherStatus_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 vkweigher_WeigherStatus_decode(const CanardRxTransfer* transfer, struct vkweigher_WeigherStatus* msg) {
+#if CANARD_ENABLE_TAO_OPTION
+    if (transfer->tao && (transfer->payload_len > VKWEIGHER_WEIGHERSTATUS_MAX_SIZE)) {
+        return true; /* invalid payload length */
+    }
+#endif
+    uint32_t bit_ofs = 0;
+    if (_vkweigher_WeigherStatus_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 vkweigher_WeigherStatus sample_vkweigher_WeigherStatus_msg(void) {
+
+    struct vkweigher_WeigherStatus msg;
+
+
+
+
+
+
+    msg.weight = (uint32_t)random_bitlen_unsigned_val(32);
+
+
+
+
+
+
+
+    msg.rate = (uint16_t)random_bitlen_unsigned_val(16);
+
+
+
+
+
+
+
+    msg.status = (uint8_t)random_bitlen_unsigned_val(8);
+
+
+
+
+
+
+
+    msg.gx = (int16_t)random_bitlen_signed_val(16);
+
+
+
+
+
+
+
+    msg.gy = (int16_t)random_bitlen_signed_val(16);
+
+
+
+
+
+
+
+    msg.gz = (int16_t)random_bitlen_signed_val(16);
+
+
+
+
+
+
+
+    msg.ax = (int16_t)random_bitlen_signed_val(16);
+
+
+
+
+
+
+
+    msg.ay = (int16_t)random_bitlen_signed_val(16);
+
+
+
+
+
+
+
+    msg.az = (int16_t)random_bitlen_signed_val(16);
+
+
+
+
+
+
+
+    for (size_t i=0; i < 4; i++) {
+
+
+
+
+        msg.Q[i] = random_float_val();
+
+
+
+    }
+
+
+
+
+    return msg;
+
+}
+#endif

+ 0 - 236
user_inc/soft_hd_water_pump.h

@@ -1,236 +0,0 @@
-#ifndef _SOFT_HD_WATER_PUMP_H
-#define _SOFT_HD_WATER_PUMP_H
-#include "stdint.h"
-#include "string.h"
-#include <stdbool.h>
-#include "soft_water_device.h"
-
-//================================MSG FRAM================================================
-#define  HD_CANID_PRI_POS         (26)
-#define  HD_CANID_PRI_MASK        (0x1C000000)   // 1 1100 0000 0000 0000 0000 0000 0000
-#define  HD_PRI_HIGHEST            0x00
-
-#define  HD_CANID_ANONYMOUS          (0)
-#define  HD_CANID_ANONYMOUS_POS      (24)
-#define  HD_CANID_ANONYMOUS_MASK     (0x01000000)	// 0 0001 0000 0000 0000 0000 0000 0000
-
-#define  HD_CANID_SUBJECT_ID		(0)
-#define  HD_CANID_SUBJECT_POS       (14)
-#define  HD_CANID_SUBJECT_MASK      (0x00FFFF00)   // 0 0000 1111 1111 1111 1111 0000 0000
-
-#define  HD_CANID_SNM_POS         (25)
-#define  HD_CANID_SNM_MASK        (0x02000000)   // 0 0010 0000 0000 0000 0000 0000 0000
-#define  HD_TYPE_MSG               (0x0)           // �㲥֡(message farme)
-#define  HD_TYPE_SER               (0x1)           // ����֡
-
-#define HD_CANID_REV_7            (0)
-#define HD_CANID_REV_7_POS        (7)
-#define HD_CANID_REV_7_MASK       (0x00000080)		// 0 0000 0000 0000 0000 0000 1000 0000
-
-#define  HD_CANID_SRCNODE_POS     (0)
-#define  HD_CANID_SRCNODE_MASK    (0x0000007F)   // 0 0000 0000 0000 0000 0000 0111 1111
-//#define  HD_NODE_BDC               0x0A          // �㲥�ڵ�
-
-//================================SER FRAM==============================================
-#define  HD_CANID_RNR_POS         (24)
-#define  HD_CANID_RNR_MASK        (0x01000000)   // 0 0001 0000 0000 0000 0000 0000 0000
-#define  HD_TYPE_RES               (0x0)
-#define  HD_TYPE_REQ               (0x1)
-
-#define  HD_CANID_REV_23			(0)
-#define  HD_CANID_REV_23_POS		(23)
-#define  HD_CANID_REV_23_MASK		(0x800000)	// 0 0000 1000 0000 0000 0000 0000 0000
-
-
-#define  HD_CANID_SERID_POS       (14)
-#define  HD_CANID_SERID_MASK      (0x007FC000)   // 0 0000 0111 1111 1100 0000 0000 0000
-#define  HD_CANID_SERID           (0)
-
-
-#define  HD_CANID_DESNODE_POS     (7)
-#define  HD_CANID_DESNODE_MASK    (0x00003F80)   // 0 0000 0000 0000 0011 1111 1000 0000
-#define  FMU_NODE_ID_HD             (0x01)          // �ɿؽڵ�
-#define  HD_CANID_PUMP_ID			(0x08)			//ˮ�ýڵ�
-
-#define  HD_CANID_NOZZLE_0_ID		(0x40)			//喷头节点
-#define  HD_CANID_NOZZLE_1_ID		(0x41)			//
-#define  HD_CANID_NOZZLE_2_ID		(0x42)			//
-#define  HD_CANID_NOZZLE_3_ID		(0x43)			//
-#define  HD_CANID_NOZZLE_4_ID		(0x44)			//
-
-//MSG ID
-//水泵
-#define HD_HIGH_FREQ_REPORT_ID   (0x34)		//水泵控制器-高频状态上报
-#define HD_LOW_FREQ_REPORT_ID  	 (0x35)		//水泵控制器-低频状态上报
-#define HD_WATER_PUMP_CONTROL_ID (0x36)		//水泵控制命令
-#define HD_FLOWMETER_PULSE_ID 	 (0x44)		//水泵控制器-流量计脉冲
-#define HD_HEART_ID			 	 (0x05)		//水泵控制器-心跳
-
-//喷头
-#define HD_NOZZLE_HIGH_FREQ_ID   (0x37)		//喷头控制器-状态上报高频
-#define HD_NOZZLE_LOW_FREQ_ID  	 (0x38)		//喷头控制器-状态上报低频
-#define HD_NOZZLE_CONTROL_ID 	 (0x39)		//喷头控制器-控制命令
-#define HD_IDENTIFY_ID			 (0x0D)		//喷头控制器-识别
-#define HD_SET_NOZZLE_ID		 (0x09)		//喷头控制器-设置id
-
-//msg_id crc payload_len 在多帧中占用的字节数量
-#define msg_id_len 	1
-#define crc_len		2
-#define length_len  2
-
-//多帧消息类型
-#define none 0 			//非多帧消息
-#define PSL	 1			///水泵控制器低频状态上报
-
-#define SSL 2			//喷头控制器低频状态上报
-
-
-//多帧消息长度
-#define PSL_LEN     21
-#define SSL_LEN     14
-
-//HD��֡��Ϣ�ṹ��
-typedef struct _HDMsg
-{	
-	uint8_t Msg_id;
-	uint8_t buffer[50];
-	uint16_t rxindex;
-	uint16_t length;
-	HWTail Tail;
-	HWTail LastTail;
-	bool finish;	
-	uint16_t crc;
-	uint8_t len_wrong;
-	uint8_t crc_wrong;
-	uint32_t setEscIdTime;
-	
-}HDMsg;
-
-typedef struct _pump_status
-{
-	uint8_t LST : 2;						//逻辑状态,0:spin; 1:Stop。
-	uint8_t SST : 3;						//子状态,0:Calib; 1:Ready; 2:Align; 3:Startup; 4:Spin; 5:Freewheel。
-	uint8_t STA : 2;						 //水泵状态,0:Fault; 1:Init; 2:Stop; 3:Run。
-	uint8_t rev: 1;
-} pump_status;
-
-typedef struct _MCU_STATUS
-{
-	uint8_t CMST : 1;						//从 MCU 通讯状态,0:在位;1:失联
-	uint8_t VQST : 1; 						//从 MCU 版本查询状态,0:版本查询成功;1:版本查询失败
-	uint8_t REST : 2;						//从 MCU 重启状态,0:运行中;1:重启中;2:重启失败。
-	uint8_t VERS : 2;						//从 MCU 版本同步状态,0:已同步;1:版本同步中;2:版本同步失败。
-	uint8_t PWMS : 1; 						//从 MCU 同步 PWM 状态,0:信号正常;1:信号丢失。
-	uint8_t rev: 1;
-}_MCU_STATUS;
-
-typedef struct _fault_code
-{
-	uint16_t current_high : 1;   		//母线电流过大
-	uint16_t vol_low : 1;   		//母线电压过低
-	uint16_t vol_high : 1;   		//母线电压过高
-	uint16_t overload : 1;   		// 过载
-	uint16_t overspeed : 1;   		// 超速
-	uint16_t blockage : 1;   		// 堵转
-	uint16_t phase_current_high : 1;   		// 相电流过大
-	uint16_t phase_current_abnormal : 1;   		// 相电流偏移值异常
-	uint16_t temp_high : 1;   		// 温度过高
-	uint16_t phase_line_missing : 1;   		// 相线缺失
-	uint16_t thr_loss : 1;   		//油门信号丢失
-	uint16_t selif_check_abnormal : 1;   		// 自检异常
-	uint16_t hard_over_current : 1;   		// 硬件过流
-	uint16_t power_abnormal : 1;   		// 驱动电源异常
-	uint16_t overheat_open : 1;   		// 电机过热开路
-}_fault_code;
-
-typedef struct _pump
-{	
-	uint32_t devID;
-	
-	uint16_t flow1;
-	uint16_t flow2;
-	pump_status pump1_status;
-	pump_status pump2_status;
-	
-	uint16_t pump1_pwm;
-	uint16_t pump2_pwm;
-	uint16_t pump1_speed;
-	uint16_t pump2_speed;
-	_fault_code pump1_fault_code;
-	_fault_code pump2_fault_code;
-	uint16_t pump1_vol;
-	uint16_t pump2_vol;
-	uint8_t pump1_current;
-	uint8_t pump2_current;
-	uint8_t pump1_temp;
-	uint8_t pump2_temp;
-	_MCU_STATUS MCU_status;
-	uint16_t flowmeter1_pulse_interval;
-	uint16_t flowmeter2_pulse_interval;
-
-	
-	
-	HDMsg MultiMsg;
-}HDpump;
-
-typedef struct _solenoid_valve_status
-{
-	uint8_t VDS : 1; 			//电磁阀检测状态,0:关; 1:开。
-	uint8_t VCS : 1; 			//电磁阀控制状态,0:关; 1:开。
-	uint8_t rev : 5;
-}_solenoid_valve_status;
-
-typedef struct _nozzle_status
-{	
-	uint8_t LST : 2;				//逻辑状态,0:spin; 1:Stop; 2:Identify_Spin。
-	uint8_t SST : 3; 			//喷头子状态,0:Calib; 1:Ready; 2:Align; 3:Startup; 4:Spin; 5:Freewheel。
-	uint8_t STA : 2; 			//喷头状态,0:Fault; 1:Init; 2:Stop; 3:Run。
-	uint8_t PLS : 1; 			//功率限制标志,0:未限制; 1 限制中。
-	
-}_nozzle_status;
-
-typedef struct _nozzle
-{
-	uint32_t devID;
-	uint16_t speed;
-	_solenoid_valve_status solenoid_valve_status;
-	uint16_t speed_command;
-	_nozzle_status nozzle_status;
-
-	_fault_code fault_code;
-	uint16_t nozzle_vol;
-	uint8_t nozzle_current;
-	uint8_t solenoid_valve_current;
-	uint8_t nozzle_temp;
-	uint16_t motor_power;
-	uint16_t over_current_num;
-	uint16_t hard_over_current_num;
-	uint8_t blockage_frequency;
-
-	HDMsg MultiMsg;
-
-	uint8_t nodeId;
-	comp_status deviceLink;
-    uint32_t linkTime;
-
-}HDnozzle;
-
-typedef struct _nozzle_id
-{
-	uint32_t devID;
-	uint8_t nodeId;
-	uint32_t linkTime;
-}_nozzle_id;
-
-//extern HDnozzle HD_nozzle;
-extern HDnozzle NozzleMsg[5];
-extern HDpump HD_pump; 
-void HD_pump_func(void);
-extern void HuiDaCanRecvHookFunction(uint32_t id, uint8_t *recv_buf, uint8_t len);
-void HD_frame_process(HDMsg *_HDMsg , uint8_t *recv_buf, uint32_t len);
-void HD_can_sendmsg( uint8_t msg_id, _nozzle_id* Nozzle_id);
-void little_to_big_16(uint16_t* value) ;
-void little_to_big_32(uint32_t* value) ;
-void add_devId(uint8_t SrcId, uint32_t devId);
-uint32_t millis(void);
-#endif

+ 2 - 3
user_inc/soft_p_2_c.h

@@ -19,8 +19,6 @@ typedef enum
 } Msg_Rx_Stage;
 
 extern Msg_Rx_Stage recv_step;
-extern int time_heart[3];
-extern int time_count[3];
 enum vklink_msgid
 {
 	_MSGID_VOL = 1,		   // 电压
@@ -132,7 +130,8 @@ typedef enum
 	DEV_PART_FRADAR,
 	DEV_PART_BRADAR,
 	DEV_QQ_BMS,
-	DEV_TEMPSENSOR
+	DEV_TEMPSENSOR,
+	DEV_LIFTWEIGHT
 } Dev_Type_NUM;
 
 enum LOCK_STATUS

+ 20 - 0
user_inc/soft_seed_device.h

@@ -340,6 +340,23 @@ typedef struct
 } Part_Fradar;
 #pragma pack()
 
+#pragma pack(1)
+typedef struct
+{
+    uint8_t facid;
+    uint32_t weight;
+    uint16_t rate;
+    uint8_t status;
+    int16_t gyrox;
+    int16_t gyroy;
+    int16_t gyroz;
+    int16_t accx;
+    int16_t accy;
+    int16_t accz;
+    float Q[4];
+} _Lift_Weight;
+#pragma pack()
+
 typedef struct
 {
     Seed_info Seed;
@@ -392,6 +409,9 @@ typedef struct
 
 	Part_Fradar Part_radarB;	
     Connect_check Part_Bradar_Link;
+
+    _Lift_Weight Lift_Weight;
+    Connect_check Lift_Weight_Link;
 } Device_type;
 extern Device_type Dev;
 

+ 1 - 0
user_inc/soft_timer.h

@@ -21,6 +21,7 @@ typedef struct
     bool tempSensor;
     bool part_Fradar;
     bool part_Bradar;
+    bool lift_weight;
 }Dev_timer;
 extern Dev_timer devinfo_time;
 

+ 4 - 1
user_inc/soft_version.h

@@ -53,10 +53,13 @@ enum _DEVICE_LIST
     DEVICE_P_TRADAR = 44, //分区仿地雷达
     DEVICE_TR60_F = 45, //EZ 4D避障前
     DEVICE_TR60_B = 46, //EZ 4D避障后
-		 DEVICE_H_BMSA = 47, //HYDROGEN氢能源智能电池1
+    DEVICE_H_BMSA = 47, //HYDROGEN氢能源智能电池1
     DEVICE_H_BMSB = 48, //HYDROGEN氢能源智能电池2
     DEVICE_REMOTEID = 49, //remote id设备
     DEVICE_TEMP_SENSOR = 50, //温度传感器
+    DEVICE_OBSL = 51, //单点左避障
+    DEVICE_OBSR = 52, //单点右避障
+    DEVICE_LIFT_WEIGHT = 53, //vk吊运模块
 		
     DEVICE_END
 };

+ 3 - 1
user_src/soft_can.c

@@ -23,7 +23,8 @@
 #include "soft_update.h"
 #include "can_debug.h"
 #include "qingxie_bms.h"
-#include "soft_hd_water_pump.h"
+#include "dronecan.h"
+
 
 CAN_RxHeaderTypeDef RxHeader;
 CAN_TxHeaderTypeDef TxHeader;
@@ -463,6 +464,7 @@ void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan)
   else
   {
     Can_decode_data_function(RxHeader);
+    // dronecan_rx_callback(RxHeader,RxData);
   }
 
   if(planep.Candebug_flag == true || HAL_GetTick() < 10000)

+ 0 - 638
user_src/soft_hd_water_pump.c

@@ -1,638 +0,0 @@
-#include "soft_hd_water_pump.h"
-#include "soft_water_device.h"
-#include "common.h"
-#include "string.h"
-#include "soft_p_2_c.h"
-#include "soft_flow.h"
-#include "soft_seed_device.h"
-#include "soft_crc.h"
-#include "soft_version.h"
-
-// 惠达采用小端存储
-
-HWTail PumpControlTail = {0};
-HWTail NozzleControlTail = {0};
-HDpump HD_pump = {0};
-HDMsg *_HDMsg = NULL;
-
-HDnozzle NozzleMsg[5] = {0};
-_nozzle_id Nozzle_id[4] = {0};
-
-// 设置喷头id标志位
-bool SetNozzleId = false;
-// 识别喷头标志位
-bool IdentifyNozzle = false;
-// 设置喷头id
-uint8_t SetNozzleIdNum = 4;
-// 设置喷头设备id
-uint32_t SetDevId = 1399067365;
-// uint16_t curNodeID = 0;
-// 超时时间
-uint32_t overtime = 0;
-
-void HuiDaCanRecvHookFunction(uint32_t id, uint8_t *recv_buf, uint8_t len)
-{
-	uint16_t TypeID = 0;
-	uint8_t SrcNodeID = (id & HD_CANID_SRCNODE_MASK) >> HD_CANID_SRCNODE_POS;
-
-	if (SrcNodeID == HD_CANID_PUMP_ID)
-	{
-	}
-	else if (SrcNodeID >= HD_CANID_NOZZLE_0_ID && SrcNodeID <= HD_CANID_NOZZLE_4_ID)
-	{
-	}
-	else
-	{
-		return;
-	}
-
-	TypeID = recv_buf[0];
-
-	switch (SrcNodeID)
-	{
-	case HD_CANID_PUMP_ID:
-		_HDMsg = &HD_pump.MultiMsg;
-
-		Dev.Pump_Link.connect_status = COMP_NORMAL;
-		Dev.Pump_Link.recv_time = HAL_GetTick();
-		Dev.Pump.facid = FAC_HD_PUMP;
-
-		// 多帧消息处理
-		// 多帧发送需要二次打包
-		// 判断接收的消息类型
-		switch (_HDMsg->Msg_id)
-		{
-		// 非多帧消息
-		case none:
-			break;
-
-		case PSL:
-			HD_frame_process(_HDMsg, recv_buf, len);
-			if (_HDMsg->finish == true)
-			{
-				memcpy(&HD_pump.pump1_pwm, &_HDMsg->buffer[3], 2);
-				little_to_big_16(&HD_pump.pump1_pwm);
-
-				memcpy(&HD_pump.pump2_pwm, &_HDMsg->buffer[5], 2);
-				little_to_big_16(&HD_pump.pump2_pwm);
-
-				memcpy(&HD_pump.pump1_speed, &_HDMsg->buffer[7], 2);
-				little_to_big_16(&HD_pump.pump1_speed);
-
-				memcpy(&HD_pump.pump2_speed, &_HDMsg->buffer[9], 2);
-				little_to_big_16(&HD_pump.pump2_speed);
-
-				uint16_t fault_code = 0;
-				memcpy(&fault_code, &_HDMsg->buffer[11], 2);
-				little_to_big_16(&fault_code);
-				memcpy(&HD_pump.pump1_fault_code, &fault_code, 2);
-
-				fault_code = 0;
-				memcpy(&fault_code, &_HDMsg->buffer[13], 2);
-				little_to_big_16(&fault_code);
-				memcpy(&HD_pump.pump2_fault_code, &fault_code, 2);
-
-				memcpy(&HD_pump.pump1_vol, &_HDMsg->buffer[15], 2);
-				little_to_big_16(&HD_pump.pump1_vol);
-
-				memcpy(&HD_pump.pump2_vol, &_HDMsg->buffer[17], 2);
-				little_to_big_16(&HD_pump.pump2_vol);
-
-				HD_pump.pump1_current = _HDMsg->buffer[19];
-				HD_pump.pump2_current = _HDMsg->buffer[20];
-				HD_pump.pump1_temp = _HDMsg->buffer[21];
-				HD_pump.pump2_temp = _HDMsg->buffer[22];
-
-				memcpy(&HD_pump.MCU_status, &_HDMsg->buffer[23], 1);
-
-				_HDMsg->finish = false;
-				_HDMsg->Msg_id = none;
-			}
-			// 处理完毕跳过单帧消息处理,防止重复处理错误
-			goto next;
-			// break;
-		}
-
-		switch (TypeID)
-		{
-		case HD_HIGH_FREQ_REPORT_ID:
-			memcpy(&HD_pump.flow1, &recv_buf[1], 2);
-			little_to_big_16(&HD_pump.flow1);
-
-			memcpy(&HD_pump.flow2, &recv_buf[3], 2);
-			little_to_big_16(&HD_pump.flow2);
-
-			memcpy(&HD_pump.pump1_status, &recv_buf[5], 1);
-			memcpy(&HD_pump.pump2_status, &recv_buf[6], 1);
-
-			break;
-		case HD_LOW_FREQ_REPORT_ID:
-			memcpy(&_HDMsg->length, &recv_buf[1], 2);
-
-			little_to_big_16(&_HDMsg->length);
-			// 如果接收的消息长度正确
-			if (_HDMsg->length == PSL_LEN)
-			{
-				_HDMsg->rxindex = 0;
-				_HDMsg->LastTail.HWTailByte = recv_buf[7];
-
-				memcpy(&_HDMsg->buffer, recv_buf, 7);
-				_HDMsg->rxindex += 7;
-				_HDMsg->Msg_id = PSL;
-			}
-			else
-			{
-				_HDMsg->rxindex = 0;
-				_HDMsg->Msg_id = none;
-			}
-			break;
-
-		case HD_FLOWMETER_PULSE_ID:
-			memcpy(&HD_pump.flowmeter1_pulse_interval, &recv_buf[1], 2);
-			little_to_big_16(&HD_pump.flowmeter1_pulse_interval);
-
-			memcpy(&HD_pump.flowmeter2_pulse_interval, &recv_buf[3], 2);
-			little_to_big_16(&HD_pump.flowmeter2_pulse_interval);
-			break;
-		case HD_HEART_ID:
-			memcpy(&HD_pump.devID, &recv_buf[1], 4);
-			little_to_big_32(&HD_pump.devID);
-			break;
-		}
-		break;
-
-	case HD_CANID_NOZZLE_0_ID ... HD_CANID_NOZZLE_4_ID:
-
-	{
-		HDnozzle *HD_nozzle = NULL;
-		HD_nozzle = &NozzleMsg[SrcNodeID - HD_CANID_NOZZLE_0_ID];
-		_HDMsg = &HD_nozzle->MultiMsg;
-
-		Dev.Nozzle_Link.connect_status = COMP_NORMAL;
-		Dev.Nozzle_Link.recv_time = HAL_GetTick();
-		Dev.Nozzle.facid = FAC_HD_NOZZLE;
-
-		HD_nozzle->deviceLink = COMP_NORMAL;
-		HD_nozzle->linkTime = HAL_GetTick();
-		HD_nozzle->nodeId = SrcNodeID;
-
-		// 多帧消息处理
-		// 多帧发送需要二次打包
-		// 判断接收的消息类型
-		switch (_HDMsg->Msg_id)
-		{
-		// 非多帧消息
-		case none:
-		{
-			break;
-		}
-
-		case SSL:
-		{
-			HD_frame_process(_HDMsg, recv_buf, len);
-			if (_HDMsg->finish == true)
-			{
-				uint16_t _fault_code = 0;
-				memcpy(&_fault_code, &_HDMsg->buffer[3], 2);
-				little_to_big_16(&_fault_code);
-				memcpy(&HD_nozzle->fault_code, &_fault_code, 2);
-
-				memcpy(&HD_nozzle->nozzle_vol, &_HDMsg->buffer[5], 2);
-				little_to_big_16(&HD_nozzle->nozzle_vol);
-
-				memcpy(&HD_nozzle->nozzle_current, &_HDMsg->buffer[7], 1);
-				memcpy(&HD_nozzle->solenoid_valve_current, &_HDMsg->buffer[8], 1);
-				memcpy(&HD_nozzle->nozzle_temp, &_HDMsg->buffer[9], 1);
-
-				memcpy(&HD_nozzle->motor_power, &_HDMsg->buffer[10], 2);
-				little_to_big_16(&HD_nozzle->motor_power);
-
-				memcpy(&HD_nozzle->over_current_num, &_HDMsg->buffer[12], 2);
-				little_to_big_16(&HD_nozzle->over_current_num);
-
-				memcpy(&HD_nozzle->hard_over_current_num, &_HDMsg->buffer[14], 2);
-				little_to_big_16(&HD_nozzle->hard_over_current_num);
-
-				memcpy(&HD_nozzle->blockage_frequency, &_HDMsg->buffer[15], 1);
-
-				_HDMsg->finish = false;
-				_HDMsg->Msg_id = none;
-			}
-			// 跳过单帧消息处理,防止重复处理错误
-			goto next;
-			// break;
-		}
-		}
-
-		switch (TypeID)
-		{
-		case HD_NOZZLE_HIGH_FREQ_ID:
-		{
-			memcpy(&HD_nozzle->speed, &recv_buf[1], 2);
-			little_to_big_16(&HD_nozzle->speed);
-
-			memcpy(&HD_nozzle->solenoid_valve_status, &recv_buf[3], 1);
-
-			memcpy(&HD_nozzle->speed_command, &recv_buf[4], 2);
-			little_to_big_16(&HD_nozzle->speed_command);
-
-			memcpy(&HD_nozzle->nozzle_status, &recv_buf[6], 1);
-			break;
-		}
-		case HD_NOZZLE_LOW_FREQ_ID:
-		{
-			memcpy(&_HDMsg->length, &recv_buf[1], 2);
-
-			little_to_big_16(&_HDMsg->length);
-			// 如果接收的消息长度正确
-			if (_HDMsg->length == SSL_LEN)
-			{
-				_HDMsg->rxindex = 0;
-				_HDMsg->LastTail.HWTailByte = recv_buf[7];
-
-				memcpy(&_HDMsg->buffer, recv_buf, 7);
-				_HDMsg->rxindex += 7;
-				_HDMsg->Msg_id = SSL;
-			}
-			else
-			{
-				_HDMsg->rxindex = 0;
-				_HDMsg->Msg_id = none;
-			}
-			break;
-		}
-		case HD_HEART_ID:
-		{
-			memcpy(&HD_nozzle->devID, &recv_buf[1], 4);
-			little_to_big_32(&HD_nozzle->devID);
-			// 添加设备id
-			add_devId(SrcNodeID, HD_nozzle->devID);
-
-			if (SetNozzleId == true && HD_nozzle->devID == SetDevId)
-			{
-				if (SrcNodeID == SetNozzleIdNum + HD_CANID_NOZZLE_0_ID)
-				{
-					SetNozzleId = false;
-				}
-				else
-					overtime = millis();
-			}
-			break;
-		}
-		case HD_IDENTIFY_ID:
-		{
-			if (recv_buf[1] == 0 && IdentifyNozzle == true)
-			{
-				uint32_t dev_id;
-				memcpy(&dev_id, &recv_buf[2], 4);
-				little_to_big_32(&dev_id);
-				if (dev_id == SetDevId)
-					IdentifyNozzle = false;
-				else
-					overtime = millis();
-			}
-			else
-				overtime = millis();
-
-			break;
-		}
-		}
-	}
-	break;
-	}
-
-next:;
-}
-
-void HD_pump_func(void)
-{
-	// test
-
-	// static uint32_t time_1hz = 0;
-	if (Dev.Pump_Link.connect_status == COMP_NORMAL && Dev.Pump.facid == FAC_HD_PUMP)
-	{
-		/*
-		if(Check_Timer_Ready(&time_1hz,_1_HZ_))
-		{
-			HW_CanGetESCInfomation();
-			HW_CanSetESCInfomation();
-		}
-*/
-
-		HD_can_sendmsg(HD_WATER_PUMP_CONTROL_ID, NULL);
-		// HD_can_sendmsg( 1300 , 1300);
-	}
-
-	if (Dev.Nozzle_Link.connect_status == COMP_NORMAL && Dev.Nozzle.facid == FAC_HD_NOZZLE)
-	{
-		/*
-		if(Check_Timer_Ready(&time_1hz,_1_HZ_))
-		{
-			HW_CanGetESCInfomation();
-			HW_CanSetESCInfomation();
-		}
-*/
-		if (IdentifyNozzle == true)
-		{
-			/*
-			if (millis() - overtime > 5000)
-			{
-				IdentifyNozzle = false;
-			}*/
-
-			for (uint8_t i = 0; i < 4; i++)
-			{
-				if (Nozzle_id[i].devID == SetDevId)
-				{
-					HD_can_sendmsg(HD_IDENTIFY_ID, &Nozzle_id[i]);
-				}
-			}
-		}
-		else if (SetNozzleId == true)
-		{
-			/*
-			if (millis() - overtime > 5000)
-			{
-				IdentifyNozzle = false;
-			}*/
-
-			for (uint8_t i = 0; i < 4; i++)
-			{
-				if (Nozzle_id[i].devID == SetDevId)
-				{
-					HD_can_sendmsg(HD_SET_NOZZLE_ID, &Nozzle_id[i]);
-				}
-			}
-		}
-		else
-			HD_can_sendmsg(HD_NOZZLE_CONTROL_ID, NULL);
-		// HD_can_sendmsg( 1300 , 1300);
-	}
-}
-
-void HD_can_sendmsg(uint8_t msg_id, _nozzle_id *Nozzle_id)
-{
-	uint32_t canID;
-	uint32_t _dev_ID;
-	uint8_t can_buf[8] = {0};
-	switch (msg_id)
-	{
-	case HD_WATER_PUMP_CONTROL_ID:
-	{
-		canID = ((HD_PRI_HIGHEST << HD_CANID_PRI_POS) & HD_CANID_PRI_MASK) |
-				((HD_TYPE_SER << HD_CANID_SNM_POS) & HD_CANID_SNM_MASK) |
-				((HD_TYPE_REQ << HD_CANID_RNR_POS) & HD_CANID_RNR_MASK) |
-				((HD_CANID_REV_23 << HD_CANID_REV_23_POS) & HD_CANID_REV_23_MASK) |
-				((HD_CANID_SERID << HD_CANID_SERID_POS) & HD_CANID_SERID_MASK) |
-				((HD_CANID_PUMP_ID << HD_CANID_DESNODE_POS) & HD_CANID_DESNODE_MASK) |
-				((FMU_NODE_ID_HD << HD_CANID_SRCNODE_POS) & HD_CANID_SRCNODE_MASK);
-
-		can_buf[0] = HD_WATER_PUMP_CONTROL_ID;
-
-		uint16_t _pwm1 = (uint16_t)pmu_pin.pump1;
-		uint16_t _pwm2 = (uint16_t)pmu_pin.pump2;
-		if (_pwm1 > 1800)
-			_pwm1 = 1800;
-		if (_pwm2 > 1800)
-			_pwm2 = 1800;
-		little_to_big_16(&_pwm1);
-		little_to_big_16(&_pwm2);
-		memcpy(&can_buf[1], &_pwm1, 2);
-		memcpy(&can_buf[3], &_pwm2, 2);
-
-		PumpControlTail.HWTailBit.start = 1;
-		PumpControlTail.HWTailBit.end = 1;
-		PumpControlTail.HWTailBit.toggle = 1;
-		can_buf[5] = PumpControlTail.HWTailByte;
-
-		can_send_msg_normal(can_buf, 6, canID);
-
-		PumpControlTail.HWTailBit.tranid++;
-		break;
-	}
-	case HD_NOZZLE_CONTROL_ID:
-	{
-		uint16_t rpm = 0;
-		uint8_t open;
-		for (uint8_t i = 1; i <= 4; i++)
-		{
-			switch (i)
-			{
-			case 1:
-				rpm = pmu_pin.nozz1_fm;
-				break;
-			case 2:
-				rpm = pmu_pin.nozz2_zp;
-				break;
-			case 3:
-				rpm = pmu_pin.nozz3;
-				break;
-			case 4:
-				rpm = pmu_pin.nozz4;
-				break;
-			default:
-				break;
-			}
-			canID = ((HD_PRI_HIGHEST << HD_CANID_PRI_POS) & HD_CANID_PRI_MASK) |
-					((HD_TYPE_SER << HD_CANID_SNM_POS) & HD_CANID_SNM_MASK) |
-					((HD_TYPE_REQ << HD_CANID_RNR_POS) & HD_CANID_RNR_MASK) |
-					((HD_CANID_REV_23 << HD_CANID_REV_23_POS) & HD_CANID_REV_23_MASK) |
-					((HD_CANID_SERID << HD_CANID_SERID_POS) & HD_CANID_SERID_MASK) |
-					(((HD_CANID_NOZZLE_0_ID + i) << HD_CANID_DESNODE_POS) & HD_CANID_DESNODE_MASK) |
-					((FMU_NODE_ID_HD << HD_CANID_SRCNODE_POS) & HD_CANID_SRCNODE_MASK);
-			open = 1;
-			if (rpm <= 1020)
-			{
-				rpm = 0;
-				open = 0;
-			}
-			else if (rpm >= 2000)
-				rpm = 14000;
-			else
-				rpm = (rpm - 1020) * ((14000 - 2000) / (2000 - 1000));
-			can_buf[0] = HD_NOZZLE_CONTROL_ID;
-			// rpm = 14000;
-			little_to_big_16(&rpm);
-			memcpy(&can_buf[1], &rpm, 2);
-			memcpy(&can_buf[3], &open, 1);
-
-			PumpControlTail.HWTailBit.start = 1;
-			PumpControlTail.HWTailBit.end = 1;
-			PumpControlTail.HWTailBit.toggle = 1;
-			can_buf[4] = PumpControlTail.HWTailByte;
-
-			can_send_msg_normal(can_buf, 5, canID);
-
-			PumpControlTail.HWTailBit.tranid++;
-		}
-
-		break;
-	}
-	case HD_IDENTIFY_ID:
-	{
-		if (Nozzle_id == NULL)
-			return;
-		canID = ((HD_PRI_HIGHEST << HD_CANID_PRI_POS) & HD_CANID_PRI_MASK) |
-				((HD_TYPE_SER << HD_CANID_SNM_POS) & HD_CANID_SNM_MASK) |
-				((HD_TYPE_REQ << HD_CANID_RNR_POS) & HD_CANID_RNR_MASK) |
-				((HD_CANID_REV_23 << HD_CANID_REV_23_POS) & HD_CANID_REV_23_MASK) |
-				((HD_CANID_SERID << HD_CANID_SERID_POS) & HD_CANID_SERID_MASK) |
-				((Nozzle_id->nodeId << HD_CANID_DESNODE_POS) & HD_CANID_DESNODE_MASK) |
-				((FMU_NODE_ID_HD << HD_CANID_SRCNODE_POS) & HD_CANID_SRCNODE_MASK);
-
-		can_buf[0] = HD_IDENTIFY_ID;
-		// rpm = 14000;
-		_dev_ID = SetDevId;
-		little_to_big_32(&_dev_ID);
-		memcpy(&can_buf[1], &_dev_ID, 4);
-		can_buf[5] = 0x00;
-		can_buf[6] = 0x00;
-		PumpControlTail.HWTailBit.start = 1;
-		PumpControlTail.HWTailBit.end = 1;
-		PumpControlTail.HWTailBit.toggle = 1;
-		can_buf[7] = PumpControlTail.HWTailByte;
-
-		can_send_msg_normal(can_buf, 8, canID);
-
-		PumpControlTail.HWTailBit.tranid++;
-		break;
-	}
-	case HD_SET_NOZZLE_ID:
-	{
-		if (Nozzle_id == NULL)
-			return;
-		canID = ((HD_PRI_HIGHEST << HD_CANID_PRI_POS) & HD_CANID_PRI_MASK) |
-				((HD_TYPE_SER << HD_CANID_SNM_POS) & HD_CANID_SNM_MASK) |
-				((HD_TYPE_REQ << HD_CANID_RNR_POS) & HD_CANID_RNR_MASK) |
-				((HD_CANID_REV_23 << HD_CANID_REV_23_POS) & HD_CANID_REV_23_MASK) |
-				((HD_CANID_SERID << HD_CANID_SERID_POS) & HD_CANID_SERID_MASK) |
-				((Nozzle_id->nodeId << HD_CANID_DESNODE_POS) & HD_CANID_DESNODE_MASK) |
-				((FMU_NODE_ID_HD << HD_CANID_SRCNODE_POS) & HD_CANID_SRCNODE_MASK);
-
-		can_buf[0] = HD_SET_NOZZLE_ID;
-
-		_dev_ID = SetDevId;
-		little_to_big_32(&_dev_ID);
-		memcpy(&can_buf[1], &_dev_ID, 4);
-		can_buf[5] = SetNozzleIdNum + HD_CANID_NOZZLE_0_ID;
-		can_buf[6] = 0;
-
-		PumpControlTail.HWTailBit.start = 1;
-		PumpControlTail.HWTailBit.end = 1;
-		PumpControlTail.HWTailBit.toggle = 1;
-		can_buf[7] = PumpControlTail.HWTailByte;
-
-		can_send_msg_normal(can_buf, 8, canID);
-
-		PumpControlTail.HWTailBit.tranid++;
-		break;
-	}
-	default:
-		break;
-	}
-}
-
-// 多帧消息处理
-void HD_frame_process(HDMsg *_HDMsg, uint8_t *recv_buf, uint32_t len)
-{
-	_HDMsg->Tail.HWTailByte = recv_buf[len - 1];
-
-	// 如果收帧连续,数据进入buffer
-	if (_HDMsg->Tail.HWTailBit.toggle != _HDMsg->LastTail.HWTailBit.toggle)
-	{
-		memcpy(&_HDMsg->buffer[_HDMsg->rxindex], recv_buf, (len - 1));
-		_HDMsg->LastTail.HWTailByte = _HDMsg->Tail.HWTailByte;
-		_HDMsg->rxindex = _HDMsg->rxindex + len - 1;
-	}
-	// 如果是最后一帧
-	if (_HDMsg->Tail.HWTailBit.end == 1 && _HDMsg->rxindex == _HDMsg->length + length_len + msg_id_len + crc_len)
-	{
-		memcpy(&_HDMsg->crc, &_HDMsg->buffer[_HDMsg->rxindex - 2], 2);
-		little_to_big_16(&_HDMsg->crc);
-
-		// 校验
-		if (_HDMsg->crc == crcAdd(0xFFFF, _HDMsg->buffer, _HDMsg->rxindex - 2))
-		{
-			_HDMsg->finish = true;
-		}
-		else
-			_HDMsg->crc_wrong++;
-
-		// 无论是否校验通过,都重置
-		_HDMsg->Msg_id = none;
-		_HDMsg->rxindex = 0;
-	}
-	// 超出字节重置
-	else if (_HDMsg->rxindex >= (_HDMsg->length + length_len + msg_id_len + crc_len))
-	{
-		_HDMsg->rxindex = 0;
-		_HDMsg->Msg_id = none;
-		_HDMsg->len_wrong++;
-	}
-}
-
-// 添加设备id到Nozzle_id数组
-void add_devId(uint8_t SrcId, uint32_t devId)
-{
-	uint8_t p = 0;
-	for (uint8_t i = 0; i < 4; i++)
-	{
-		// 超时视为断开连接,清除设备id
-		if (Nozzle_id[i].devID != 0 && millis() - Nozzle_id[i].linkTime >= 2000)
-			Nozzle_id[i].devID = 0;
-	}
-	for (uint8_t i = 0; i < 4; i++)
-	{
-		// 如果设备id已经存在,更新时间
-		if (Nozzle_id[i].devID == devId)
-		{
-			Nozzle_id[i].linkTime = millis();
-			Nozzle_id[i].nodeId = SrcId;
-			return;
-		}
-		// 空位,记录
-		else if (Nozzle_id[i].devID == 0)
-		{
-			p = i;
-		}
-	}
-	// 当前id与之前的id都不相同,添加
-	// 如果数组已满,不添加
-	if (p < 4)
-	{
-		Nozzle_id[p].devID = devId;
-		Nozzle_id[p].nodeId = SrcId;
-		Nozzle_id[p].linkTime = millis();
-	}
-}
-
-void little_to_big_32(uint32_t *value)
-{
-	if (value == NULL)
-	{
-		return;
-	}
-	uint32_t _value = *value;
-	_value = ((_value & 0xFF) << 24) |
-			 ((_value & 0xFF00) << 8) |
-			 ((_value >> 8) & 0xFF00) |
-			 ((_value >> 24) & 0xFF);
-	*value = _value;
-}
-
-void little_to_big_16(uint16_t *value)
-{
-	if (value == NULL)
-	{
-		return;
-	}
-	uint16_t _value = *value;
-	_value = ((_value & 0xFF) << 8) |
-			 ((_value >> 8) & 0xFF);
-	*value = _value;
-}
-
-uint32_t millis()
-{
-	return HAL_GetTick();
-}

+ 7 - 2
user_src/soft_p_2_c.c

@@ -953,6 +953,13 @@ void pmu_to_con_devtype_data(void)
         index += sizeof(Weight_info);
         devinfo_time.weight = false;
     }
+    else if(Dev.Lift_Weight_Link.connect_status == COMP_NORMAL && devinfo_time.lift_weight == true)
+    {
+        msg_buf[index++] = DEV_LIFTWEIGHT;
+        memcpy(&msg_buf[index],&Dev.Lift_Weight.facid,sizeof(_Lift_Weight));
+        index += sizeof(_Lift_Weight);
+        devinfo_time.lift_weight = false;
+    }
     else if(Dev.Seed_Link.connect_status == COMP_NORMAL && devinfo_time.seed == true)
     {
         msg_buf[index++] = DEV_SEED;
@@ -1471,8 +1478,6 @@ void Check_Rst(void)
 /******************void check_fmu_link()************************
  * ****************检查是否收到FMU信息************************************
  * ****************************************************************/
-int time_heart[3] = {0};
-int time_count[3] = {0};//test
 static uint32_t fmu_link_time = 0;
 void check_fmu_link()
 {

+ 47 - 14
user_src/soft_seed_device.c

@@ -15,7 +15,8 @@
 #include "qingxie_bms.h"
 #include "soft_adc.h"
 #include "soft_flash.h"
-#include "soft_hd_water_pump.h"
+#include "drv_vkweigher_vls300.h"
+
 weight weight_vkinfo;
 seed seed_vkinfo;
 send_seed_device seed_dev;
@@ -683,7 +684,17 @@ void DM_obs_test( void )
     if(Check_Timer_Ready(&time_47hz,19))
     {
         memcpy(&can_buf[0],&planep.pos_z,4);
-        memcpy(&can_buf[4],&planep.pos_flag,4);
+        memcpy(&can_buf[4],&planep.alt,2);
+        static uint16_t fmu_lock_status = 0;
+        if(planep.lock_status == 4)
+        {
+            fmu_lock_status = 1;
+        }
+        else
+        {
+            fmu_lock_status = 0;
+        }
+        memcpy(&can_buf[6],&fmu_lock_status,2);
         can_send_msg_normal((unsigned char *)&can_buf, 8, 0x2348);
     }
 }
@@ -717,6 +728,7 @@ void  update_device_type_data(void)
         Check_dev_link(&Dev.Lackloss_Link,5000,NULL,0);
         Check_dev_link(&Dev.L_pump1_Link,5000,(char *)&Dev.L_pump1.facid,sizeof(Linear_pump_info));
         Check_dev_link(&Dev.L_pump2_Link,5000,(char *)&Dev.L_pump2.facid,sizeof(Linear_pump_info));
+        Check_dev_link(&Dev.Lift_Weight_Link,5000,(char *)&Dev.Lift_Weight.facid,sizeof(_Lift_Weight));
         
         check_radar_link_status();
     }
@@ -743,8 +755,6 @@ void  update_device_type_data(void)
     {
         //好盈电调水泵
         Hobbywing_esc_func();
-		//惠达水泵
-		HD_pump_func();
         //播撒器
         if(Dev.Seed_Link.connect_status == COMP_NORMAL)
         {
@@ -838,6 +848,29 @@ void  update_device_type_data(void)
             }
         }
 
+        if(Dev.Lift_Weight_Link.connect_status == COMP_NORMAL)
+        {
+            switch (Dev.Weight.facid)
+            {
+                case FAC_VK:
+                    Dev.Lift_Weight.weight = _vk_vls300.status_data.weight;
+                    Dev.Lift_Weight.rate = _vk_vls300.status_data.weight_dot;
+                    Dev.Lift_Weight.status = _vk_vls300.status_data.status;
+                    Dev.Lift_Weight.accx = _vk_vls300.status_data.acce[0];//0.01
+                    Dev.Lift_Weight.accy = _vk_vls300.status_data.acce[1];
+                    Dev.Lift_Weight.accz = _vk_vls300.status_data.acce[2];
+                    Dev.Lift_Weight.gyrox = _vk_vls300.status_data.gyro[0]; //0.01
+                    Dev.Lift_Weight.gyroy = _vk_vls300.status_data.gyro[1];
+                    Dev.Lift_Weight.gyroz = _vk_vls300.status_data.gyro[2];
+                    Dev.Lift_Weight.Q[0] = _vk_vls300.status_data.Q[0];
+                    Dev.Lift_Weight.Q[1] = _vk_vls300.status_data.Q[1];
+                    Dev.Lift_Weight.Q[2] = _vk_vls300.status_data.Q[2];
+                    Dev.Lift_Weight.Q[3] = _vk_vls300.status_data.Q[3];
+                    break;
+
+            }
+        }
+
         //水泵
         if(Dev.Pump_Link.connect_status == COMP_NORMAL)
         {
@@ -863,10 +896,10 @@ void  update_device_type_data(void)
                 Dev.Pump.warn = 0; //屏蔽报警
                 break;
 			case FAC_HD_PUMP:
-				Dev.Pump.rpm1 = HD_pump.pump1_speed;
-                Dev.Pump.rpm2 = HD_pump.pump2_speed;
-			    Dev.Pump.rpm3 = 0;
-                Dev.Pump.rpm4 = 0;
+				// Dev.Pump.rpm1 = HD_pump.pump1_speed;
+                // Dev.Pump.rpm2 = HD_pump.pump2_speed;
+			    // Dev.Pump.rpm3 = 0;
+                // Dev.Pump.rpm4 = 0;
 				
 				
 				break;
@@ -908,10 +941,10 @@ void  update_device_type_data(void)
                 Dev.Nozzle.warn = 0; //屏蔽报警
                 break;
             case FAC_HD_NOZZLE:
-                Dev.Nozzle.rpm1 = NozzleMsg[1].speed;
-                Dev.Nozzle.rpm2 = NozzleMsg[2].speed;
-                Dev.Nozzle.rpm3 = NozzleMsg[3].speed;
-                Dev.Nozzle.rpm4 = NozzleMsg[4].speed;
+                // Dev.Nozzle.rpm1 = NozzleMsg[1].speed;
+                // Dev.Nozzle.rpm2 = NozzleMsg[2].speed;
+                // Dev.Nozzle.rpm3 = NozzleMsg[3].speed;
+                // Dev.Nozzle.rpm4 = NozzleMsg[4].speed;
                 break;
             default:
                 break;
@@ -1171,8 +1204,8 @@ void  update_device_type_data(void)
             Dev.Radar.signal_R_qulity = 0;
 
             terrain_is_link = Dev.Radar.height_T  > -1? true:false;
-            obs_f_is_link = Dev.Radar.distance_F_Y  > -1? true:false;
-            obs_b_is_link = Dev.Radar.distance_B_Y > -1? true:false;
+            obs_f_is_link = Dev.Radar.distance_F_Y  > -1? true:(Dev.Part_Fradar_Link.connect_status == COMP_NORMAL? true : false);
+            obs_b_is_link = Dev.Radar.distance_B_Y > -1? true:(Dev.Part_Bradar_Link.connect_status == COMP_NORMAL? true : false);
 
         }
 

+ 3 - 0
user_src/soft_test.c

@@ -14,6 +14,7 @@
 #include "can_debug.h"
 #include "soft_version.h"
 #include "config.h"
+#include "dronecan.h"
 
 /******************************************************************
  * ****************测试程序*****************************************
@@ -196,6 +197,8 @@ void user_init(void)
 
   //PVD_Config();
 
+  //dronecan_init(); //test
+
   //上电读内存参数
   flash_read_funcktion();
   

+ 1 - 0
user_src/soft_timer.c

@@ -70,6 +70,7 @@ void timer_function()
         mimo360_radar_flag = true;
         
         devinfo_time.weight = true;
+        devinfo_time.lift_weight = true;
         devinfo_time.L_pump1 = true;
         devinfo_time.L_pump2 = true;
 

+ 8 - 0
user_src/soft_version.c

@@ -12,6 +12,7 @@
 #include "soft_bms.h"
 #include "soft_seed_device.h"
 #include "soft_water_device.h"
+#include "drv_vkweigher_vls300.h"
 
 
 dev_version_content dev_pmu;
@@ -37,6 +38,9 @@ dev_version_content dev_h_bmsA;
 dev_version_content dev_h_bmsB;
 dev_version_content dev_remoteid;
 dev_version_content dev_tempSensor;
+dev_version_content dev_obsl;
+dev_version_content dev_obsr;
+dev_version_content dev_lift_weight;
 
 dev_version_content dev_null;
 
@@ -104,6 +108,9 @@ void *dev_ptr[] = {&dev_null,
                    &dev_h_bmsB,
                    &dev_remoteid,
                    &dev_tempSensor,
+                   &dev_obsl,
+                   &dev_obsr,
+                   &dev_lift_weight,
                   };
 short dev_num = sizeof( dev_ptr )/sizeof( void * );
 /**
@@ -512,6 +519,7 @@ void get_device_version_and_sn(void)
 
     if(Check_Timer_Ready(&circu_time,_2_HZ_))
     {  
+
         //获取雷达版本和SN号
         get_radar_version_and_sn();
 

+ 2 - 24
user_src/soft_water_device.c

@@ -10,6 +10,7 @@
 #include "soft_tattu.h"
 #include "soft_terrain.h"
 #include "soft_obstacle.h"
+#include "canard.h"
 /**
   * @file    liquid_recieved_hookfuction
   * @brief   液位计解析
@@ -510,29 +511,6 @@ void HW_CanSetESCInfomation( void )
     }
 }
 
-
-float canardConvertFloat16ToNativeFloat(uint16_t value)
-{
-    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;
-}
 /**
   * @file    uavcan_equipment_power_BatteryInfo_decode
   * @brief   CAN解析电流传感器
@@ -1060,7 +1038,7 @@ void Get_auger_sowing_mag(uint32_t CanID, uint8_t data[], uint8_t len)
             //churn.reserve += (1<<(z70_info.reserve2 & 0x07));
 
             static uint8_t churn_size = 0;
-            if(churn_size != z70_info.reserve3 & 0x07)
+            if(churn_size != (z70_info.reserve3 & 0x07))
             {
                churn_size = z70_info.reserve3 & 0x07;
                DM_4DRADARMAG.Packing_auger_size = churn_size;

Daži faili netika attēloti, jo izmaiņu fails ir pārāk liels