Update UAVCAN drivers, Add UAVCAN boot loader support. Add UAVCAN parameter support. Update get node info responses

This commit is contained in:
Jaime 2021-03-25 16:58:45 -06:00
parent 8b9e3bf93f
commit d76dffbc44
49 changed files with 7348 additions and 293 deletions

2
.gitignore vendored
View File

@ -5,3 +5,5 @@ build
.project
.cproject
.settings/language.settings.xml
.DS_Store
workspace.code-workspace

View File

@ -19,6 +19,8 @@
#define HW_410_H_
#define HW_NAME "410"
#define HW_MAJOR 4
#define HW_MINOR 10
// Macros
#define ENABLE_GATE() palSetPad(GPIOC, 10)

View File

@ -30,6 +30,9 @@
#define HW_NAME "60"
#endif
#define HW_MAJOR 6
#define HW_MINOR 0
// HW properties
#define HW_HAS_DRV8301
#define HW_HAS_3_SHUNTS

View File

@ -2,7 +2,18 @@ CANARDSRC = libcanard/canard.c \
libcanard/canard_driver.c \
libcanard/dsdl/uavcan/equipment/esc/esc_Status.c \
libcanard/dsdl/uavcan/equipment/esc/esc_RawCommand.c \
libcanard/dsdl/uavcan/equipment/esc/esc_RPMCommand.c
libcanard/dsdl/uavcan/equipment/esc/esc_RPMCommand.c \
libcanard/dsdl/uavcan/protocol/protocol_GetNodeInfo.c \
libcanard/dsdl/uavcan/protocol/protocol_HardwareVersion.c \
libcanard/dsdl/uavcan/protocol/protocol_NodeStatus.c \
libcanard/dsdl/uavcan/protocol/protocol_SoftwareVersion.c \
libcanard/dsdl/uavcan/protocol/param/param_Empty.c \
libcanard/dsdl/uavcan/protocol/param/param_ExecuteOpcode.c \
libcanard/dsdl/uavcan/protocol/param/param_GetSet.c \
libcanard/dsdl/uavcan/protocol/param/param_NumericValue.c \
libcanard/dsdl/uavcan/protocol/param/param_Value.c \
libcanard/dsdl/uavcan/protocol/file/file_BeginFirmwareUpdate.c \
libcanard/dsdl/uavcan/protocol/file/file_Read.c
CANARDINC = libcanard \
libcanard/dsdl

1151
libcanard/canard_driver.c Normal file → Executable file

File diff suppressed because it is too large Load Diff

View File

@ -3,7 +3,7 @@
*
* Autogenerated, do not edit.
*
* Source file: /home/benjamin/Skrivbord/tmp/uavcan/libcanard/dsdl_compiler/pyuavcan/uavcan/dsdl_files/uavcan/equipment/esc/1031.RPMCommand.uavcan
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/equipment/esc/1031.RPMCommand.uavcan
*/
#ifndef __UAVCAN_EQUIPMENT_ESC_RPMCOMMAND
@ -64,7 +64,7 @@ extern
uint32_t uavcan_equipment_esc_RPMCommand_encode_internal(uavcan_equipment_esc_RPMCommand* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_equipment_esc_RPMCommand_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_equipment_esc_RPMCommand* dest, uint8_t** dyn_arr_buf, int32_t offset, uint8_t tao);
int32_t uavcan_equipment_esc_RPMCommand_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_equipment_esc_RPMCommand* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"

View File

@ -3,7 +3,7 @@
*
* Autogenerated, do not edit.
*
* Source file: /home/benjamin/Skrivbord/tmp/uavcan/libcanard/dsdl_compiler/pyuavcan/uavcan/dsdl_files/uavcan/equipment/esc/1030.RawCommand.uavcan
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/equipment/esc/1030.RawCommand.uavcan
*/
#ifndef __UAVCAN_EQUIPMENT_ESC_RAWCOMMAND
@ -63,7 +63,7 @@ extern
uint32_t uavcan_equipment_esc_RawCommand_encode_internal(uavcan_equipment_esc_RawCommand* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_equipment_esc_RawCommand_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_equipment_esc_RawCommand* dest, uint8_t** dyn_arr_buf, int32_t offset, uint8_t tao);
int32_t uavcan_equipment_esc_RawCommand_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_equipment_esc_RawCommand* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"

View File

@ -3,7 +3,7 @@
*
* Autogenerated, do not edit.
*
* Source file: /home/benjamin/Skrivbord/tmp/uavcan/libcanard/dsdl_compiler/pyuavcan/uavcan/dsdl_files/uavcan/equipment/esc/1034.Status.uavcan
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/equipment/esc/1034.Status.uavcan
*/
#ifndef __UAVCAN_EQUIPMENT_ESC_STATUS
@ -78,7 +78,7 @@ extern
uint32_t uavcan_equipment_esc_Status_encode_internal(uavcan_equipment_esc_Status* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_equipment_esc_Status_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_equipment_esc_Status* dest, uint8_t** dyn_arr_buf, int32_t offset, uint8_t tao);
int32_t uavcan_equipment_esc_Status_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_equipment_esc_Status* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"

View File

@ -3,7 +3,7 @@
*
* Autogenerated, do not edit.
*
* Source file: /home/benjamin/Skrivbord/tmp/uavcan/libcanard/dsdl_compiler/pyuavcan/uavcan/dsdl_files/uavcan/equipment/esc/1031.RPMCommand.uavcan
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/equipment/esc/1031.RPMCommand.uavcan
*/
#include "uavcan/equipment/esc/RPMCommand.h"
#include "canard.h"
@ -13,12 +13,9 @@
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) > max) ? max : (x) );
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#define CANARD_INTERNAL_ENABLE_TAO ((uint8_t) 1)
#define CANARD_INTERNAL_DISABLE_TAO ((uint8_t) 0)
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
@ -85,7 +82,6 @@ uint32_t uavcan_equipment_esc_RPMCommand_encode(uavcan_equipment_esc_RPMCommand*
* uavcan_equipment_esc_RPMCommand dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @param tao: is tail array optimization used
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_equipment_esc_RPMCommand_decode_internal(
@ -93,15 +89,14 @@ int32_t uavcan_equipment_esc_RPMCommand_decode_internal(
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_equipment_esc_RPMCommand* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset,
uint8_t CANARD_MAYBE_UNUSED(tao))
int32_t offset)
{
int32_t ret = 0;
uint32_t c = 0;
// Dynamic Array (rpm)
// - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization
if (payload_len && tao == CANARD_INTERNAL_ENABLE_TAO)
if (payload_len)
{
// - Calculate Array length from MSG length
dest->rpm.len = ((payload_len * 8) - offset ) / 18; // 18 bit array item size
@ -110,7 +105,7 @@ int32_t uavcan_equipment_esc_RPMCommand_decode_internal(
{
// - Array length 5 bits
ret = canardDecodeScalar(transfer,
offset,
(uint32_t)offset,
5,
false,
(void*)&dest->rpm.len); // 131071
@ -132,7 +127,7 @@ int32_t uavcan_equipment_esc_RPMCommand_decode_internal(
if (dyn_arr_buf)
{
ret = canardDecodeScalar(transfer,
offset,
(uint32_t)offset,
18,
true,
(void*)*dyn_arr_buf); // 131071
@ -175,33 +170,13 @@ int32_t uavcan_equipment_esc_RPMCommand_decode(const CanardRxTransfer* transfer,
const int32_t offset = 0;
int32_t ret = 0;
/* Backward compatibility support for removing TAO
* - first try to decode with TAO DISABLED
* - if it fails fall back to TAO ENABLED
*/
uint8_t tao = CANARD_INTERNAL_DISABLE_TAO;
while (1)
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_equipment_esc_RPMCommand); c++)
{
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_equipment_esc_RPMCommand); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_equipment_esc_RPMCommand_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset, tao);
if (ret >= 0)
{
break;
}
if (tao == CANARD_INTERNAL_ENABLE_TAO)
{
break;
}
tao = CANARD_INTERNAL_ENABLE_TAO;
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_equipment_esc_RPMCommand_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -3,7 +3,7 @@
*
* Autogenerated, do not edit.
*
* Source file: /home/benjamin/Skrivbord/tmp/uavcan/libcanard/dsdl_compiler/pyuavcan/uavcan/dsdl_files/uavcan/equipment/esc/1030.RawCommand.uavcan
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/equipment/esc/1030.RawCommand.uavcan
*/
#include "uavcan/equipment/esc/RawCommand.h"
#include "canard.h"
@ -13,12 +13,9 @@
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) > max) ? max : (x) );
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#define CANARD_INTERNAL_ENABLE_TAO ((uint8_t) 1)
#define CANARD_INTERNAL_DISABLE_TAO ((uint8_t) 0)
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
@ -85,7 +82,6 @@ uint32_t uavcan_equipment_esc_RawCommand_encode(uavcan_equipment_esc_RawCommand*
* uavcan_equipment_esc_RawCommand dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @param tao: is tail array optimization used
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_equipment_esc_RawCommand_decode_internal(
@ -93,15 +89,14 @@ int32_t uavcan_equipment_esc_RawCommand_decode_internal(
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_equipment_esc_RawCommand* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset,
uint8_t CANARD_MAYBE_UNUSED(tao))
int32_t offset)
{
int32_t ret = 0;
uint32_t c = 0;
// Dynamic Array (cmd)
// - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization
if (payload_len && tao == CANARD_INTERNAL_ENABLE_TAO)
if (payload_len)
{
// - Calculate Array length from MSG length
dest->cmd.len = ((payload_len * 8) - offset ) / 14; // 14 bit array item size
@ -110,7 +105,7 @@ int32_t uavcan_equipment_esc_RawCommand_decode_internal(
{
// - Array length 5 bits
ret = canardDecodeScalar(transfer,
offset,
(uint32_t)offset,
5,
false,
(void*)&dest->cmd.len); // 8191
@ -132,7 +127,7 @@ int32_t uavcan_equipment_esc_RawCommand_decode_internal(
if (dyn_arr_buf)
{
ret = canardDecodeScalar(transfer,
offset,
(uint32_t)offset,
14,
true,
(void*)*dyn_arr_buf); // 8191
@ -175,33 +170,13 @@ int32_t uavcan_equipment_esc_RawCommand_decode(const CanardRxTransfer* transfer,
const int32_t offset = 0;
int32_t ret = 0;
/* Backward compatibility support for removing TAO
* - first try to decode with TAO DISABLED
* - if it fails fall back to TAO ENABLED
*/
uint8_t tao = CANARD_INTERNAL_DISABLE_TAO;
while (1)
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_equipment_esc_RawCommand); c++)
{
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_equipment_esc_RawCommand); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_equipment_esc_RawCommand_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset, tao);
if (ret >= 0)
{
break;
}
if (tao == CANARD_INTERNAL_ENABLE_TAO)
{
break;
}
tao = CANARD_INTERNAL_ENABLE_TAO;
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_equipment_esc_RawCommand_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -3,7 +3,7 @@
*
* Autogenerated, do not edit.
*
* Source file: /home/benjamin/Skrivbord/tmp/uavcan/libcanard/dsdl_compiler/pyuavcan/uavcan/dsdl_files/uavcan/equipment/esc/1034.Status.uavcan
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/equipment/esc/1034.Status.uavcan
*/
#include "uavcan/equipment/esc/Status.h"
#include "canard.h"
@ -13,12 +13,9 @@
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) > max) ? max : (x) );
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#define CANARD_INTERNAL_ENABLE_TAO ((uint8_t) 1)
#define CANARD_INTERNAL_DISABLE_TAO ((uint8_t) 0)
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
@ -112,7 +109,6 @@ uint32_t uavcan_equipment_esc_Status_encode(uavcan_equipment_esc_Status* source,
* uavcan_equipment_esc_Status dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @param tao: is tail array optimization used
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_equipment_esc_Status_decode_internal(
@ -120,8 +116,7 @@ int32_t uavcan_equipment_esc_Status_decode_internal(
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_equipment_esc_Status* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset,
uint8_t CANARD_MAYBE_UNUSED(tao))
int32_t offset)
{
int32_t ret = 0;
#ifndef CANARD_USE_FLOAT16_CAST
@ -130,7 +125,7 @@ int32_t uavcan_equipment_esc_Status_decode_internal(
CANARD_USE_FLOAT16_CAST tmp_float = 0;
#endif
ret = canardDecodeScalar(transfer, offset, 32, false, (void*)&dest->error_count);
ret = canardDecodeScalar(transfer, (uint32_t)offset, 32, false, (void*)&dest->error_count);
if (ret != 32)
{
goto uavcan_equipment_esc_Status_error_exit;
@ -138,7 +133,7 @@ int32_t uavcan_equipment_esc_Status_decode_internal(
offset += 32;
// float16 special handling
ret = canardDecodeScalar(transfer, offset, 16, false, (void*)&tmp_float);
ret = canardDecodeScalar(transfer, (uint32_t)offset, 16, false, (void*)&tmp_float);
if (ret != 16)
{
@ -152,7 +147,7 @@ int32_t uavcan_equipment_esc_Status_decode_internal(
offset += 16;
// float16 special handling
ret = canardDecodeScalar(transfer, offset, 16, false, (void*)&tmp_float);
ret = canardDecodeScalar(transfer, (uint32_t)offset, 16, false, (void*)&tmp_float);
if (ret != 16)
{
@ -166,7 +161,7 @@ int32_t uavcan_equipment_esc_Status_decode_internal(
offset += 16;
// float16 special handling
ret = canardDecodeScalar(transfer, offset, 16, false, (void*)&tmp_float);
ret = canardDecodeScalar(transfer, (uint32_t)offset, 16, false, (void*)&tmp_float);
if (ret != 16)
{
@ -179,21 +174,21 @@ int32_t uavcan_equipment_esc_Status_decode_internal(
#endif
offset += 16;
ret = canardDecodeScalar(transfer, offset, 18, true, (void*)&dest->rpm);
ret = canardDecodeScalar(transfer, (uint32_t)offset, 18, true, (void*)&dest->rpm);
if (ret != 18)
{
goto uavcan_equipment_esc_Status_error_exit;
}
offset += 18;
ret = canardDecodeScalar(transfer, offset, 7, false, (void*)&dest->power_rating_pct);
ret = canardDecodeScalar(transfer, (uint32_t)offset, 7, false, (void*)&dest->power_rating_pct);
if (ret != 7)
{
goto uavcan_equipment_esc_Status_error_exit;
}
offset += 7;
ret = canardDecodeScalar(transfer, offset, 5, false, (void*)&dest->esc_index);
ret = canardDecodeScalar(transfer, (uint32_t)offset, 5, false, (void*)&dest->esc_index);
if (ret != 5)
{
goto uavcan_equipment_esc_Status_error_exit;
@ -230,33 +225,13 @@ int32_t uavcan_equipment_esc_Status_decode(const CanardRxTransfer* transfer,
const int32_t offset = 0;
int32_t ret = 0;
/* Backward compatibility support for removing TAO
* - first try to decode with TAO DISABLED
* - if it fails fall back to TAO ENABLED
*/
uint8_t tao = CANARD_INTERNAL_DISABLE_TAO;
while (1)
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_equipment_esc_Status); c++)
{
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_equipment_esc_Status); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_equipment_esc_Status_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset, tao);
if (ret >= 0)
{
break;
}
if (tao == CANARD_INTERNAL_ENABLE_TAO)
{
break;
}
tao = CANARD_INTERNAL_ENABLE_TAO;
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_equipment_esc_Status_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,120 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/AION/ardupilot_private/modules/uavcan/dsdl/uavcan/protocol/1.GetNodeInfo.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_GETNODEINFO
#define __UAVCAN_PROTOCOL_GETNODEINFO
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
#include <uavcan/protocol/HardwareVersion.h>
#include <uavcan/protocol/NodeStatus.h>
#include <uavcan/protocol/SoftwareVersion.h>
/******************************* Source text **********************************
#
# Full node info request.
# Note that all fields of the response section are byte-aligned.
#
---
#
# Current node status
#
NodeStatus status
#
# Version information shall not be changed while the node is running.
#
SoftwareVersion software_version
HardwareVersion hardware_version
#
# Human readable non-empty ASCII node name.
# Node name shall not be changed while the node is running.
# Empty string is not a valid node name.
# Allowed characters are: a-z (lowercase ASCII letters) 0-9 (decimal digits) . (dot) - (dash) _ (underscore).
# Node name is a reversed internet domain name (like Java packages), e.g. "com.manufacturer.project.product".
#
uint8[<=80] name
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.GetNodeInfo
---
uavcan.protocol.NodeStatus status
uavcan.protocol.SoftwareVersion software_version
uavcan.protocol.HardwareVersion hardware_version
saturated uint8[<=80] name
******************************************************************************/
#define UAVCAN_PROTOCOL_GETNODEINFO_ID 1
#define UAVCAN_PROTOCOL_GETNODEINFO_NAME "uavcan.protocol.GetNodeInfo"
#define UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE (0xEE468A8121C46A9EULL)
#define UAVCAN_PROTOCOL_GETNODEINFO_REQUEST_MAX_SIZE ((0 + 7)/8)
typedef struct
{
uint8_t empty;
} uavcan_protocol_GetNodeInfoRequest;
extern
uint32_t uavcan_protocol_GetNodeInfoRequest_encode(uavcan_protocol_GetNodeInfoRequest* source, void* msg_buf);
extern
int32_t uavcan_protocol_GetNodeInfoRequest_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_GetNodeInfoRequest* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_GetNodeInfoRequest_encode_internal(uavcan_protocol_GetNodeInfoRequest* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_GetNodeInfoRequest_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_GetNodeInfoRequest* dest, uint8_t** dyn_arr_buf, int32_t offset);
#define UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE ((3015 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_NAME_MAX_LENGTH 80
typedef struct
{
// FieldTypes
uavcan_protocol_NodeStatus status; //
uavcan_protocol_SoftwareVersion software_version; //
uavcan_protocol_HardwareVersion hardware_version; //
struct
{
uint8_t len; // Dynamic array length
uint8_t* data; // Dynamic Array 8bit[80] max items
} name;
} uavcan_protocol_GetNodeInfoResponse;
extern
uint32_t uavcan_protocol_GetNodeInfoResponse_encode(uavcan_protocol_GetNodeInfoResponse* source, void* msg_buf);
extern
int32_t uavcan_protocol_GetNodeInfoResponse_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_GetNodeInfoResponse* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_GetNodeInfoResponse_encode_internal(uavcan_protocol_GetNodeInfoResponse* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_GetNodeInfoResponse_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_GetNodeInfoResponse* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_GETNODEINFO

View File

@ -0,0 +1,93 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/HardwareVersion.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_HARDWAREVERSION
#define __UAVCAN_PROTOCOL_HARDWAREVERSION
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
/******************************* Source text **********************************
#
# Nested type.
# Generic hardware version information.
# These values should remain unchanged for the device's lifetime.
#
#
# Hardware version code.
#
uint8 major
uint8 minor
#
# Unique ID is a 128 bit long sequence that is globally unique for each node.
# All zeros is not a valid UID.
# If filled with zeros, assume that the value is undefined.
#
uint8[16] unique_id
#
# Certificate of authenticity (COA) of the hardware, 255 bytes max.
#
uint8[<=255] certificate_of_authenticity
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.HardwareVersion
saturated uint8 major
saturated uint8 minor
saturated uint8[16] unique_id
saturated uint8[<=255] certificate_of_authenticity
******************************************************************************/
#define UAVCAN_PROTOCOL_HARDWAREVERSION_NAME "uavcan.protocol.HardwareVersion"
#define UAVCAN_PROTOCOL_HARDWAREVERSION_SIGNATURE (0xAD5C4C933F4A0C4ULL)
#define UAVCAN_PROTOCOL_HARDWAREVERSION_MAX_SIZE ((2192 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_HARDWAREVERSION_UNIQUE_ID_LENGTH 16
#define UAVCAN_PROTOCOL_HARDWAREVERSION_CERTIFICATE_OF_AUTHENTICITY_MAX_LENGTH 255
typedef struct
{
// FieldTypes
uint8_t major; // bit len 8
uint8_t minor; // bit len 8
uint8_t unique_id[16]; // Static Array 8bit[16] max items
struct
{
uint8_t len; // Dynamic array length
uint8_t* data; // Dynamic Array 8bit[255] max items
} certificate_of_authenticity;
} uavcan_protocol_HardwareVersion;
extern
uint32_t uavcan_protocol_HardwareVersion_encode(uavcan_protocol_HardwareVersion* source, void* msg_buf);
extern
int32_t uavcan_protocol_HardwareVersion_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_HardwareVersion* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_HardwareVersion_encode_internal(uavcan_protocol_HardwareVersion* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_HardwareVersion_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_HardwareVersion* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_HARDWAREVERSION

View File

@ -0,0 +1,136 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/AION/ardupilot_private/modules/uavcan/dsdl/uavcan/protocol/341.NodeStatus.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_NODESTATUS
#define __UAVCAN_PROTOCOL_NODESTATUS
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
/******************************* Source text **********************************
#
# Abstract node status information.
#
# All UAVCAN nodes are required to publish this message periodically.
#
#
# Publication period may vary within these limits.
# It is NOT recommended to change it at run time.
#
uint16 MAX_BROADCASTING_PERIOD_MS = 1000
uint16 MIN_BROADCASTING_PERIOD_MS = 2
#
# If a node fails to publish this message in this amount of time, it should be considered offline.
#
uint16 OFFLINE_TIMEOUT_MS = 3000
#
# Uptime counter should never overflow.
# Other nodes may detect that a remote node has restarted when this value goes backwards.
#
uint32 uptime_sec
#
# Abstract node health.
#
uint2 HEALTH_OK = 0 # The node is functioning properly.
uint2 HEALTH_WARNING = 1 # A critical parameter went out of range or the node encountered a minor failure.
uint2 HEALTH_ERROR = 2 # The node encountered a major failure.
uint2 HEALTH_CRITICAL = 3 # The node suffered a fatal malfunction.
uint2 health
#
# Current mode.
#
# Mode OFFLINE can be actually reported by the node to explicitly inform other network
# participants that the sending node is about to shutdown. In this case other nodes will not
# have to wait OFFLINE_TIMEOUT_MS before they detect that the node is no longer available.
#
# Reserved values can be used in future revisions of the specification.
#
uint3 MODE_OPERATIONAL = 0 # Normal operating mode.
uint3 MODE_INITIALIZATION = 1 # Initialization is in progress; this mode is entered immediately after startup.
uint3 MODE_MAINTENANCE = 2 # E.g. calibration, the bootloader is running, etc.
uint3 MODE_SOFTWARE_UPDATE = 3 # New software/firmware is being loaded.
uint3 MODE_OFFLINE = 7 # The node is no longer available.
uint3 mode
#
# Not used currently, keep zero when publishing, ignore when receiving.
#
uint3 sub_mode
#
# Optional, vendor-specific node status code, e.g. a fault code or a status bitmask.
#
uint16 vendor_specific_status_code
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.NodeStatus
saturated uint32 uptime_sec
saturated uint2 health
saturated uint3 mode
saturated uint3 sub_mode
saturated uint16 vendor_specific_status_code
******************************************************************************/
#define UAVCAN_PROTOCOL_NODESTATUS_ID 341
#define UAVCAN_PROTOCOL_NODESTATUS_NAME "uavcan.protocol.NodeStatus"
#define UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE (0xF0868D0C1A7C6F1ULL)
#define UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE ((56 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_NODESTATUS_MAX_BROADCASTING_PERIOD_MS 1000 // 1000
#define UAVCAN_PROTOCOL_NODESTATUS_MIN_BROADCASTING_PERIOD_MS 2 // 2
#define UAVCAN_PROTOCOL_NODESTATUS_OFFLINE_TIMEOUT_MS 3000 // 3000
#define UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK 0 // 0
#define UAVCAN_PROTOCOL_NODESTATUS_HEALTH_WARNING 1 // 1
#define UAVCAN_PROTOCOL_NODESTATUS_HEALTH_ERROR 2 // 2
#define UAVCAN_PROTOCOL_NODESTATUS_HEALTH_CRITICAL 3 // 3
#define UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL 0 // 0
#define UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION 1 // 1
#define UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE 2 // 2
#define UAVCAN_PROTOCOL_NODESTATUS_MODE_SOFTWARE_UPDATE 3 // 3
#define UAVCAN_PROTOCOL_NODESTATUS_MODE_OFFLINE 7 // 7
typedef struct
{
// FieldTypes
uint32_t uptime_sec; // bit len 32
uint8_t health; // bit len 2
uint8_t mode; // bit len 3
uint8_t sub_mode; // bit len 3
uint16_t vendor_specific_status_code; // bit len 16
} uavcan_protocol_NodeStatus;
extern
uint32_t uavcan_protocol_NodeStatus_encode(uavcan_protocol_NodeStatus* source, void* msg_buf);
extern
int32_t uavcan_protocol_NodeStatus_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_NodeStatus* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_NodeStatus_encode_internal(uavcan_protocol_NodeStatus* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_NodeStatus_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_NodeStatus* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_NODESTATUS

View File

@ -0,0 +1,98 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/5.RestartNode.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_RESTARTNODE
#define __UAVCAN_PROTOCOL_RESTARTNODE
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
/******************************* Source text **********************************
#
# Restart the node.
#
# Some nodes may require restart before the new configuration will be applied.
#
# The request should be rejected if magic_number does not equal MAGIC_NUMBER.
#
uint40 MAGIC_NUMBER = 0xACCE551B1E
uint40 magic_number
---
bool ok
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.RestartNode
saturated uint40 magic_number
---
saturated bool ok
******************************************************************************/
#define UAVCAN_PROTOCOL_RESTARTNODE_ID 5
#define UAVCAN_PROTOCOL_RESTARTNODE_NAME "uavcan.protocol.RestartNode"
#define UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE (0x569E05394A3017F0ULL)
#define UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_MAX_SIZE ((40 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_MAGIC_NUMBER 0xACCE551B1E // 0xACCE551B1E
typedef struct
{
// FieldTypes
uint64_t magic_number; // bit len 40
} uavcan_protocol_RestartNodeRequest;
extern
uint32_t uavcan_protocol_RestartNodeRequest_encode(uavcan_protocol_RestartNodeRequest* source, void* msg_buf);
extern
int32_t uavcan_protocol_RestartNodeRequest_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_RestartNodeRequest* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_RestartNodeRequest_encode_internal(uavcan_protocol_RestartNodeRequest* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_RestartNodeRequest_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_RestartNodeRequest* dest, uint8_t** dyn_arr_buf, int32_t offset);
#define UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_MAX_SIZE ((1 + 7)/8)
// Constants
typedef struct
{
// FieldTypes
bool ok; // bit len 1
} uavcan_protocol_RestartNodeResponse;
extern
uint32_t uavcan_protocol_RestartNodeResponse_encode(uavcan_protocol_RestartNodeResponse* source, void* msg_buf);
extern
int32_t uavcan_protocol_RestartNodeResponse_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_RestartNodeResponse* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_RestartNodeResponse_encode_internal(uavcan_protocol_RestartNodeResponse* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_RestartNodeResponse_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_RestartNodeResponse* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_RESTARTNODE

View File

@ -0,0 +1,111 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/SoftwareVersion.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_SOFTWAREVERSION
#define __UAVCAN_PROTOCOL_SOFTWAREVERSION
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
/******************************* Source text **********************************
#
# Nested type.
# Generic software version information.
#
#
# Primary version numbers.
# If both fields are set to zero, the version is considered unknown.
#
uint8 major
uint8 minor
#
# This mask indicates which optional fields (see below) are set.
#
uint8 OPTIONAL_FIELD_FLAG_VCS_COMMIT = 1
uint8 OPTIONAL_FIELD_FLAG_IMAGE_CRC = 2
uint8 optional_field_flags
#
# VCS commit hash or revision number, e.g. git short commit hash. Optional.
#
uint32 vcs_commit
#
# The value of an arbitrary hash function applied to the firmware image.
# This field is used to detect whether the firmware running on the node is EXACTLY THE SAME
# as a certain specific revision. This field provides the absolute identity guarantee, unlike
# the version fields above, which can be the same for different builds of the firmware.
#
# The exact hash function and the methods of its application are implementation defined.
# However, implementations are recommended to adhere to the following guidelines,
# fully or partially:
#
# - The hash function should be CRC-64-WE, the same that is used for computing DSDL signatures.
#
# - The hash function should be applied to the entire application image padded to 8 bytes.
#
# - If the computed image CRC is stored within the firmware image itself, the value of
# the hash function becomes ill-defined, because it becomes recursively dependent on itself.
# In order to circumvent this issue, while computing or checking the CRC, its value stored
# within the image should be zeroed out.
#
uint64 image_crc
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.SoftwareVersion
saturated uint8 major
saturated uint8 minor
saturated uint8 optional_field_flags
saturated uint32 vcs_commit
saturated uint64 image_crc
******************************************************************************/
#define UAVCAN_PROTOCOL_SOFTWAREVERSION_NAME "uavcan.protocol.SoftwareVersion"
#define UAVCAN_PROTOCOL_SOFTWAREVERSION_SIGNATURE (0xDD46FD376527FEA1ULL)
#define UAVCAN_PROTOCOL_SOFTWAREVERSION_MAX_SIZE ((120 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_VCS_COMMIT 1 // 1
#define UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_IMAGE_CRC 2 // 2
typedef struct
{
// FieldTypes
uint8_t major; // bit len 8
uint8_t minor; // bit len 8
uint8_t optional_field_flags; // bit len 8
uint32_t vcs_commit; // bit len 32
uint64_t image_crc; // bit len 64
} uavcan_protocol_SoftwareVersion;
extern
uint32_t uavcan_protocol_SoftwareVersion_encode(uavcan_protocol_SoftwareVersion* source, void* msg_buf);
extern
int32_t uavcan_protocol_SoftwareVersion_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_SoftwareVersion* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_SoftwareVersion_encode_internal(uavcan_protocol_SoftwareVersion* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_SoftwareVersion_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_SoftwareVersion* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_SOFTWAREVERSION

View File

@ -0,0 +1,130 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/40.BeginFirmwareUpdate.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE
#define __UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
#include <uavcan/protocol/file/Path.h>
/******************************* Source text **********************************
#
# This service initiates firmware update on a remote node.
#
# The node that is being updated (slave) will retrieve the firmware image file 'image_file_remote_path' from the node
# 'source_node_id' using the file read service, then it will update the firmware and reboot.
#
# The slave can explicitly reject this request if it is not possible to update the firmware at the moment
# (e.g. if the node is busy).
#
# If the slave node accepts this request, the initiator will get a response immediately, before the update process
# actually begins.
#
# While the firmware is being updated, the slave should set its mode (uavcan.protocol.NodeStatus.mode) to
# MODE_SOFTWARE_UPDATE.
#
uint8 source_node_id # If this field is zero, the caller's Node ID will be used instead.
Path image_file_remote_path
---
#
# Other error codes may be added in the future.
#
uint8 ERROR_OK = 0
uint8 ERROR_INVALID_MODE = 1 # Cannot perform the update in the current operating mode or state.
uint8 ERROR_IN_PROGRESS = 2 # Firmware update is already in progress, and the slave doesn't want to restart.
uint8 ERROR_UNKNOWN = 255
uint8 error
uint8[<128] optional_error_message # Detailed description of the error.
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.file.BeginFirmwareUpdate
saturated uint8 source_node_id
uavcan.protocol.file.Path image_file_remote_path
---
saturated uint8 error
saturated uint8[<=127] optional_error_message
******************************************************************************/
#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID 40
#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_NAME "uavcan.protocol.file.BeginFirmwareUpdate"
#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE (0xB7D725DF72724126ULL)
#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_REQUEST_MAX_SIZE ((1616 + 7)/8)
// Constants
typedef struct
{
// FieldTypes
uint8_t source_node_id; // bit len 8
uavcan_protocol_file_Path image_file_remote_path; //
} uavcan_protocol_file_BeginFirmwareUpdateRequest;
extern
uint32_t uavcan_protocol_file_BeginFirmwareUpdateRequest_encode(uavcan_protocol_file_BeginFirmwareUpdateRequest* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_BeginFirmwareUpdateRequest* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_BeginFirmwareUpdateRequest_encode_internal(uavcan_protocol_file_BeginFirmwareUpdateRequest* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_BeginFirmwareUpdateRequest_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_BeginFirmwareUpdateRequest* dest, uint8_t** dyn_arr_buf, int32_t offset);
#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE ((1031 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK 0 // 0
#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_INVALID_MODE 1 // 1
#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_IN_PROGRESS 2 // 2
#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_UNKNOWN 255 // 255
#define UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_OPTIONAL_ERROR_MESSAGE_MAX_LENGTH 127
typedef struct
{
// FieldTypes
uint8_t error; // bit len 8
struct
{
uint8_t len; // Dynamic array length
uint8_t* data; // Dynamic Array 8bit[127] max items
} optional_error_message;
} uavcan_protocol_file_BeginFirmwareUpdateResponse;
extern
uint32_t uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(uavcan_protocol_file_BeginFirmwareUpdateResponse* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_BeginFirmwareUpdateResponse_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_BeginFirmwareUpdateResponse* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_BeginFirmwareUpdateResponse_encode_internal(uavcan_protocol_file_BeginFirmwareUpdateResponse* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_BeginFirmwareUpdateResponse_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_BeginFirmwareUpdateResponse* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE

View File

@ -0,0 +1,96 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/47.Delete.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_FILE_DELETE
#define __UAVCAN_PROTOCOL_FILE_DELETE
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
#include <uavcan/protocol/file/Error.h>
#include <uavcan/protocol/file/Path.h>
/******************************* Source text **********************************
#
# Delete remote file system entry.
# If the remote entry is a directory, all nested entries will be removed too.
#
Path path
---
Error error
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.file.Delete
uavcan.protocol.file.Path path
---
uavcan.protocol.file.Error error
******************************************************************************/
#define UAVCAN_PROTOCOL_FILE_DELETE_ID 47
#define UAVCAN_PROTOCOL_FILE_DELETE_NAME "uavcan.protocol.file.Delete"
#define UAVCAN_PROTOCOL_FILE_DELETE_SIGNATURE (0x78648C99170B47AAULL)
#define UAVCAN_PROTOCOL_FILE_DELETE_REQUEST_MAX_SIZE ((1608 + 7)/8)
// Constants
typedef struct
{
// FieldTypes
uavcan_protocol_file_Path path; //
} uavcan_protocol_file_DeleteRequest;
extern
uint32_t uavcan_protocol_file_DeleteRequest_encode(uavcan_protocol_file_DeleteRequest* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_DeleteRequest_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_DeleteRequest* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_DeleteRequest_encode_internal(uavcan_protocol_file_DeleteRequest* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_DeleteRequest_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_DeleteRequest* dest, uint8_t** dyn_arr_buf, int32_t offset);
#define UAVCAN_PROTOCOL_FILE_DELETE_RESPONSE_MAX_SIZE ((16 + 7)/8)
// Constants
typedef struct
{
// FieldTypes
uavcan_protocol_file_Error error; //
} uavcan_protocol_file_DeleteResponse;
extern
uint32_t uavcan_protocol_file_DeleteResponse_encode(uavcan_protocol_file_DeleteResponse* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_DeleteResponse_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_DeleteResponse* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_DeleteResponse_encode_internal(uavcan_protocol_file_DeleteResponse* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_DeleteResponse_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_DeleteResponse* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_FILE_DELETE

View File

@ -0,0 +1,75 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/EntryType.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_FILE_ENTRYTYPE
#define __UAVCAN_PROTOCOL_FILE_ENTRYTYPE
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
/******************************* Source text **********************************
#
# Nested type.
# Represents the type of the file system entry (e.g. file or directory).
# If such entry does not exist, 'flags' must be set to zero.
#
uint8 FLAG_FILE = 1 # Excludes FLAG_DIRECTORY
uint8 FLAG_DIRECTORY = 2 # Excludes FLAG_FILE
uint8 FLAG_SYMLINK = 4 # Link target is either FLAG_FILE or FLAG_DIRECTORY
uint8 FLAG_READABLE = 8
uint8 FLAG_WRITEABLE = 16
uint8 flags
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.file.EntryType
saturated uint8 flags
******************************************************************************/
#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_NAME "uavcan.protocol.file.EntryType"
#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_SIGNATURE (0x6924572FBB2086E5ULL)
#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_MAX_SIZE ((8 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_FLAG_FILE 1 // 1
#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_FLAG_DIRECTORY 2 // 2
#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_FLAG_SYMLINK 4 // 4
#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_FLAG_READABLE 8 // 8
#define UAVCAN_PROTOCOL_FILE_ENTRYTYPE_FLAG_WRITEABLE 16 // 16
typedef struct
{
// FieldTypes
uint8_t flags; // bit len 8
} uavcan_protocol_file_EntryType;
extern
uint32_t uavcan_protocol_file_EntryType_encode(uavcan_protocol_file_EntryType* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_EntryType_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_EntryType* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_EntryType_encode_internal(uavcan_protocol_file_EntryType* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_EntryType_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_EntryType* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_FILE_ENTRYTYPE

View File

@ -0,0 +1,85 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/Error.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_FILE_ERROR
#define __UAVCAN_PROTOCOL_FILE_ERROR
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
/******************************* Source text **********************************
#
# Nested type.
# File operation result code.
#
int16 OK = 0
int16 UNKNOWN_ERROR = 32767
int16 NOT_FOUND = 2
int16 IO_ERROR = 5
int16 ACCESS_DENIED = 13
int16 IS_DIRECTORY = 21 # I.e. attempt to read/write on a path that points to a directory
int16 INVALID_VALUE = 22 # E.g. file name is not valid for the target file system
int16 FILE_TOO_LARGE = 27
int16 OUT_OF_SPACE = 28
int16 NOT_IMPLEMENTED = 38
int16 value
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.file.Error
saturated int16 value
******************************************************************************/
#define UAVCAN_PROTOCOL_FILE_ERROR_NAME "uavcan.protocol.file.Error"
#define UAVCAN_PROTOCOL_FILE_ERROR_SIGNATURE (0xA83071FFEA4FAE15ULL)
#define UAVCAN_PROTOCOL_FILE_ERROR_MAX_SIZE ((16 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_FILE_ERROR_OK 0 // 0
#define UAVCAN_PROTOCOL_FILE_ERROR_UNKNOWN_ERROR 32767 // 32767
#define UAVCAN_PROTOCOL_FILE_ERROR_NOT_FOUND 2 // 2
#define UAVCAN_PROTOCOL_FILE_ERROR_IO_ERROR 5 // 5
#define UAVCAN_PROTOCOL_FILE_ERROR_ACCESS_DENIED 13 // 13
#define UAVCAN_PROTOCOL_FILE_ERROR_IS_DIRECTORY 21 // 21
#define UAVCAN_PROTOCOL_FILE_ERROR_INVALID_VALUE 22 // 22
#define UAVCAN_PROTOCOL_FILE_ERROR_FILE_TOO_LARGE 27 // 27
#define UAVCAN_PROTOCOL_FILE_ERROR_OUT_OF_SPACE 28 // 28
#define UAVCAN_PROTOCOL_FILE_ERROR_NOT_IMPLEMENTED 38 // 38
typedef struct
{
// FieldTypes
int16_t value; // bit len 16
} uavcan_protocol_file_Error;
extern
uint32_t uavcan_protocol_file_Error_encode(uavcan_protocol_file_Error* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_Error_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_Error* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_Error_encode_internal(uavcan_protocol_file_Error* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_Error_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_Error* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_FILE_ERROR

View File

@ -0,0 +1,114 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/46.GetDirectoryEntryInfo.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO
#define __UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
#include <uavcan/protocol/file/EntryType.h>
#include <uavcan/protocol/file/Error.h>
#include <uavcan/protocol/file/Path.h>
/******************************* Source text **********************************
#
# This service can be used to retrieve a remote directory listing, one entry per request.
#
# The client should query each entry independently, iterating 'entry_index' from 0 until the last entry is passed,
# in which case the server will report that there is no such entry (via the fields 'entry_type' and 'error').
#
# The entry_index shall be applied to the ordered list of directory entries (e.g. alphabetically ordered). The exact
# sorting criteria does not matter as long as it provides the same ordering for subsequent service calls.
#
uint32 entry_index
Path directory_path
---
Error error
EntryType entry_type
Path entry_full_path # Ignored/Empty if such entry does not exist.
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.file.GetDirectoryEntryInfo
saturated uint32 entry_index
uavcan.protocol.file.Path directory_path
---
uavcan.protocol.file.Error error
uavcan.protocol.file.EntryType entry_type
uavcan.protocol.file.Path entry_full_path
******************************************************************************/
#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_ID 46
#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_NAME "uavcan.protocol.file.GetDirectoryEntryInfo"
#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_SIGNATURE (0x8C46E8AB568BDA79ULL)
#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_REQUEST_MAX_SIZE ((1640 + 7)/8)
// Constants
typedef struct
{
// FieldTypes
uint32_t entry_index; // bit len 32
uavcan_protocol_file_Path directory_path; //
} uavcan_protocol_file_GetDirectoryEntryInfoRequest;
extern
uint32_t uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode(uavcan_protocol_file_GetDirectoryEntryInfoRequest* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_GetDirectoryEntryInfoRequest* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode_internal(uavcan_protocol_file_GetDirectoryEntryInfoRequest* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_GetDirectoryEntryInfoRequest* dest, uint8_t** dyn_arr_buf, int32_t offset);
#define UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_RESPONSE_MAX_SIZE ((1632 + 7)/8)
// Constants
typedef struct
{
// FieldTypes
uavcan_protocol_file_Error error; //
uavcan_protocol_file_EntryType entry_type; //
uavcan_protocol_file_Path entry_full_path; //
} uavcan_protocol_file_GetDirectoryEntryInfoResponse;
extern
uint32_t uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode(uavcan_protocol_file_GetDirectoryEntryInfoResponse* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_GetDirectoryEntryInfoResponse* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode_internal(uavcan_protocol_file_GetDirectoryEntryInfoResponse* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_GetDirectoryEntryInfoResponse* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO

View File

@ -0,0 +1,108 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/45.GetInfo.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_FILE_GETINFO
#define __UAVCAN_PROTOCOL_FILE_GETINFO
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
#include <uavcan/protocol/file/EntryType.h>
#include <uavcan/protocol/file/Error.h>
#include <uavcan/protocol/file/Path.h>
/******************************* Source text **********************************
#
# Request info about a remote file system entry (file, directory, etc).
#
Path path
---
#
# File size in bytes.
# Should be set to zero for directories.
#
uint40 size
Error error
EntryType entry_type
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.file.GetInfo
uavcan.protocol.file.Path path
---
saturated uint40 size
uavcan.protocol.file.Error error
uavcan.protocol.file.EntryType entry_type
******************************************************************************/
#define UAVCAN_PROTOCOL_FILE_GETINFO_ID 45
#define UAVCAN_PROTOCOL_FILE_GETINFO_NAME "uavcan.protocol.file.GetInfo"
#define UAVCAN_PROTOCOL_FILE_GETINFO_SIGNATURE (0x5004891EE8A27531ULL)
#define UAVCAN_PROTOCOL_FILE_GETINFO_REQUEST_MAX_SIZE ((1608 + 7)/8)
// Constants
typedef struct
{
// FieldTypes
uavcan_protocol_file_Path path; //
} uavcan_protocol_file_GetInfoRequest;
extern
uint32_t uavcan_protocol_file_GetInfoRequest_encode(uavcan_protocol_file_GetInfoRequest* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_GetInfoRequest_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_GetInfoRequest* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_GetInfoRequest_encode_internal(uavcan_protocol_file_GetInfoRequest* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_GetInfoRequest_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_GetInfoRequest* dest, uint8_t** dyn_arr_buf, int32_t offset);
#define UAVCAN_PROTOCOL_FILE_GETINFO_RESPONSE_MAX_SIZE ((64 + 7)/8)
// Constants
typedef struct
{
// FieldTypes
uint64_t size; // bit len 40
uavcan_protocol_file_Error error; //
uavcan_protocol_file_EntryType entry_type; //
} uavcan_protocol_file_GetInfoResponse;
extern
uint32_t uavcan_protocol_file_GetInfoResponse_encode(uavcan_protocol_file_GetInfoResponse* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_GetInfoResponse_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_GetInfoResponse* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_GetInfoResponse_encode_internal(uavcan_protocol_file_GetInfoResponse* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_GetInfoResponse_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_GetInfoResponse* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_FILE_GETINFO

View File

@ -0,0 +1,75 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/Path.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_FILE_PATH
#define __UAVCAN_PROTOCOL_FILE_PATH
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
/******************************* Source text **********************************
#
# Nested type.
#
# File system path in UTF8.
#
# The only valid separator is forward slash.
#
uint8 SEPARATOR = '/'
uint8[<=200] path
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.file.Path
saturated uint8[<=200] path
******************************************************************************/
#define UAVCAN_PROTOCOL_FILE_PATH_NAME "uavcan.protocol.file.Path"
#define UAVCAN_PROTOCOL_FILE_PATH_SIGNATURE (0x12AEFC50878A43E2ULL)
#define UAVCAN_PROTOCOL_FILE_PATH_MAX_SIZE ((1608 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_FILE_PATH_SEPARATOR '/' // '/'
#define UAVCAN_PROTOCOL_FILE_PATH_PATH_MAX_LENGTH 200
typedef struct
{
// FieldTypes
struct
{
uint8_t len; // Dynamic array length
uint8_t* data; // Dynamic Array 8bit[200] max items
} path;
} uavcan_protocol_file_Path;
extern
uint32_t uavcan_protocol_file_Path_encode(uavcan_protocol_file_Path* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_Path_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_Path* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_Path_encode_internal(uavcan_protocol_file_Path* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_Path_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_Path* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_FILE_PATH

View File

@ -0,0 +1,119 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/48.Read.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_FILE_READ
#define __UAVCAN_PROTOCOL_FILE_READ
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
#include <uavcan/protocol/file/Error.h>
#include <uavcan/protocol/file/Path.h>
/******************************* Source text **********************************
#
# Read file from a remote node.
#
# There are two possible outcomes of a successful service call:
# 1. Data array size equals its capacity. This means that the end of the file is not reached yet.
# 2. Data array size is less than its capacity, possibly zero. This means that the end of file is reached.
#
# Thus, if the client needs to fetch the entire file, it should repeatedly call this service while increasing the
# offset, until incomplete data is returned.
#
# If the object pointed by 'path' cannot be read (e.g. it is a directory or it does not exist), appropriate error code
# will be returned, and data array will be empty.
#
uint40 offset
Path path
---
Error error
uint8[<=256] data
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.file.Read
saturated uint40 offset
uavcan.protocol.file.Path path
---
uavcan.protocol.file.Error error
saturated uint8[<=256] data
******************************************************************************/
#define UAVCAN_PROTOCOL_FILE_READ_ID 48
#define UAVCAN_PROTOCOL_FILE_READ_NAME "uavcan.protocol.file.Read"
#define UAVCAN_PROTOCOL_FILE_READ_SIGNATURE (0x8DCDCA939F33F678ULL)
#define UAVCAN_PROTOCOL_FILE_READ_REQUEST_MAX_SIZE ((1648 + 7)/8)
// Constants
typedef struct
{
// FieldTypes
uint64_t offset; // bit len 40
uavcan_protocol_file_Path path; //
} uavcan_protocol_file_ReadRequest;
extern
uint32_t uavcan_protocol_file_ReadRequest_encode(uavcan_protocol_file_ReadRequest* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_ReadRequest_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_ReadRequest* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_ReadRequest_encode_internal(uavcan_protocol_file_ReadRequest* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_ReadRequest_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_ReadRequest* dest, uint8_t** dyn_arr_buf, int32_t offset);
#define UAVCAN_PROTOCOL_FILE_READ_RESPONSE_MAX_SIZE ((2073 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_FILE_READ_RESPONSE_DATA_MAX_LENGTH 256
typedef struct
{
// FieldTypes
uavcan_protocol_file_Error error; //
struct
{
uint16_t len; // Dynamic array length
uint8_t* data; // Dynamic Array 8bit[256] max items
} data;
} uavcan_protocol_file_ReadResponse;
extern
uint32_t uavcan_protocol_file_ReadResponse_encode(uavcan_protocol_file_ReadResponse* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_ReadResponse_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_ReadResponse* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_ReadResponse_encode_internal(uavcan_protocol_file_ReadResponse* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_ReadResponse_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_ReadResponse* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_FILE_READ

View File

@ -0,0 +1,122 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/49.Write.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_FILE_WRITE
#define __UAVCAN_PROTOCOL_FILE_WRITE
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
#include <uavcan/protocol/file/Error.h>
#include <uavcan/protocol/file/Path.h>
/******************************* Source text **********************************
#
# Write into a remote file.
# The server shall place the contents of the field 'data' into the file pointed by 'path' at the offset specified by
# the field 'offset'.
#
# When writing a file, the client should repeatedly call this service with data while advancing offset until the file
# is written completely. When write is complete, the client shall call the service one last time, with the offset
# set to the size of the file and with the data field empty, which will signal the server that the write operation is
# complete.
#
# When the write operation is complete, the server shall truncate the resulting file past the specified offset.
#
# Server implementation advice:
# It is recommended to implement proper handling of concurrent writes to the same file from different clients, for
# example by means of creating a staging area for uncompleted writes (like FTP servers do).
#
uint40 offset
Path path
uint8[<=192] data
---
Error error
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.file.Write
saturated uint40 offset
uavcan.protocol.file.Path path
saturated uint8[<=192] data
---
uavcan.protocol.file.Error error
******************************************************************************/
#define UAVCAN_PROTOCOL_FILE_WRITE_ID 49
#define UAVCAN_PROTOCOL_FILE_WRITE_NAME "uavcan.protocol.file.Write"
#define UAVCAN_PROTOCOL_FILE_WRITE_SIGNATURE (0x515AA1DC77E58429ULL)
#define UAVCAN_PROTOCOL_FILE_WRITE_REQUEST_MAX_SIZE ((3192 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_FILE_WRITE_REQUEST_DATA_MAX_LENGTH 192
typedef struct
{
// FieldTypes
uint64_t offset; // bit len 40
uavcan_protocol_file_Path path; //
struct
{
uint8_t len; // Dynamic array length
uint8_t* data; // Dynamic Array 8bit[192] max items
} data;
} uavcan_protocol_file_WriteRequest;
extern
uint32_t uavcan_protocol_file_WriteRequest_encode(uavcan_protocol_file_WriteRequest* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_WriteRequest_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_WriteRequest* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_WriteRequest_encode_internal(uavcan_protocol_file_WriteRequest* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_WriteRequest_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_WriteRequest* dest, uint8_t** dyn_arr_buf, int32_t offset);
#define UAVCAN_PROTOCOL_FILE_WRITE_RESPONSE_MAX_SIZE ((16 + 7)/8)
// Constants
typedef struct
{
// FieldTypes
uavcan_protocol_file_Error error; //
} uavcan_protocol_file_WriteResponse;
extern
uint32_t uavcan_protocol_file_WriteResponse_encode(uavcan_protocol_file_WriteResponse* source, void* msg_buf);
extern
int32_t uavcan_protocol_file_WriteResponse_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_WriteResponse* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_file_WriteResponse_encode_internal(uavcan_protocol_file_WriteResponse* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_file_WriteResponse_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_file_WriteResponse* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_FILE_WRITE

View File

@ -0,0 +1,305 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/40.BeginFirmwareUpdate.uavcan
*/
#include "uavcan/protocol/file/BeginFirmwareUpdate.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_file_BeginFirmwareUpdateRequest_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_BeginFirmwareUpdateRequest_encode_internal(uavcan_protocol_file_BeginFirmwareUpdateRequest* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->source_node_id); // 255
offset += 8;
// Compound
offset = uavcan_protocol_file_Path_encode_internal(&source->image_file_remote_path, msg_buf, offset, 0);
return offset;
}
/**
* @brief uavcan_protocol_file_BeginFirmwareUpdateRequest_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_BeginFirmwareUpdateRequest_encode(uavcan_protocol_file_BeginFirmwareUpdateRequest* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_BeginFirmwareUpdateRequest_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_BeginFirmwareUpdateRequest_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_BeginFirmwareUpdateRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_BeginFirmwareUpdateRequest_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_BeginFirmwareUpdateRequest* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 8, false, (void*)&dest->source_node_id);
if (ret != 8)
{
goto uavcan_protocol_file_BeginFirmwareUpdateRequest_error_exit;
}
offset += 8;
// Compound
offset = uavcan_protocol_file_Path_decode_internal(transfer, payload_len, &dest->image_file_remote_path, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_BeginFirmwareUpdateRequest_error_exit;
}
return offset;
uavcan_protocol_file_BeginFirmwareUpdateRequest_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_BeginFirmwareUpdateRequest_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_BeginFirmwareUpdateRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_BeginFirmwareUpdateRequest* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_BeginFirmwareUpdateRequest); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_BeginFirmwareUpdateRequest_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}
/**
* @brief uavcan_protocol_file_BeginFirmwareUpdateResponse_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_BeginFirmwareUpdateResponse_encode_internal(uavcan_protocol_file_BeginFirmwareUpdateResponse* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
uint32_t c = 0;
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->error); // 255
offset += 8;
// Dynamic Array (optional_error_message)
if (! root_item)
{
// - Add array length
canardEncodeScalar(msg_buf, offset, 7, (void*)&source->optional_error_message.len);
offset += 7;
}
// - Add array items
for (c = 0; c < source->optional_error_message.len; c++)
{
canardEncodeScalar(msg_buf,
offset,
8,
(void*)(source->optional_error_message.data + c));// 255
offset += 8;
}
return offset;
}
/**
* @brief uavcan_protocol_file_BeginFirmwareUpdateResponse_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(uavcan_protocol_file_BeginFirmwareUpdateResponse* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_BeginFirmwareUpdateResponse_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_BeginFirmwareUpdateResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_BeginFirmwareUpdateResponse_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_BeginFirmwareUpdateResponse* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
uint32_t c = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 8, false, (void*)&dest->error);
if (ret != 8)
{
goto uavcan_protocol_file_BeginFirmwareUpdateResponse_error_exit;
}
offset += 8;
// Dynamic Array (optional_error_message)
// - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization
if (payload_len)
{
// - Calculate Array length from MSG length
dest->optional_error_message.len = ((payload_len * 8) - offset ) / 8; // 8 bit array item size
}
else
{
// - Array length 7 bits
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
7,
false,
(void*)&dest->optional_error_message.len); // 255
if (ret != 7)
{
goto uavcan_protocol_file_BeginFirmwareUpdateResponse_error_exit;
}
offset += 7;
}
// - Get Array
if (dyn_arr_buf)
{
dest->optional_error_message.data = (uint8_t*)*dyn_arr_buf;
}
for (c = 0; c < dest->optional_error_message.len; c++)
{
if (dyn_arr_buf)
{
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)*dyn_arr_buf); // 255
if (ret != 8)
{
goto uavcan_protocol_file_BeginFirmwareUpdateResponse_error_exit;
}
*dyn_arr_buf = (uint8_t*)(((uint8_t*)*dyn_arr_buf) + 1);
}
offset += 8;
}
return offset;
uavcan_protocol_file_BeginFirmwareUpdateResponse_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_BeginFirmwareUpdateResponse_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_BeginFirmwareUpdateResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_BeginFirmwareUpdateResponse_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_BeginFirmwareUpdateResponse* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_BeginFirmwareUpdateResponse); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_BeginFirmwareUpdateResponse_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,229 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/47.Delete.uavcan
*/
#include "uavcan/protocol/file/Delete.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_file_DeleteRequest_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_DeleteRequest_encode_internal(uavcan_protocol_file_DeleteRequest* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
// Compound
offset = uavcan_protocol_file_Path_encode_internal(&source->path, msg_buf, offset, 0);
return offset;
}
/**
* @brief uavcan_protocol_file_DeleteRequest_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_DeleteRequest_encode(uavcan_protocol_file_DeleteRequest* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_DeleteRequest_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_DeleteRequest_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_DeleteRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_DeleteRequest_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_DeleteRequest* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
// Compound
offset = uavcan_protocol_file_Path_decode_internal(transfer, payload_len, &dest->path, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_DeleteRequest_error_exit;
}
return offset;
uavcan_protocol_file_DeleteRequest_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_DeleteRequest_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_DeleteRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_DeleteRequest_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_DeleteRequest* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_DeleteRequest); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_DeleteRequest_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}
/**
* @brief uavcan_protocol_file_DeleteResponse_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_DeleteResponse_encode_internal(uavcan_protocol_file_DeleteResponse* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
// Compound
offset = uavcan_protocol_file_Error_encode_internal(&source->error, msg_buf, offset, 0);
return offset;
}
/**
* @brief uavcan_protocol_file_DeleteResponse_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_DeleteResponse_encode(uavcan_protocol_file_DeleteResponse* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_DeleteResponse_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_DeleteResponse_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_DeleteResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_DeleteResponse_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_DeleteResponse* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
// Compound
offset = uavcan_protocol_file_Error_decode_internal(transfer, payload_len, &dest->error, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_DeleteResponse_error_exit;
}
return offset;
uavcan_protocol_file_DeleteResponse_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_DeleteResponse_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_DeleteResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_DeleteResponse_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_DeleteResponse* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_DeleteResponse); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_DeleteResponse_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,125 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/EntryType.uavcan
*/
#include "uavcan/protocol/file/EntryType.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_file_EntryType_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_EntryType_encode_internal(uavcan_protocol_file_EntryType* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->flags); // 255
offset += 8;
return offset;
}
/**
* @brief uavcan_protocol_file_EntryType_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_EntryType_encode(uavcan_protocol_file_EntryType* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_EntryType_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_EntryType_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_EntryType dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_EntryType_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_EntryType* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 8, false, (void*)&dest->flags);
if (ret != 8)
{
goto uavcan_protocol_file_EntryType_error_exit;
}
offset += 8;
return offset;
uavcan_protocol_file_EntryType_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_EntryType_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_EntryType dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_EntryType_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_EntryType* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_EntryType); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_EntryType_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,125 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/Error.uavcan
*/
#include "uavcan/protocol/file/Error.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_file_Error_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_Error_encode_internal(uavcan_protocol_file_Error* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
canardEncodeScalar(msg_buf, offset, 16, (void*)&source->value); // 32767
offset += 16;
return offset;
}
/**
* @brief uavcan_protocol_file_Error_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_Error_encode(uavcan_protocol_file_Error* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_Error_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_Error_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_Error dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_Error_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_Error* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 16, true, (void*)&dest->value);
if (ret != 16)
{
goto uavcan_protocol_file_Error_error_exit;
}
offset += 16;
return offset;
uavcan_protocol_file_Error_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_Error_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_Error dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_Error_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_Error* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_Error); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_Error_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,261 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/46.GetDirectoryEntryInfo.uavcan
*/
#include "uavcan/protocol/file/GetDirectoryEntryInfo.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode_internal(uavcan_protocol_file_GetDirectoryEntryInfoRequest* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
canardEncodeScalar(msg_buf, offset, 32, (void*)&source->entry_index); // 4294967295
offset += 32;
// Compound
offset = uavcan_protocol_file_Path_encode_internal(&source->directory_path, msg_buf, offset, 0);
return offset;
}
/**
* @brief uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode(uavcan_protocol_file_GetDirectoryEntryInfoRequest* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_GetDirectoryEntryInfoRequest_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_GetDirectoryEntryInfoRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_GetDirectoryEntryInfoRequest* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 32, false, (void*)&dest->entry_index);
if (ret != 32)
{
goto uavcan_protocol_file_GetDirectoryEntryInfoRequest_error_exit;
}
offset += 32;
// Compound
offset = uavcan_protocol_file_Path_decode_internal(transfer, payload_len, &dest->directory_path, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_GetDirectoryEntryInfoRequest_error_exit;
}
return offset;
uavcan_protocol_file_GetDirectoryEntryInfoRequest_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_GetDirectoryEntryInfoRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_GetDirectoryEntryInfoRequest* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_GetDirectoryEntryInfoRequest); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_GetDirectoryEntryInfoRequest_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}
/**
* @brief uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode_internal(uavcan_protocol_file_GetDirectoryEntryInfoResponse* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
// Compound
offset = uavcan_protocol_file_Error_encode_internal(&source->error, msg_buf, offset, 0);
// Compound
offset = uavcan_protocol_file_EntryType_encode_internal(&source->entry_type, msg_buf, offset, 0);
// Compound
offset = uavcan_protocol_file_Path_encode_internal(&source->entry_full_path, msg_buf, offset, 0);
return offset;
}
/**
* @brief uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode(uavcan_protocol_file_GetDirectoryEntryInfoResponse* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_GetDirectoryEntryInfoResponse_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_GetDirectoryEntryInfoResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_GetDirectoryEntryInfoResponse* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
// Compound
offset = uavcan_protocol_file_Error_decode_internal(transfer, payload_len, &dest->error, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_GetDirectoryEntryInfoResponse_error_exit;
}
// Compound
offset = uavcan_protocol_file_EntryType_decode_internal(transfer, payload_len, &dest->entry_type, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_GetDirectoryEntryInfoResponse_error_exit;
}
// Compound
offset = uavcan_protocol_file_Path_decode_internal(transfer, payload_len, &dest->entry_full_path, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_GetDirectoryEntryInfoResponse_error_exit;
}
return offset;
uavcan_protocol_file_GetDirectoryEntryInfoResponse_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_GetDirectoryEntryInfoResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_GetDirectoryEntryInfoResponse* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_GetDirectoryEntryInfoResponse); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_GetDirectoryEntryInfoResponse_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,251 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/45.GetInfo.uavcan
*/
#include "uavcan/protocol/file/GetInfo.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_file_GetInfoRequest_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_GetInfoRequest_encode_internal(uavcan_protocol_file_GetInfoRequest* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
// Compound
offset = uavcan_protocol_file_Path_encode_internal(&source->path, msg_buf, offset, 0);
return offset;
}
/**
* @brief uavcan_protocol_file_GetInfoRequest_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_GetInfoRequest_encode(uavcan_protocol_file_GetInfoRequest* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_GetInfoRequest_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_GetInfoRequest_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_GetInfoRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_GetInfoRequest_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_GetInfoRequest* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
// Compound
offset = uavcan_protocol_file_Path_decode_internal(transfer, payload_len, &dest->path, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_GetInfoRequest_error_exit;
}
return offset;
uavcan_protocol_file_GetInfoRequest_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_GetInfoRequest_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_GetInfoRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_GetInfoRequest_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_GetInfoRequest* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_GetInfoRequest); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_GetInfoRequest_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}
/**
* @brief uavcan_protocol_file_GetInfoResponse_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_GetInfoResponse_encode_internal(uavcan_protocol_file_GetInfoResponse* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
source->size = CANARD_INTERNAL_SATURATE_UNSIGNED(source->size, 1099511627775)
canardEncodeScalar(msg_buf, offset, 40, (void*)&source->size); // 1099511627775
offset += 40;
// Compound
offset = uavcan_protocol_file_Error_encode_internal(&source->error, msg_buf, offset, 0);
// Compound
offset = uavcan_protocol_file_EntryType_encode_internal(&source->entry_type, msg_buf, offset, 0);
return offset;
}
/**
* @brief uavcan_protocol_file_GetInfoResponse_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_GetInfoResponse_encode(uavcan_protocol_file_GetInfoResponse* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_GetInfoResponse_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_GetInfoResponse_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_GetInfoResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_GetInfoResponse_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_GetInfoResponse* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 40, false, (void*)&dest->size);
if (ret != 40)
{
goto uavcan_protocol_file_GetInfoResponse_error_exit;
}
offset += 40;
// Compound
offset = uavcan_protocol_file_Error_decode_internal(transfer, payload_len, &dest->error, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_GetInfoResponse_error_exit;
}
// Compound
offset = uavcan_protocol_file_EntryType_decode_internal(transfer, payload_len, &dest->entry_type, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_GetInfoResponse_error_exit;
}
return offset;
uavcan_protocol_file_GetInfoResponse_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_GetInfoResponse_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_GetInfoResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_GetInfoResponse_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_GetInfoResponse* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_GetInfoResponse); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_GetInfoResponse_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,182 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/Path.uavcan
*/
#include "uavcan/protocol/file/Path.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_file_Path_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_Path_encode_internal(uavcan_protocol_file_Path* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
uint32_t c = 0;
// Dynamic Array (path)
if (! root_item)
{
// - Add array length
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->path.len);
offset += 8;
}
// - Add array items
for (c = 0; c < source->path.len; c++)
{
canardEncodeScalar(msg_buf,
offset,
8,
(void*)(source->path.data + c));// 255
offset += 8;
}
return offset;
}
/**
* @brief uavcan_protocol_file_Path_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_Path_encode(uavcan_protocol_file_Path* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_Path_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_Path_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_Path dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_Path_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_Path* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
uint32_t c = 0;
// Dynamic Array (path)
// - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization
if (payload_len)
{
// - Calculate Array length from MSG length
dest->path.len = ((payload_len * 8) - offset ) / 8; // 8 bit array item size
}
else
{
// - Array length 8 bits
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)&dest->path.len); // 255
if (ret != 8)
{
goto uavcan_protocol_file_Path_error_exit;
}
offset += 8;
}
// - Get Array
if (dyn_arr_buf)
{
dest->path.data = (uint8_t*)*dyn_arr_buf;
}
for (c = 0; c < dest->path.len; c++)
{
if (dyn_arr_buf)
{
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)*dyn_arr_buf); // 255
if (ret != 8)
{
goto uavcan_protocol_file_Path_error_exit;
}
*dyn_arr_buf = (uint8_t*)(((uint8_t*)*dyn_arr_buf) + 1);
}
offset += 8;
}
return offset;
uavcan_protocol_file_Path_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_Path_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_Path dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_Path_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_Path* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_Path); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_Path_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,307 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/48.Read.uavcan
*/
#include "uavcan/protocol/file/Read.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_file_ReadRequest_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_ReadRequest_encode_internal(uavcan_protocol_file_ReadRequest* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
source->offset = CANARD_INTERNAL_SATURATE_UNSIGNED(source->offset, 1099511627775)
canardEncodeScalar(msg_buf, offset, 40, (void*)&source->offset); // 1099511627775
offset += 40;
// Compound
offset = uavcan_protocol_file_Path_encode_internal(&source->path, msg_buf, offset, 0);
return offset;
}
/**
* @brief uavcan_protocol_file_ReadRequest_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_ReadRequest_encode(uavcan_protocol_file_ReadRequest* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_ReadRequest_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_ReadRequest_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_ReadRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_ReadRequest_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_ReadRequest* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 40, false, (void*)&dest->offset);
if (ret != 40)
{
goto uavcan_protocol_file_ReadRequest_error_exit;
}
offset += 40;
// Compound
offset = uavcan_protocol_file_Path_decode_internal(transfer, payload_len, &dest->path, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_ReadRequest_error_exit;
}
return offset;
uavcan_protocol_file_ReadRequest_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_ReadRequest_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_ReadRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_ReadRequest_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_ReadRequest* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_ReadRequest); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_ReadRequest_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}
/**
* @brief uavcan_protocol_file_ReadResponse_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_ReadResponse_encode_internal(uavcan_protocol_file_ReadResponse* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
uint32_t c = 0;
// Compound
offset = uavcan_protocol_file_Error_encode_internal(&source->error, msg_buf, offset, 0);
// Dynamic Array (data)
if (! root_item)
{
// - Add array length
canardEncodeScalar(msg_buf, offset, 9, (void*)&source->data.len);
offset += 9;
}
// - Add array items
for (c = 0; c < source->data.len; c++)
{
canardEncodeScalar(msg_buf,
offset,
8,
(void*)(source->data.data + c));// 255
offset += 8;
}
return offset;
}
/**
* @brief uavcan_protocol_file_ReadResponse_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_ReadResponse_encode(uavcan_protocol_file_ReadResponse* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_ReadResponse_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_ReadResponse_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_ReadResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_ReadResponse_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_ReadResponse* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
uint32_t c = 0;
// Compound
offset = uavcan_protocol_file_Error_decode_internal(transfer, payload_len, &dest->error, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_ReadResponse_error_exit;
}
// Dynamic Array (data)
// - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization
if (payload_len)
{
// - Calculate Array length from MSG length
dest->data.len = ((payload_len * 8) - offset ) / 8; // 8 bit array item size
}
else
{
// - Array length 9 bits
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
9,
false,
(void*)&dest->data.len); // 255
if (ret != 9)
{
goto uavcan_protocol_file_ReadResponse_error_exit;
}
offset += 9;
}
// - Get Array
if (dyn_arr_buf)
{
dest->data.data = (uint8_t*)*dyn_arr_buf;
}
for (c = 0; c < dest->data.len; c++)
{
if (dyn_arr_buf)
{
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)*dyn_arr_buf); // 255
if (ret != 8)
{
goto uavcan_protocol_file_ReadResponse_error_exit;
}
*dyn_arr_buf = (uint8_t*)(((uint8_t*)*dyn_arr_buf) + 1);
}
offset += 8;
}
return offset;
uavcan_protocol_file_ReadResponse_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_ReadResponse_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_ReadResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_ReadResponse_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_ReadResponse* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_ReadResponse); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_ReadResponse_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,307 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/file/49.Write.uavcan
*/
#include "uavcan/protocol/file/Write.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_file_WriteRequest_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_WriteRequest_encode_internal(uavcan_protocol_file_WriteRequest* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
uint32_t c = 0;
source->offset = CANARD_INTERNAL_SATURATE_UNSIGNED(source->offset, 1099511627775)
canardEncodeScalar(msg_buf, offset, 40, (void*)&source->offset); // 1099511627775
offset += 40;
// Compound
offset = uavcan_protocol_file_Path_encode_internal(&source->path, msg_buf, offset, 0);
// Dynamic Array (data)
if (! root_item)
{
// - Add array length
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->data.len);
offset += 8;
}
// - Add array items
for (c = 0; c < source->data.len; c++)
{
canardEncodeScalar(msg_buf,
offset,
8,
(void*)(source->data.data + c));// 255
offset += 8;
}
return offset;
}
/**
* @brief uavcan_protocol_file_WriteRequest_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_WriteRequest_encode(uavcan_protocol_file_WriteRequest* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_WriteRequest_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_WriteRequest_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_WriteRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_WriteRequest_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_WriteRequest* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
uint32_t c = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 40, false, (void*)&dest->offset);
if (ret != 40)
{
goto uavcan_protocol_file_WriteRequest_error_exit;
}
offset += 40;
// Compound
offset = uavcan_protocol_file_Path_decode_internal(transfer, payload_len, &dest->path, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_WriteRequest_error_exit;
}
// Dynamic Array (data)
// - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization
if (payload_len)
{
// - Calculate Array length from MSG length
dest->data.len = ((payload_len * 8) - offset ) / 8; // 8 bit array item size
}
else
{
// - Array length 8 bits
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)&dest->data.len); // 255
if (ret != 8)
{
goto uavcan_protocol_file_WriteRequest_error_exit;
}
offset += 8;
}
// - Get Array
if (dyn_arr_buf)
{
dest->data.data = (uint8_t*)*dyn_arr_buf;
}
for (c = 0; c < dest->data.len; c++)
{
if (dyn_arr_buf)
{
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)*dyn_arr_buf); // 255
if (ret != 8)
{
goto uavcan_protocol_file_WriteRequest_error_exit;
}
*dyn_arr_buf = (uint8_t*)(((uint8_t*)*dyn_arr_buf) + 1);
}
offset += 8;
}
return offset;
uavcan_protocol_file_WriteRequest_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_WriteRequest_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_WriteRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_WriteRequest_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_WriteRequest* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_WriteRequest); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_WriteRequest_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}
/**
* @brief uavcan_protocol_file_WriteResponse_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_file_WriteResponse_encode_internal(uavcan_protocol_file_WriteResponse* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
// Compound
offset = uavcan_protocol_file_Error_encode_internal(&source->error, msg_buf, offset, 0);
return offset;
}
/**
* @brief uavcan_protocol_file_WriteResponse_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_file_WriteResponse_encode(uavcan_protocol_file_WriteResponse* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_file_WriteResponse_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_file_WriteResponse_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_WriteResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_WriteResponse_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_file_WriteResponse* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
// Compound
offset = uavcan_protocol_file_Error_decode_internal(transfer, payload_len, &dest->error, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_file_WriteResponse_error_exit;
}
return offset;
uavcan_protocol_file_WriteResponse_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_file_WriteResponse_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_file_WriteResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_file_WriteResponse_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_file_WriteResponse* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_file_WriteResponse); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_file_WriteResponse_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,55 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/param/Empty.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_PARAM_EMPTY
#define __UAVCAN_PROTOCOL_PARAM_EMPTY
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
/******************************* Source text **********************************
#
# Ex nihilo nihil fit.
#
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.param.Empty
******************************************************************************/
#define UAVCAN_PROTOCOL_PARAM_EMPTY_NAME "uavcan.protocol.param.Empty"
#define UAVCAN_PROTOCOL_PARAM_EMPTY_SIGNATURE (0x6C4D0E8EF37361DFULL)
#define UAVCAN_PROTOCOL_PARAM_EMPTY_MAX_SIZE ((0 + 7)/8)
typedef struct
{
uint8_t empty;
} uavcan_protocol_param_Empty;
extern
uint32_t uavcan_protocol_param_Empty_encode(uavcan_protocol_param_Empty* source, void* msg_buf);
extern
int32_t uavcan_protocol_param_Empty_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_Empty* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_param_Empty_encode_internal(uavcan_protocol_param_Empty* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_param_Empty_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_Empty* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_PARAM_EMPTY

View File

@ -0,0 +1,123 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/param/10.ExecuteOpcode.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE
#define __UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
/******************************* Source text **********************************
#
# Service to control the node configuration.
#
#
# SAVE operation instructs the remote node to save the current configuration parameters into a non-volatile
# storage. The node may require a restart in order for some changes to take effect.
#
# ERASE operation instructs the remote node to clear its configuration storage and reinitialize the parameters
# with their default values. The node may require a restart in order for some changes to take effect.
#
# Other opcodes may be added in the future (for example, an opcode for switching between multiple configurations).
#
uint8 OPCODE_SAVE = 0 # Save all parameters to non-volatile storage.
uint8 OPCODE_ERASE = 1 # Clear the non-volatile storage; some changes may take effect only after reboot.
uint8 opcode
#
# Reserved, keep zero.
#
int48 argument
---
#
# If 'ok' (the field below) is true, this value is not used and must be kept zero.
# If 'ok' is false, this value may contain error code. Error code constants may be defined in the future.
#
int48 argument
#
# True if the operation has been performed successfully, false otherwise.
#
bool ok
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.param.ExecuteOpcode
saturated uint8 opcode
saturated int48 argument
---
saturated int48 argument
saturated bool ok
******************************************************************************/
#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID 10
#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_NAME "uavcan.protocol.param.ExecuteOpcode"
#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE (0x3B131AC5EB69D2CDULL)
#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_MAX_SIZE ((56 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_SAVE 0 // 0
#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_ERASE 1 // 1
typedef struct
{
// FieldTypes
uint8_t opcode; // bit len 8
int64_t argument; // bit len 48
} uavcan_protocol_param_ExecuteOpcodeRequest;
extern
uint32_t uavcan_protocol_param_ExecuteOpcodeRequest_encode(uavcan_protocol_param_ExecuteOpcodeRequest* source, void* msg_buf);
extern
int32_t uavcan_protocol_param_ExecuteOpcodeRequest_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_ExecuteOpcodeRequest* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_param_ExecuteOpcodeRequest_encode_internal(uavcan_protocol_param_ExecuteOpcodeRequest* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_param_ExecuteOpcodeRequest_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_ExecuteOpcodeRequest* dest, uint8_t** dyn_arr_buf, int32_t offset);
#define UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE ((49 + 7)/8)
// Constants
typedef struct
{
// FieldTypes
int64_t argument; // bit len 48
bool ok; // bit len 1
} uavcan_protocol_param_ExecuteOpcodeResponse;
extern
uint32_t uavcan_protocol_param_ExecuteOpcodeResponse_encode(uavcan_protocol_param_ExecuteOpcodeResponse* source, void* msg_buf);
extern
int32_t uavcan_protocol_param_ExecuteOpcodeResponse_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_ExecuteOpcodeResponse* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_param_ExecuteOpcodeResponse_encode_internal(uavcan_protocol_param_ExecuteOpcodeResponse* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_param_ExecuteOpcodeResponse_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_ExecuteOpcodeResponse* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE

View File

@ -0,0 +1,172 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/param/11.GetSet.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_PARAM_GETSET
#define __UAVCAN_PROTOCOL_PARAM_GETSET
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
#include <uavcan/protocol/param/NumericValue.h>
#include <uavcan/protocol/param/Value.h>
/******************************* Source text **********************************
#
# Get or set a parameter by name or by index.
# Note that access by index should only be used to retrieve the list of parameters; it is highly
# discouraged to use it for anything else, because persistent ordering is not guaranteed.
#
#
# Index of the parameter starting from 0; ignored if name is nonempty.
# Use index only to retrieve the list of parameters.
# Parameter ordering must be well defined (e.g. alphabetical, or any other stable ordering),
# in order for the index access to work.
#
uint13 index
#
# If set - parameter will be assigned this value, then the new value will be returned.
# If not set - current parameter value will be returned.
# Refer to the definition of Value for details.
#
Value value
#
# Name of the parameter; always preferred over index if nonempty.
#
uint8[<=92] name
---
void5
#
# Actual parameter value.
#
# For set requests, it should contain the actual parameter value after the set request was
# executed. The objective is to let the client know if the value could not be updated, e.g.
# due to its range violation, etc.
#
# Empty value (and/or empty name) indicates that there is no such parameter.
#
Value value
void5
Value default_value # Optional
void6
NumericValue max_value # Optional, not applicable for bool/string
void6
NumericValue min_value # Optional, not applicable for bool/string
#
# Empty name (and/or empty value) in response indicates that there is no such parameter.
#
uint8[<=92] name
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.param.GetSet
saturated uint13 index
uavcan.protocol.param.Value value
saturated uint8[<=92] name
---
void5
uavcan.protocol.param.Value value
void5
uavcan.protocol.param.Value default_value
void6
uavcan.protocol.param.NumericValue max_value
void6
uavcan.protocol.param.NumericValue min_value
saturated uint8[<=92] name
******************************************************************************/
#define UAVCAN_PROTOCOL_PARAM_GETSET_ID 11
#define UAVCAN_PROTOCOL_PARAM_GETSET_NAME "uavcan.protocol.param.GetSet"
#define UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE (0xA7B622F939D1A4D5ULL)
#define UAVCAN_PROTOCOL_PARAM_GETSET_REQUEST_MAX_SIZE ((1791 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_PARAM_GETSET_REQUEST_NAME_MAX_LENGTH 92
typedef struct
{
// FieldTypes
uint16_t index; // bit len 13
uavcan_protocol_param_Value value; //
struct
{
uint8_t len; // Dynamic array length
uint8_t* data; // Dynamic Array 8bit[92] max items
} name;
} uavcan_protocol_param_GetSetRequest;
extern
uint32_t uavcan_protocol_param_GetSetRequest_encode(uavcan_protocol_param_GetSetRequest* source, void* msg_buf);
extern
int32_t uavcan_protocol_param_GetSetRequest_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_GetSetRequest* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_param_GetSetRequest_encode_internal(uavcan_protocol_param_GetSetRequest* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_param_GetSetRequest_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_GetSetRequest* dest, uint8_t** dyn_arr_buf, int32_t offset);
#define UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE ((2967 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_NAME_MAX_LENGTH 92
typedef struct
{
// FieldTypes
// void5
uavcan_protocol_param_Value value; //
// void5
uavcan_protocol_param_Value default_value; //
// void6
uavcan_protocol_param_NumericValue max_value; //
// void6
uavcan_protocol_param_NumericValue min_value; //
struct
{
uint8_t len; // Dynamic array length
uint8_t* data; // Dynamic Array 8bit[92] max items
} name;
} uavcan_protocol_param_GetSetResponse;
extern
uint32_t uavcan_protocol_param_GetSetResponse_encode(uavcan_protocol_param_GetSetResponse* source, void* msg_buf);
extern
int32_t uavcan_protocol_param_GetSetResponse_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_GetSetResponse* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_param_GetSetResponse_encode_internal(uavcan_protocol_param_GetSetResponse* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_param_GetSetResponse_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_GetSetResponse* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_PARAM_GETSET

View File

@ -0,0 +1,89 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/param/NumericValue.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_PARAM_NUMERICVALUE
#define __UAVCAN_PROTOCOL_PARAM_NUMERICVALUE
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
#include <uavcan/protocol/param/Empty.h>
/******************************* Source text **********************************
#
# Numeric-only value.
#
# This is a union, which means that this structure can contain either one of the fields below.
# The structure is prefixed with tag - a selector value that indicates which particular field is encoded.
#
@union # Tag is 2 bits long.
Empty empty # Empty field, used to represent an undefined value.
int64 integer_value
float32 real_value
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.param.NumericValue
@union
uavcan.protocol.param.Empty empty
saturated int64 integer_value
saturated float32 real_value
******************************************************************************/
#define UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_NAME "uavcan.protocol.param.NumericValue"
#define UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_SIGNATURE (0xDA6D6FEA22E3587ULL)
#define UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_MAX_SIZE ((66 + 7)/8)
// Constants
typedef enum
{
UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_EMPTY,
UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE,
UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_REAL_VALUE
} uavcan_protocol_param_NumericValue_ENUM;
typedef struct
{
uavcan_protocol_param_NumericValue_ENUM union_tag; // union_tag indicates what field the data structure is holding
union
{
// FieldTypes
uavcan_protocol_param_Empty empty; //
int64_t integer_value; // bit len 64
float real_value; // float32 Saturate
};
} uavcan_protocol_param_NumericValue;
extern
uint32_t uavcan_protocol_param_NumericValue_encode(uavcan_protocol_param_NumericValue* source, void* msg_buf);
extern
int32_t uavcan_protocol_param_NumericValue_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_NumericValue* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_param_NumericValue_encode_internal(uavcan_protocol_param_NumericValue* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_param_NumericValue_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_NumericValue* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_PARAM_NUMERICVALUE

View File

@ -0,0 +1,103 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/param/Value.uavcan
*/
#ifndef __UAVCAN_PROTOCOL_PARAM_VALUE
#define __UAVCAN_PROTOCOL_PARAM_VALUE
#include <stdint.h>
#include "canard.h"
#ifdef __cplusplus
extern "C"
{
#endif
#include <uavcan/protocol/param/Empty.h>
/******************************* Source text **********************************
#
# Single parameter value.
#
# This is a union, which means that this structure can contain either one of the fields below.
# The structure is prefixed with tag - a selector value that indicates which particular field is encoded.
#
@union # Tag is 3 bit long, so outer structure has 5-bit prefix to ensure proper alignment
Empty empty # Empty field, used to represent an undefined value.
int64 integer_value
float32 real_value # 32-bit type is used to simplify implementation on low-end systems
uint8 boolean_value # 8-bit value is used for alignment reasons
uint8[<=128] string_value # Length prefix is exactly one byte long, which ensures proper alignment of payload
******************************************************************************/
/********************* DSDL signature source definition ***********************
uavcan.protocol.param.Value
@union
uavcan.protocol.param.Empty empty
saturated int64 integer_value
saturated float32 real_value
saturated uint8 boolean_value
saturated uint8[<=128] string_value
******************************************************************************/
#define UAVCAN_PROTOCOL_PARAM_VALUE_NAME "uavcan.protocol.param.Value"
#define UAVCAN_PROTOCOL_PARAM_VALUE_SIGNATURE (0x29F14BF484727267ULL)
#define UAVCAN_PROTOCOL_PARAM_VALUE_MAX_SIZE ((1035 + 7)/8)
// Constants
#define UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE_MAX_LENGTH 128
typedef enum
{
UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY,
UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE,
UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE,
UAVCAN_PROTOCOL_PARAM_VALUE_BOOLEAN_VALUE,
UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE
} uavcan_protocol_param_Value_ENUM;
typedef struct
{
uavcan_protocol_param_Value_ENUM union_tag; // union_tag indicates what field the data structure is holding
union
{
// FieldTypes
uavcan_protocol_param_Empty empty; //
int64_t integer_value; // bit len 64
float real_value; // float32 Saturate
uint8_t boolean_value; // bit len 8
struct
{
uint8_t len; // Dynamic array length
uint8_t* data; // Dynamic Array 8bit[128] max items
} string_value;
};
} uavcan_protocol_param_Value;
extern
uint32_t uavcan_protocol_param_Value_encode(uavcan_protocol_param_Value* source, void* msg_buf);
extern
int32_t uavcan_protocol_param_Value_decode(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_Value* dest, uint8_t** dyn_arr_buf);
extern
uint32_t uavcan_protocol_param_Value_encode_internal(uavcan_protocol_param_Value* source, void* msg_buf, uint32_t offset, uint8_t root_item);
extern
int32_t uavcan_protocol_param_Value_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, uavcan_protocol_param_Value* dest, uint8_t** dyn_arr_buf, int32_t offset);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __UAVCAN_PROTOCOL_PARAM_VALUE

View File

@ -0,0 +1,53 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/param/Empty.uavcan
*/
#include "uavcan/protocol/param/Empty.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
uint32_t uavcan_protocol_param_Empty_encode_internal(uavcan_protocol_param_Empty* CANARD_MAYBE_UNUSED(source),
void* CANARD_MAYBE_UNUSED(msg_buf),
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
return offset;
}
uint32_t uavcan_protocol_param_Empty_encode(uavcan_protocol_param_Empty* CANARD_MAYBE_UNUSED(source), void* CANARD_MAYBE_UNUSED(msg_buf))
{
return 0;
}
int32_t uavcan_protocol_param_Empty_decode_internal(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer),
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_param_Empty* CANARD_MAYBE_UNUSED(dest),
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
return offset;
}
int32_t uavcan_protocol_param_Empty_decode(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer),
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_param_Empty* CANARD_MAYBE_UNUSED(dest),
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf))
{
return 0;
}

View File

@ -0,0 +1,250 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/param/10.ExecuteOpcode.uavcan
*/
#include "uavcan/protocol/param/ExecuteOpcode.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_param_ExecuteOpcodeRequest_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_param_ExecuteOpcodeRequest_encode_internal(uavcan_protocol_param_ExecuteOpcodeRequest* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->opcode); // 255
offset += 8;
source->argument = CANARD_INTERNAL_SATURATE(source->argument, 140737488355327)
canardEncodeScalar(msg_buf, offset, 48, (void*)&source->argument); // 140737488355327
offset += 48;
return offset;
}
/**
* @brief uavcan_protocol_param_ExecuteOpcodeRequest_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_param_ExecuteOpcodeRequest_encode(uavcan_protocol_param_ExecuteOpcodeRequest* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_param_ExecuteOpcodeRequest_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_param_ExecuteOpcodeRequest_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_ExecuteOpcodeRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_ExecuteOpcodeRequest_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_param_ExecuteOpcodeRequest* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 8, false, (void*)&dest->opcode);
if (ret != 8)
{
goto uavcan_protocol_param_ExecuteOpcodeRequest_error_exit;
}
offset += 8;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 48, true, (void*)&dest->argument);
if (ret != 48)
{
goto uavcan_protocol_param_ExecuteOpcodeRequest_error_exit;
}
offset += 48;
return offset;
uavcan_protocol_param_ExecuteOpcodeRequest_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_param_ExecuteOpcodeRequest_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_ExecuteOpcodeRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_ExecuteOpcodeRequest_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_param_ExecuteOpcodeRequest* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_param_ExecuteOpcodeRequest); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_param_ExecuteOpcodeRequest_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}
/**
* @brief uavcan_protocol_param_ExecuteOpcodeResponse_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_param_ExecuteOpcodeResponse_encode_internal(uavcan_protocol_param_ExecuteOpcodeResponse* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
source->argument = CANARD_INTERNAL_SATURATE(source->argument, 140737488355327)
canardEncodeScalar(msg_buf, offset, 48, (void*)&source->argument); // 140737488355327
offset += 48;
source->ok = CANARD_INTERNAL_SATURATE_UNSIGNED(source->ok, 1)
canardEncodeScalar(msg_buf, offset, 1, (void*)&source->ok); // 1
offset += 1;
return offset;
}
/**
* @brief uavcan_protocol_param_ExecuteOpcodeResponse_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_param_ExecuteOpcodeResponse_encode(uavcan_protocol_param_ExecuteOpcodeResponse* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_param_ExecuteOpcodeResponse_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_param_ExecuteOpcodeResponse_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_ExecuteOpcodeResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_ExecuteOpcodeResponse_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_param_ExecuteOpcodeResponse* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 48, true, (void*)&dest->argument);
if (ret != 48)
{
goto uavcan_protocol_param_ExecuteOpcodeResponse_error_exit;
}
offset += 48;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 1, false, (void*)&dest->ok);
if (ret != 1)
{
goto uavcan_protocol_param_ExecuteOpcodeResponse_error_exit;
}
offset += 1;
return offset;
uavcan_protocol_param_ExecuteOpcodeResponse_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_param_ExecuteOpcodeResponse_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_ExecuteOpcodeResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_ExecuteOpcodeResponse_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_param_ExecuteOpcodeResponse* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_param_ExecuteOpcodeResponse); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_param_ExecuteOpcodeResponse_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,431 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/param/11.GetSet.uavcan
*/
#include "uavcan/protocol/param/GetSet.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_param_GetSetRequest_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_param_GetSetRequest_encode_internal(uavcan_protocol_param_GetSetRequest* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
uint32_t c = 0;
source->index = CANARD_INTERNAL_SATURATE_UNSIGNED(source->index, 8191)
canardEncodeScalar(msg_buf, offset, 13, (void*)&source->index); // 8191
offset += 13;
// Compound
offset = uavcan_protocol_param_Value_encode_internal(&source->value, msg_buf, offset, 0);
// Dynamic Array (name)
if (! root_item)
{
// - Add array length
canardEncodeScalar(msg_buf, offset, 7, (void*)&source->name.len);
offset += 7;
}
// - Add array items
for (c = 0; c < source->name.len; c++)
{
canardEncodeScalar(msg_buf,
offset,
8,
(void*)(source->name.data + c));// 255
offset += 8;
}
return offset;
}
/**
* @brief uavcan_protocol_param_GetSetRequest_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_param_GetSetRequest_encode(uavcan_protocol_param_GetSetRequest* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_param_GetSetRequest_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_param_GetSetRequest_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_GetSetRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_GetSetRequest_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_param_GetSetRequest* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
uint32_t c = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 13, false, (void*)&dest->index);
if (ret != 13)
{
goto uavcan_protocol_param_GetSetRequest_error_exit;
}
offset += 13;
// Compound
offset = uavcan_protocol_param_Value_decode_internal(transfer, payload_len, &dest->value, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_param_GetSetRequest_error_exit;
}
// Dynamic Array (name)
// - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization
if (payload_len)
{
// - Calculate Array length from MSG length
dest->name.len = ((payload_len * 8) - offset ) / 8; // 8 bit array item size
}
else
{
// - Array length 7 bits
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
7,
false,
(void*)&dest->name.len); // 255
if (ret != 7)
{
goto uavcan_protocol_param_GetSetRequest_error_exit;
}
offset += 7;
}
// - Get Array
if (dyn_arr_buf)
{
dest->name.data = (uint8_t*)*dyn_arr_buf;
}
for (c = 0; c < dest->name.len; c++)
{
if (dyn_arr_buf)
{
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)*dyn_arr_buf); // 255
if (ret != 8)
{
goto uavcan_protocol_param_GetSetRequest_error_exit;
}
*dyn_arr_buf = (uint8_t*)(((uint8_t*)*dyn_arr_buf) + 1);
}
offset += 8;
}
return offset;
uavcan_protocol_param_GetSetRequest_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_param_GetSetRequest_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_GetSetRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_GetSetRequest_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_param_GetSetRequest* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_param_GetSetRequest); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_param_GetSetRequest_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}
/**
* @brief uavcan_protocol_param_GetSetResponse_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_param_GetSetResponse_encode_internal(uavcan_protocol_param_GetSetResponse* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
uint32_t c = 0;
// Void5
offset += 5;
// Compound
offset = uavcan_protocol_param_Value_encode_internal(&source->value, msg_buf, offset, 0);
// Void5
offset += 5;
// Compound
offset = uavcan_protocol_param_Value_encode_internal(&source->default_value, msg_buf, offset, 0);
// Void6
offset += 6;
// Compound
offset = uavcan_protocol_param_NumericValue_encode_internal(&source->max_value, msg_buf, offset, 0);
// Void6
offset += 6;
// Compound
offset = uavcan_protocol_param_NumericValue_encode_internal(&source->min_value, msg_buf, offset, 0);
// Dynamic Array (name)
if (! root_item)
{
// - Add array length
canardEncodeScalar(msg_buf, offset, 7, (void*)&source->name.len);
offset += 7;
}
// - Add array items
for (c = 0; c < source->name.len; c++)
{
canardEncodeScalar(msg_buf,
offset,
8,
(void*)(source->name.data + c));// 255
offset += 8;
}
return offset;
}
/**
* @brief uavcan_protocol_param_GetSetResponse_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_param_GetSetResponse_encode(uavcan_protocol_param_GetSetResponse* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_param_GetSetResponse_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_param_GetSetResponse_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_GetSetResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_GetSetResponse_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_param_GetSetResponse* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
uint32_t c = 0;
// Void5
offset += 5;
// Compound
offset = uavcan_protocol_param_Value_decode_internal(transfer, payload_len, &dest->value, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_param_GetSetResponse_error_exit;
}
// Void5
offset += 5;
// Compound
offset = uavcan_protocol_param_Value_decode_internal(transfer, payload_len, &dest->default_value, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_param_GetSetResponse_error_exit;
}
// Void6
offset += 6;
// Compound
offset = uavcan_protocol_param_NumericValue_decode_internal(transfer, payload_len, &dest->max_value, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_param_GetSetResponse_error_exit;
}
// Void6
offset += 6;
// Compound
offset = uavcan_protocol_param_NumericValue_decode_internal(transfer, payload_len, &dest->min_value, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_param_GetSetResponse_error_exit;
}
// Dynamic Array (name)
// - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization
if (payload_len)
{
// - Calculate Array length from MSG length
dest->name.len = ((payload_len * 8) - offset ) / 8; // 8 bit array item size
}
else
{
// - Array length 7 bits
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
7,
false,
(void*)&dest->name.len); // 255
if (ret != 7)
{
goto uavcan_protocol_param_GetSetResponse_error_exit;
}
offset += 7;
}
// - Get Array
if (dyn_arr_buf)
{
dest->name.data = (uint8_t*)*dyn_arr_buf;
}
for (c = 0; c < dest->name.len; c++)
{
if (dyn_arr_buf)
{
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)*dyn_arr_buf); // 255
if (ret != 8)
{
goto uavcan_protocol_param_GetSetResponse_error_exit;
}
*dyn_arr_buf = (uint8_t*)(((uint8_t*)*dyn_arr_buf) + 1);
}
offset += 8;
}
return offset;
uavcan_protocol_param_GetSetResponse_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_param_GetSetResponse_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_GetSetResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_GetSetResponse_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_param_GetSetResponse* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_param_GetSetResponse); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_param_GetSetResponse_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,174 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/param/NumericValue.uavcan
*/
#include "uavcan/protocol/param/NumericValue.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_param_NumericValue_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_param_NumericValue_encode_internal(uavcan_protocol_param_NumericValue* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
// Max Union Tag Value
CANARD_ASSERT(source->union_tag <= 2);
// Union Tag 2 bits
canardEncodeScalar(msg_buf, offset, 2, (void*)&source->union_tag); // 2 bits
offset += 2;
if (source->union_tag == 0) {
// Compound
offset = uavcan_protocol_param_Empty_encode_internal(&source->empty, msg_buf, offset, 0);
}
else if (source->union_tag == 1) {
canardEncodeScalar(msg_buf, offset, 64, (void*)&source->integer_value); // 9223372036854775807
offset += 64;
}
else if (source->union_tag == 2) {
canardEncodeScalar(msg_buf, offset, 32, (void*)&source->real_value); // 2147483647
offset += 32;
}
return offset;
}
/**
* @brief uavcan_protocol_param_NumericValue_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_param_NumericValue_encode(uavcan_protocol_param_NumericValue* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_param_NumericValue_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_param_NumericValue_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_NumericValue dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_NumericValue_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_param_NumericValue* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
// Get Union Tag
ret = canardDecodeScalar(transfer, (uint32_t)offset, 2, false, (void*)&dest->union_tag); // 2
if (ret != 2)
{
goto uavcan_protocol_param_NumericValue_error_exit;
}
offset += 2;
if (dest->union_tag == 0)
{
// Compound
offset = uavcan_protocol_param_Empty_decode_internal(transfer, payload_len, &dest->empty, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_param_NumericValue_error_exit;
}
}
else if (dest->union_tag == 1)
{
ret = canardDecodeScalar(transfer, (uint32_t)offset, 64, true, (void*)&dest->integer_value);
if (ret != 64)
{
goto uavcan_protocol_param_NumericValue_error_exit;
}
offset += 64;
}
else if (dest->union_tag == 2)
{
ret = canardDecodeScalar(transfer, (uint32_t)offset, 32, false, (void*)&dest->real_value);
if (ret != 32)
{
goto uavcan_protocol_param_NumericValue_error_exit;
}
offset += 32;
}
return offset;
uavcan_protocol_param_NumericValue_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_param_NumericValue_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_NumericValue dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_NumericValue_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_param_NumericValue* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_param_NumericValue); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_param_NumericValue_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,258 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/param/Value.uavcan
*/
#include "uavcan/protocol/param/Value.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_param_Value_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_param_Value_encode_internal(uavcan_protocol_param_Value* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
// Max Union Tag Value
CANARD_ASSERT(source->union_tag <= 4);
uint32_t c = 0;
// Union Tag 3 bits
canardEncodeScalar(msg_buf, offset, 3, (void*)&source->union_tag); // 3 bits
offset += 3;
if (source->union_tag == 0) {
// Compound
offset = uavcan_protocol_param_Empty_encode_internal(&source->empty, msg_buf, offset, 0);
}
else if (source->union_tag == 1) {
canardEncodeScalar(msg_buf, offset, 64, (void*)&source->integer_value); // 9223372036854775807
offset += 64;
}
else if (source->union_tag == 2) {
canardEncodeScalar(msg_buf, offset, 32, (void*)&source->real_value); // 2147483647
offset += 32;
}
else if (source->union_tag == 3) {
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->boolean_value); // 255
offset += 8;
}
else if (source->union_tag == 4) {
// Dynamic Array (string_value)
if (! root_item)
{
// - Add array length
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->string_value.len);
offset += 8;
}
// - Add array items
for (c = 0; c < source->string_value.len; c++)
{
canardEncodeScalar(msg_buf,
offset,
8,
(void*)(source->string_value.data + c));// 255
offset += 8;
}
}
return offset;
}
/**
* @brief uavcan_protocol_param_Value_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_param_Value_encode(uavcan_protocol_param_Value* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_param_Value_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_param_Value_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_Value dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_Value_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_param_Value* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
uint32_t c = 0;
// Get Union Tag
ret = canardDecodeScalar(transfer, (uint32_t)offset, 3, false, (void*)&dest->union_tag); // 3
if (ret != 3)
{
goto uavcan_protocol_param_Value_error_exit;
}
offset += 3;
if (dest->union_tag == 0)
{
// Compound
offset = uavcan_protocol_param_Empty_decode_internal(transfer, payload_len, &dest->empty, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_param_Value_error_exit;
}
}
else if (dest->union_tag == 1)
{
ret = canardDecodeScalar(transfer, (uint32_t)offset, 64, true, (void*)&dest->integer_value);
if (ret != 64)
{
goto uavcan_protocol_param_Value_error_exit;
}
offset += 64;
}
else if (dest->union_tag == 2)
{
ret = canardDecodeScalar(transfer, (uint32_t)offset, 32, false, (void*)&dest->real_value);
if (ret != 32)
{
goto uavcan_protocol_param_Value_error_exit;
}
offset += 32;
}
else if (dest->union_tag == 3)
{
ret = canardDecodeScalar(transfer, (uint32_t)offset, 8, false, (void*)&dest->boolean_value);
if (ret != 8)
{
goto uavcan_protocol_param_Value_error_exit;
}
offset += 8;
}
else if (dest->union_tag == 4)
{
// Dynamic Array (string_value)
// - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization
if (payload_len)
{
// - Calculate Array length from MSG length
dest->string_value.len = ((payload_len * 8) - offset ) / 8; // 8 bit array item size
}
else
{
// - Array length 8 bits
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)&dest->string_value.len); // 255
if (ret != 8)
{
goto uavcan_protocol_param_Value_error_exit;
}
offset += 8;
}
// - Get Array
if (dyn_arr_buf)
{
dest->string_value.data = (uint8_t*)*dyn_arr_buf;
}
for (c = 0; c < dest->string_value.len; c++)
{
if (dyn_arr_buf)
{
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)*dyn_arr_buf); // 255
if (ret != 8)
{
goto uavcan_protocol_param_Value_error_exit;
}
*dyn_arr_buf = (uint8_t*)(((uint8_t*)*dyn_arr_buf) + 1);
}
offset += 8;
}
}
return offset;
uavcan_protocol_param_Value_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_param_Value_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_param_Value dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_param_Value_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_param_Value* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_param_Value); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_param_Value_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,245 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/AION/ardupilot_private/modules/uavcan/dsdl/uavcan/protocol/1.GetNodeInfo.uavcan
*/
#include "uavcan/protocol/GetNodeInfo.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
uint32_t uavcan_protocol_GetNodeInfoRequest_encode_internal(uavcan_protocol_GetNodeInfoRequest* CANARD_MAYBE_UNUSED(source),
void* CANARD_MAYBE_UNUSED(msg_buf),
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
return offset;
}
uint32_t uavcan_protocol_GetNodeInfoRequest_encode(uavcan_protocol_GetNodeInfoRequest* CANARD_MAYBE_UNUSED(source), void* CANARD_MAYBE_UNUSED(msg_buf))
{
return 0;
}
int32_t uavcan_protocol_GetNodeInfoRequest_decode_internal(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer),
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_GetNodeInfoRequest* CANARD_MAYBE_UNUSED(dest),
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
return offset;
}
int32_t uavcan_protocol_GetNodeInfoRequest_decode(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer),
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_GetNodeInfoRequest* CANARD_MAYBE_UNUSED(dest),
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf))
{
return 0;
}
/**
* @brief uavcan_protocol_GetNodeInfoResponse_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_GetNodeInfoResponse_encode_internal(uavcan_protocol_GetNodeInfoResponse* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
uint32_t c = 0;
// Compound
offset = uavcan_protocol_NodeStatus_encode_internal(&source->status, msg_buf, offset, 0);
// Compound
offset = uavcan_protocol_SoftwareVersion_encode_internal(&source->software_version, msg_buf, offset, 0);
// Compound
offset = uavcan_protocol_HardwareVersion_encode_internal(&source->hardware_version, msg_buf, offset, 0);
// Dynamic Array (name)
if (! root_item)
{
// - Add array length
canardEncodeScalar(msg_buf, offset, 7, (void*)&source->name.len);
offset += 7;
}
// - Add array items
for (c = 0; c < source->name.len; c++)
{
canardEncodeScalar(msg_buf,
offset,
8,
(void*)(source->name.data + c));// 255
offset += 8;
}
return offset;
}
/**
* @brief uavcan_protocol_GetNodeInfoResponse_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_GetNodeInfoResponse_encode(uavcan_protocol_GetNodeInfoResponse* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_GetNodeInfoResponse_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_GetNodeInfoResponse_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_GetNodeInfoResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_GetNodeInfoResponse_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_GetNodeInfoResponse* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
uint32_t c = 0;
// Compound
offset = uavcan_protocol_NodeStatus_decode_internal(transfer, payload_len, &dest->status, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_GetNodeInfoResponse_error_exit;
}
// Compound
offset = uavcan_protocol_SoftwareVersion_decode_internal(transfer, payload_len, &dest->software_version, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_GetNodeInfoResponse_error_exit;
}
// Compound
offset = uavcan_protocol_HardwareVersion_decode_internal(transfer, payload_len, &dest->hardware_version, dyn_arr_buf, offset);
if (offset < 0)
{
ret = offset;
goto uavcan_protocol_GetNodeInfoResponse_error_exit;
}
// Dynamic Array (name)
// - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization
if (payload_len)
{
// - Calculate Array length from MSG length
dest->name.len = ((payload_len * 8) - offset ) / 8; // 8 bit array item size
}
else
{
// - Array length 7 bits
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
7,
false,
(void*)&dest->name.len); // 255
if (ret != 7)
{
goto uavcan_protocol_GetNodeInfoResponse_error_exit;
}
offset += 7;
}
// - Get Array
if (dyn_arr_buf)
{
dest->name.data = (uint8_t*)*dyn_arr_buf;
}
for (c = 0; c < dest->name.len; c++)
{
if (dyn_arr_buf)
{
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)*dyn_arr_buf); // 255
if (ret != 8)
{
goto uavcan_protocol_GetNodeInfoResponse_error_exit;
}
*dyn_arr_buf = (uint8_t*)(((uint8_t*)*dyn_arr_buf) + 1);
}
offset += 8;
}
return offset;
uavcan_protocol_GetNodeInfoResponse_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_GetNodeInfoResponse_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_GetNodeInfoResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_GetNodeInfoResponse_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_GetNodeInfoResponse* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_GetNodeInfoResponse); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_GetNodeInfoResponse_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,220 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/HardwareVersion.uavcan
*/
#include "uavcan/protocol/HardwareVersion.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_HardwareVersion_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_HardwareVersion_encode_internal(uavcan_protocol_HardwareVersion* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
uint32_t c = 0;
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->major); // 255
offset += 8;
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->minor); // 255
offset += 8;
// Static array (unique_id)
for (c = 0; c < 16; c++)
{
canardEncodeScalar(msg_buf, offset, 8, (void*)(source->unique_id + c)); // 255
offset += 8;
}
// Dynamic Array (certificate_of_authenticity)
if (! root_item)
{
// - Add array length
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->certificate_of_authenticity.len);
offset += 8;
}
// - Add array items
for (c = 0; c < source->certificate_of_authenticity.len; c++)
{
canardEncodeScalar(msg_buf,
offset,
8,
(void*)(source->certificate_of_authenticity.data + c));// 255
offset += 8;
}
return offset;
}
/**
* @brief uavcan_protocol_HardwareVersion_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_HardwareVersion_encode(uavcan_protocol_HardwareVersion* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_HardwareVersion_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_HardwareVersion_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_HardwareVersion dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_HardwareVersion_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_HardwareVersion* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
uint32_t c = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 8, false, (void*)&dest->major);
if (ret != 8)
{
goto uavcan_protocol_HardwareVersion_error_exit;
}
offset += 8;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 8, false, (void*)&dest->minor);
if (ret != 8)
{
goto uavcan_protocol_HardwareVersion_error_exit;
}
offset += 8;
// Static array (unique_id)
for (c = 0; c < 16; c++)
{
ret = canardDecodeScalar(transfer, (uint32_t)offset, 8, false, (void*)(dest->unique_id + c));
if (ret != 8)
{
goto uavcan_protocol_HardwareVersion_error_exit;
}
offset += 8;
}
// Dynamic Array (certificate_of_authenticity)
// - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization
if (payload_len)
{
// - Calculate Array length from MSG length
dest->certificate_of_authenticity.len = ((payload_len * 8) - offset ) / 8; // 8 bit array item size
}
else
{
// - Array length 8 bits
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)&dest->certificate_of_authenticity.len); // 255
if (ret != 8)
{
goto uavcan_protocol_HardwareVersion_error_exit;
}
offset += 8;
}
// - Get Array
if (dyn_arr_buf)
{
dest->certificate_of_authenticity.data = (uint8_t*)*dyn_arr_buf;
}
for (c = 0; c < dest->certificate_of_authenticity.len; c++)
{
if (dyn_arr_buf)
{
ret = canardDecodeScalar(transfer,
(uint32_t)offset,
8,
false,
(void*)*dyn_arr_buf); // 255
if (ret != 8)
{
goto uavcan_protocol_HardwareVersion_error_exit;
}
*dyn_arr_buf = (uint8_t*)(((uint8_t*)*dyn_arr_buf) + 1);
}
offset += 8;
}
return offset;
uavcan_protocol_HardwareVersion_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_HardwareVersion_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_HardwareVersion dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_HardwareVersion_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_HardwareVersion* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_HardwareVersion); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_HardwareVersion_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,168 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/AION/ardupilot_private/modules/uavcan/dsdl/uavcan/protocol/341.NodeStatus.uavcan
*/
#include "uavcan/protocol/NodeStatus.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_NodeStatus_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_NodeStatus_encode_internal(uavcan_protocol_NodeStatus* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
canardEncodeScalar(msg_buf, offset, 32, (void*)&source->uptime_sec); // 4294967295
offset += 32;
source->health = CANARD_INTERNAL_SATURATE_UNSIGNED(source->health, 3)
canardEncodeScalar(msg_buf, offset, 2, (void*)&source->health); // 3
offset += 2;
source->mode = CANARD_INTERNAL_SATURATE_UNSIGNED(source->mode, 7)
canardEncodeScalar(msg_buf, offset, 3, (void*)&source->mode); // 7
offset += 3;
source->sub_mode = CANARD_INTERNAL_SATURATE_UNSIGNED(source->sub_mode, 7)
canardEncodeScalar(msg_buf, offset, 3, (void*)&source->sub_mode); // 7
offset += 3;
canardEncodeScalar(msg_buf, offset, 16, (void*)&source->vendor_specific_status_code); // 65535
offset += 16;
return offset;
}
/**
* @brief uavcan_protocol_NodeStatus_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_NodeStatus_encode(uavcan_protocol_NodeStatus* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_NodeStatus_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_NodeStatus_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_NodeStatus dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_NodeStatus_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_NodeStatus* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 32, false, (void*)&dest->uptime_sec);
if (ret != 32)
{
goto uavcan_protocol_NodeStatus_error_exit;
}
offset += 32;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 2, false, (void*)&dest->health);
if (ret != 2)
{
goto uavcan_protocol_NodeStatus_error_exit;
}
offset += 2;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 3, false, (void*)&dest->mode);
if (ret != 3)
{
goto uavcan_protocol_NodeStatus_error_exit;
}
offset += 3;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 3, false, (void*)&dest->sub_mode);
if (ret != 3)
{
goto uavcan_protocol_NodeStatus_error_exit;
}
offset += 3;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 16, false, (void*)&dest->vendor_specific_status_code);
if (ret != 16)
{
goto uavcan_protocol_NodeStatus_error_exit;
}
offset += 16;
return offset;
uavcan_protocol_NodeStatus_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_NodeStatus_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_NodeStatus dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_NodeStatus_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_NodeStatus* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_NodeStatus); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_NodeStatus_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,229 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/5.RestartNode.uavcan
*/
#include "uavcan/protocol/RestartNode.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_RestartNodeRequest_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_RestartNodeRequest_encode_internal(uavcan_protocol_RestartNodeRequest* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
source->magic_number = CANARD_INTERNAL_SATURATE_UNSIGNED(source->magic_number, 1099511627775)
canardEncodeScalar(msg_buf, offset, 40, (void*)&source->magic_number); // 1099511627775
offset += 40;
return offset;
}
/**
* @brief uavcan_protocol_RestartNodeRequest_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_RestartNodeRequest_encode(uavcan_protocol_RestartNodeRequest* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_RestartNodeRequest_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_RestartNodeRequest_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_RestartNodeRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_RestartNodeRequest_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_RestartNodeRequest* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 40, false, (void*)&dest->magic_number);
if (ret != 40)
{
goto uavcan_protocol_RestartNodeRequest_error_exit;
}
offset += 40;
return offset;
uavcan_protocol_RestartNodeRequest_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_RestartNodeRequest_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_RestartNodeRequest dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_RestartNodeRequest_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_RestartNodeRequest* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_RestartNodeRequest); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_RestartNodeRequest_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}
/**
* @brief uavcan_protocol_RestartNodeResponse_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_RestartNodeResponse_encode_internal(uavcan_protocol_RestartNodeResponse* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
source->ok = CANARD_INTERNAL_SATURATE_UNSIGNED(source->ok, 1)
canardEncodeScalar(msg_buf, offset, 1, (void*)&source->ok); // 1
offset += 1;
return offset;
}
/**
* @brief uavcan_protocol_RestartNodeResponse_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_RestartNodeResponse_encode(uavcan_protocol_RestartNodeResponse* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_RestartNodeResponse_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_RestartNodeResponse_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_RestartNodeResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_RestartNodeResponse_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_RestartNodeResponse* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 1, false, (void*)&dest->ok);
if (ret != 1)
{
goto uavcan_protocol_RestartNodeResponse_error_exit;
}
offset += 1;
return offset;
uavcan_protocol_RestartNodeResponse_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_RestartNodeResponse_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_RestartNodeResponse dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_RestartNodeResponse_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_RestartNodeResponse* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_RestartNodeResponse); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_RestartNodeResponse_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}

View File

@ -0,0 +1,165 @@
/*
* UAVCAN data structure definition for libcanard.
*
* Autogenerated, do not edit.
*
* Source file: /Users/jaime/Developer/ardupilot/modules/uavcan/dsdl/uavcan/protocol/SoftwareVersion.uavcan
*/
#include "uavcan/protocol/SoftwareVersion.h"
#include "canard.h"
#ifndef CANARD_INTERNAL_SATURATE
#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) );
#endif
#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED
#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) );
#endif
#if defined(__GNUC__)
# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused))
#else
# define CANARD_MAYBE_UNUSED(x) x
#endif
/**
* @brief uavcan_protocol_SoftwareVersion_encode_internal
* @param source : pointer to source data struct
* @param msg_buf: pointer to msg storage
* @param offset: bit offset to msg storage
* @param root_item: for detecting if TAO should be used
* @retval returns offset
*/
uint32_t uavcan_protocol_SoftwareVersion_encode_internal(uavcan_protocol_SoftwareVersion* source,
void* msg_buf,
uint32_t offset,
uint8_t CANARD_MAYBE_UNUSED(root_item))
{
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->major); // 255
offset += 8;
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->minor); // 255
offset += 8;
canardEncodeScalar(msg_buf, offset, 8, (void*)&source->optional_field_flags); // 255
offset += 8;
canardEncodeScalar(msg_buf, offset, 32, (void*)&source->vcs_commit); // 4294967295
offset += 32;
canardEncodeScalar(msg_buf, offset, 64, (void*)&source->image_crc); // 18446744073709551615
offset += 64;
return offset;
}
/**
* @brief uavcan_protocol_SoftwareVersion_encode
* @param source : Pointer to source data struct
* @param msg_buf: Pointer to msg storage
* @retval returns message length as bytes
*/
uint32_t uavcan_protocol_SoftwareVersion_encode(uavcan_protocol_SoftwareVersion* source, void* msg_buf)
{
uint32_t offset = 0;
offset = uavcan_protocol_SoftwareVersion_encode_internal(source, msg_buf, offset, 1);
return (offset + 7 ) / 8;
}
/**
* @brief uavcan_protocol_SoftwareVersion_decode_internal
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_SoftwareVersion dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @param offset: Call with 0, bit offset to msg storage
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_SoftwareVersion_decode_internal(
const CanardRxTransfer* transfer,
uint16_t CANARD_MAYBE_UNUSED(payload_len),
uavcan_protocol_SoftwareVersion* dest,
uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf),
int32_t offset)
{
int32_t ret = 0;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 8, false, (void*)&dest->major);
if (ret != 8)
{
goto uavcan_protocol_SoftwareVersion_error_exit;
}
offset += 8;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 8, false, (void*)&dest->minor);
if (ret != 8)
{
goto uavcan_protocol_SoftwareVersion_error_exit;
}
offset += 8;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 8, false, (void*)&dest->optional_field_flags);
if (ret != 8)
{
goto uavcan_protocol_SoftwareVersion_error_exit;
}
offset += 8;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 32, false, (void*)&dest->vcs_commit);
if (ret != 32)
{
goto uavcan_protocol_SoftwareVersion_error_exit;
}
offset += 32;
ret = canardDecodeScalar(transfer, (uint32_t)offset, 64, false, (void*)&dest->image_crc);
if (ret != 64)
{
goto uavcan_protocol_SoftwareVersion_error_exit;
}
offset += 64;
return offset;
uavcan_protocol_SoftwareVersion_error_exit:
if (ret < 0)
{
return ret;
}
else
{
return -CANARD_ERROR_INTERNAL;
}
}
/**
* @brief uavcan_protocol_SoftwareVersion_decode
* @param transfer: Pointer to CanardRxTransfer transfer
* @param payload_len: Payload message length
* @param dest: Pointer to destination struct
* @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays
* uavcan_protocol_SoftwareVersion dyn memory will point to dyn_arr_buf memory.
* NULL will ignore dynamic arrays decoding.
* @retval offset or ERROR value if < 0
*/
int32_t uavcan_protocol_SoftwareVersion_decode(const CanardRxTransfer* transfer,
uint16_t payload_len,
uavcan_protocol_SoftwareVersion* dest,
uint8_t** dyn_arr_buf)
{
const int32_t offset = 0;
int32_t ret = 0;
// Clear the destination struct
for (uint32_t c = 0; c < sizeof(uavcan_protocol_SoftwareVersion); c++)
{
((uint8_t*)dest)[c] = 0x00;
}
ret = uavcan_protocol_SoftwareVersion_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset);
return ret;
}