diff --git a/ExtLibs/DroneCAN/build.bat b/ExtLibs/DroneCAN/build.bat index 2100443753..518cc98b43 100644 --- a/ExtLibs/DroneCAN/build.bat +++ b/ExtLibs/DroneCAN/build.bat @@ -1,6 +1,6 @@ #!/bin/bash -python3 -m pip install dronecan empy pexpect --user +python3 -m pip install dronecan empy==3.3.4 pexpect setuptools --user python3 -m pip install --upgrade dronecan diff --git a/ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py b/ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py index 368ab99d16..02a8fd5cc6 100644 --- a/ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py +++ b/ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py @@ -4,6 +4,7 @@ import em import json from canard_dsdlc_helpers import * +from multiprocessing import Pool templates = [ {'source_file': 'request.h', @@ -48,7 +49,7 @@ messages = dronecan.dsdl.parse_namespaces(namespace_paths) message_dict = {} for msg in messages: - print(msg) + #print(msg) message_dict[msg.full_name] = msg for template in templates: @@ -58,19 +59,22 @@ def build_message(msg_name): print ('building %s' % (msg_name)) print(f'{os.getpid()}: {os.getcwd()}') - msg = message_dict[msg_name] + msglocal = message_dict[msg_name] #with open('%s.json' % (msg_name), 'w') as f: # f.write(json.dumps(msg, default=lambda x: x.__dict__)) for template in templates: - output = em.expand(template['source'], msg=msg) + output = em.expand(template['source'], msg=msglocal) if not output.strip(): continue - output_file = os.path.join(build_dir, em.expand('@{from canard_dsdlc_helpers import *}'+template['output_file'], msg=msg)) + + output_file = os.path.join(build_dir, em.expand('@{from canard_dsdlc_helpers import *}'+template['output_file'], msg=msglocal)) mkdir_p(os.path.dirname(output_file)) + print(f'Doing {msg_name} {template['source_file']} {output_file} ') with open(output_file, 'w') as f: f.write(output) + print(f'Done {msg_name}') # error callback function def handler(error): @@ -79,15 +83,20 @@ def handler(error): if __name__ == '__main__': print("start main") - from multiprocessing import Pool pool = Pool() - print("pool: buildlist is None") - for msg_name in [msg.full_name for msg in messages]: - #print ('building %s' % (msg_name,)) - #builtlist.add(msg_name) - pool.apply_async(build_message, (msg_name,),error_callback=handler) - #build_message(msg_name) + print("pool: buildlist is None") + msglist = [msg.full_name for msg in messages] + #for msg_name in [msg.full_name for msg in messages]: + # build_message(msg_name) + + pool.map_async(build_message, msglist ,error_callback=handler) + + pool.close() + pool.join() + print("pool: Done") + + for msg_name in msglist: msg = message_dict[msg_name] #print (dir(msg)) if not msg.default_dtid is None and msg.kind == msg.KIND_MESSAGE: @@ -96,9 +105,7 @@ def handler(error): if not msg.default_dtid is None and msg.kind == msg.KIND_SERVICE: message_names_enum += '\t(typeof(%s_req), %s, 0x%08X, (b,s,fd) => %s_req.ByteArrayToDroneCANMsg(b,s,fd)),\n' % (msg.full_name.replace('.','_'), msg.default_dtid, msg.get_data_type_signature(),msg.full_name.replace('.','_')) message_names_enum += '\t(typeof(%s_res), %s, 0x%08X, (b,s,fd) => %s_res.ByteArrayToDroneCANMsg(b,s,fd)),\n' % (msg.full_name.replace('.','_'), msg.default_dtid, msg.get_data_type_signature(),msg.full_name.replace('.','_')) - - pool.close() - pool.join() + assert buildlist is None or not buildlist-builtlist, "%s not built" % (buildlist-builtlist,) @@ -106,5 +113,5 @@ def handler(error): with open('messages.cs', 'w') as f: f.write('using System;using System.Reflection;\nnamespace DroneCAN {\npublic partial class DroneCAN {\n public static (Type type,UInt16 msgid, ulong crcseed, Func convert)[] MSG_INFO = { \n%s};}}' % (message_names_enum)) - print (message_names_enum) + #print (message_names_enum) diff --git a/ExtLibs/DroneCAN/canard_dsdlc/messages.cs b/ExtLibs/DroneCAN/canard_dsdlc/messages.cs index 15e6385890..d286b4ea11 100644 --- a/ExtLibs/DroneCAN/canard_dsdlc/messages.cs +++ b/ExtLibs/DroneCAN/canard_dsdlc/messages.cs @@ -2,6 +2,7 @@ namespace DroneCAN { public partial class DroneCAN { public static (Type type,UInt16 msgid, ulong crcseed, Func convert)[] MSG_INFO = { + (typeof(dronecan_protocol_FlexDebug), 16371, 0xECA60382FF038F39, (b,s,fd) => dronecan_protocol_FlexDebug.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(dronecan_protocol_Stats), 342, 0x763AE3B8A986F8D1, (b,s,fd) => dronecan_protocol_Stats.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(dronecan_protocol_CanStats), 343, 0xCE080CAE3CA33C75, (b,s,fd) => dronecan_protocol_CanStats.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(dronecan_remoteid_BasicID), 20030, 0x5B1C624A8E4FC533, (b,s,fd) => dronecan_remoteid_BasicID.ByteArrayToDroneCANMsg(b,s,fd)), @@ -13,7 +14,9 @@ public static (Type type,UInt16 msgid, ulong crcseed, Func dronecan_remoteid_SecureCommand_req.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(dronecan_remoteid_SecureCommand_res), 64, 0x126A47C9C17A8BD7, (b,s,fd) => dronecan_remoteid_SecureCommand_res.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(dronecan_sensors_hygrometer_Hygrometer), 1032, 0xCEB308892BF163E8, (b,s,fd) => dronecan_sensors_hygrometer_Hygrometer.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes), 1043, 0x3053EBE3D750286F, (b,s,fd) => dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(dronecan_sensors_rc_RCInput), 1140, 0x771555E596AAB4CF, (b,s,fd) => dronecan_sensors_rc_RCInput.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(dronecan_sensors_rpm_RPM), 1045, 0x140707C09274F6E7, (b,s,fd) => dronecan_sensors_rpm_RPM.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(com_hex_equipment_flow_Measurement), 20200, 0x6A908866BCB49C18, (b,s,fd) => com_hex_equipment_flow_Measurement.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(com_himark_servo_ServoCmd), 2018, 0x5D09E48551CE9194, (b,s,fd) => com_himark_servo_ServoCmd.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(com_himark_servo_ServoInfo), 2019, 0xCA8F4B8F97D23B57, (b,s,fd) => com_himark_servo_ServoInfo.ByteArrayToDroneCANMsg(b,s,fd)), @@ -42,6 +45,11 @@ public static (Type type,UInt16 msgid, ulong crcseed, Func com_hobbywing_esc_GetMaintenanceInformation_res.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(com_hobbywing_esc_GetMajorConfig_req), 242, 0x1506774DA3930BFD, (b,s,fd) => com_hobbywing_esc_GetMajorConfig_req.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(com_hobbywing_esc_GetMajorConfig_res), 242, 0x1506774DA3930BFD, (b,s,fd) => com_hobbywing_esc_GetMajorConfig_res.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_tmotor_esc_ParamCfg), 1033, 0x948F5E0B33E0EDEE, (b,s,fd) => com_tmotor_esc_ParamCfg.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_tmotor_esc_FocCtrl), 1035, 0x598143612FBC000B, (b,s,fd) => com_tmotor_esc_FocCtrl.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_tmotor_esc_PUSHSCI), 1038, 0xCE2B6D6B6BDC0AE8, (b,s,fd) => com_tmotor_esc_PUSHSCI.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_tmotor_esc_PUSHCAN), 1039, 0xAACF9B4B2577BC6E, (b,s,fd) => com_tmotor_esc_PUSHCAN.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_tmotor_esc_ParamGet), 1332, 0x462875A0ED874302, (b,s,fd) => com_tmotor_esc_ParamGet.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(com_volz_servo_ActuatorStatus), 20020, 0x29BF0D53B4060263, (b,s,fd) => com_volz_servo_ActuatorStatus.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(com_xacti_GnssStatus), 20305, 0x3413AC5D3E1DCBE3, (b,s,fd) => com_xacti_GnssStatus.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(com_xacti_GnssStatusReq), 20306, 0x60F5464E1CA03449, (b,s,fd) => com_xacti_GnssStatusReq.ByteArrayToDroneCANMsg(b,s,fd)), @@ -82,6 +90,7 @@ public static (Type type,UInt16 msgid, ulong crcseed, Func uavcan_equipment_esc_RawCommand.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(uavcan_equipment_esc_RPMCommand), 1031, 0xCE0F9F621CF7E70B, (b,s,fd) => uavcan_equipment_esc_RPMCommand.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(uavcan_equipment_esc_Status), 1034, 0xA9AF28AEA2FBB254, (b,s,fd) => uavcan_equipment_esc_Status.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(uavcan_equipment_esc_StatusExtended), 1036, 0x2DC203C50960EDC, (b,s,fd) => uavcan_equipment_esc_StatusExtended.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(uavcan_equipment_gnss_Fix), 1060, 0x54C1572B9E07F297, (b,s,fd) => uavcan_equipment_gnss_Fix.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(uavcan_equipment_gnss_Auxiliary), 1061, 0x9BE8BDC4C3DBBFD2, (b,s,fd) => uavcan_equipment_gnss_Auxiliary.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(uavcan_equipment_gnss_RTCMStream), 1062, 0x1F56030ECB171501, (b,s,fd) => uavcan_equipment_gnss_RTCMStream.ByteArrayToDroneCANMsg(b,s,fd)), diff --git a/ExtLibs/DroneCAN/out/include/com.tmotor.esc.FocCtrl.cs b/ExtLibs/DroneCAN/out/include/com.tmotor.esc.FocCtrl.cs new file mode 100644 index 0000000000..6f070ff5aa --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.tmotor.esc.FocCtrl.cs @@ -0,0 +1,51 @@ +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; + +namespace DroneCAN +{ + public partial class DroneCAN + { + public partial class com_tmotor_esc_FocCtrl: IDroneCANSerialize + { + public const int COM_TMOTOR_ESC_FOCCTRL_MAX_PACK_SIZE = 8; + public const ulong COM_TMOTOR_ESC_FOCCTRL_DT_SIG = 0x598143612FBC000B; + public const int COM_TMOTOR_ESC_FOCCTRL_DT_ID = 1035; + + public uint8_t esc_index = new uint8_t(); + public uint8_t esc_mode = new uint8_t(); + public uint8_t esc_fdb_rate = new uint8_t(); + public uint8_t esc_cmd = new uint8_t(); + public int32_t esc_cmd_val = new int32_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_tmotor_esc_FocCtrl(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_tmotor_esc_FocCtrl(transfer, this, fdcan); + } + + public static com_tmotor_esc_FocCtrl ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_tmotor_esc_FocCtrl(); + ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()), fdcan); + return ans; + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/include/com.tmotor.esc.PUSHCAN.cs b/ExtLibs/DroneCAN/out/include/com.tmotor.esc.PUSHCAN.cs new file mode 100644 index 0000000000..ce5ae88618 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.tmotor.esc.PUSHCAN.cs @@ -0,0 +1,48 @@ +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; + +namespace DroneCAN +{ + public partial class DroneCAN + { + public partial class com_tmotor_esc_PUSHCAN: IDroneCANSerialize + { + public const int COM_TMOTOR_ESC_PUSHCAN_MAX_PACK_SIZE = 260; + public const ulong COM_TMOTOR_ESC_PUSHCAN_DT_SIG = 0xAACF9B4B2577BC6E; + public const int COM_TMOTOR_ESC_PUSHCAN_DT_ID = 1039; + + public uint32_t data_sequence = new uint32_t(); + public uint8_t data_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=255)] public uint8_t[] data = Enumerable.Range(1, 255).Select(i => new uint8_t()).ToArray(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_tmotor_esc_PUSHCAN(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_tmotor_esc_PUSHCAN(transfer, this, fdcan); + } + + public static com_tmotor_esc_PUSHCAN ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_tmotor_esc_PUSHCAN(); + ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()), fdcan); + return ans; + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/include/com.tmotor.esc.PUSHSCI.cs b/ExtLibs/DroneCAN/out/include/com.tmotor.esc.PUSHSCI.cs new file mode 100644 index 0000000000..c108904608 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.tmotor.esc.PUSHSCI.cs @@ -0,0 +1,48 @@ +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; + +namespace DroneCAN +{ + public partial class DroneCAN + { + public partial class com_tmotor_esc_PUSHSCI: IDroneCANSerialize + { + public const int COM_TMOTOR_ESC_PUSHSCI_MAX_PACK_SIZE = 260; + public const ulong COM_TMOTOR_ESC_PUSHSCI_DT_SIG = 0xCE2B6D6B6BDC0AE8; + public const int COM_TMOTOR_ESC_PUSHSCI_DT_ID = 1038; + + public uint32_t data_sequence = new uint32_t(); + public uint8_t data_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=255)] public uint8_t[] data = Enumerable.Range(1, 255).Select(i => new uint8_t()).ToArray(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_tmotor_esc_PUSHSCI(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_tmotor_esc_PUSHSCI(transfer, this, fdcan); + } + + public static com_tmotor_esc_PUSHSCI ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_tmotor_esc_PUSHSCI(); + ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()), fdcan); + return ans; + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/include/com.tmotor.esc.ParamCfg.cs b/ExtLibs/DroneCAN/out/include/com.tmotor.esc.ParamCfg.cs new file mode 100644 index 0000000000..5b4e704028 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.tmotor.esc.ParamCfg.cs @@ -0,0 +1,61 @@ +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; + +namespace DroneCAN +{ + public partial class DroneCAN + { + public partial class com_tmotor_esc_ParamCfg: IDroneCANSerialize + { + public const int COM_TMOTOR_ESC_PARAMCFG_MAX_PACK_SIZE = 27; + public const ulong COM_TMOTOR_ESC_PARAMCFG_DT_SIG = 0x948F5E0B33E0EDEE; + public const int COM_TMOTOR_ESC_PARAMCFG_DT_ID = 1033; + + public uint8_t esc_index = new uint8_t(); + public uint32_t esc_uuid = new uint32_t(); + public uint16_t esc_id_set = new uint16_t(); + public uint16_t esc_ov_threshold = new uint16_t(); + public uint16_t esc_oc_threshold = new uint16_t(); + public uint16_t esc_ot_threshold = new uint16_t(); + public uint16_t esc_acc_threshold = new uint16_t(); + public uint16_t esc_dacc_threshold = new uint16_t(); + public int16_t esc_rotate_dir = new int16_t(); + public uint8_t esc_timing = new uint8_t(); + public uint8_t esc_signal_priority = new uint8_t(); + public uint16_t esc_led_mode = new uint16_t(); + public uint8_t esc_can_rate = new uint8_t(); + public uint16_t esc_fdb_rate = new uint16_t(); + public uint8_t esc_save_option = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_tmotor_esc_ParamCfg(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_tmotor_esc_ParamCfg(transfer, this, fdcan); + } + + public static com_tmotor_esc_ParamCfg ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_tmotor_esc_ParamCfg(); + ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()), fdcan); + return ans; + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/include/com.tmotor.esc.ParamGet.cs b/ExtLibs/DroneCAN/out/include/com.tmotor.esc.ParamGet.cs new file mode 100644 index 0000000000..4155ae2983 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.tmotor.esc.ParamGet.cs @@ -0,0 +1,66 @@ +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; + +namespace DroneCAN +{ + public partial class DroneCAN + { + public partial class com_tmotor_esc_ParamGet: IDroneCANSerialize + { + public const int COM_TMOTOR_ESC_PARAMGET_MAX_PACK_SIZE = 74; + public const ulong COM_TMOTOR_ESC_PARAMGET_DT_SIG = 0x462875A0ED874302; + public const int COM_TMOTOR_ESC_PARAMGET_DT_ID = 1332; + + public uint8_t esc_index = new uint8_t(); + public uint32_t esc_uuid = new uint32_t(); + public uint16_t esc_id_req = new uint16_t(); + public uint16_t esc_ov_threshold = new uint16_t(); + public uint16_t esc_oc_threshold = new uint16_t(); + public uint16_t esc_ot_threshold = new uint16_t(); + public uint16_t esc_acc_threshold = new uint16_t(); + public uint16_t esc_dacc_threshold = new uint16_t(); + public int16_t esc_rotate_dir = new int16_t(); + public uint8_t esc_timing = new uint8_t(); + public uint16_t esc_startup_times = new uint16_t(); + public uint32_t esc_startup_duration = new uint32_t(); + public uint32_t esc_product_date = new uint32_t(); + public uint32_t esc_error_count = new uint32_t(); + public uint8_t esc_signal_priority = new uint8_t(); + public uint16_t esc_led_mode = new uint16_t(); + public uint8_t esc_can_rate = new uint8_t(); + public uint16_t esc_fdb_rate = new uint16_t(); + public uint8_t esc_save_option = new uint8_t(); + public uint8_t rsvd_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] public uint8_t[] rsvd = Enumerable.Range(1, 32).Select(i => new uint8_t()).ToArray(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_tmotor_esc_ParamGet(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_tmotor_esc_ParamGet(transfer, this, fdcan); + } + + public static com_tmotor_esc_ParamGet ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_tmotor_esc_ParamGet(); + ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()), fdcan); + return ans; + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/include/dronecan.protocol.FlexDebug.cs b/ExtLibs/DroneCAN/out/include/dronecan.protocol.FlexDebug.cs new file mode 100644 index 0000000000..ff170f4296 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/dronecan.protocol.FlexDebug.cs @@ -0,0 +1,52 @@ +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; + +namespace DroneCAN +{ + public partial class DroneCAN + { + public partial class dronecan_protocol_FlexDebug: IDroneCANSerialize + { + public const int DRONECAN_PROTOCOL_FLEXDEBUG_MAX_PACK_SIZE = 258; + public const ulong DRONECAN_PROTOCOL_FLEXDEBUG_DT_SIG = 0xECA60382FF038F39; + public const int DRONECAN_PROTOCOL_FLEXDEBUG_DT_ID = 16371; + + public const double DRONECAN_PROTOCOL_FLEXDEBUG_RESERVATION_SIZE = 10; // saturated uint16 + public const double DRONECAN_PROTOCOL_FLEXDEBUG_AM32_RESERVE_START = 100; // saturated uint16 + public const double DRONECAN_PROTOCOL_FLEXDEBUG_MLRS_RESERVE_START = 110; // saturated uint16 + + public uint16_t id = new uint16_t(); + public uint8_t u8_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=255)] public uint8_t[] u8 = Enumerable.Range(1, 255).Select(i => new uint8_t()).ToArray(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_dronecan_protocol_FlexDebug(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_dronecan_protocol_FlexDebug(transfer, this, fdcan); + } + + public static dronecan_protocol_FlexDebug ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new dronecan_protocol_FlexDebug(); + ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()), fdcan); + return ans; + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/include/dronecan.sensors.magnetometer.MagneticFieldStrengthHiRes.cs b/ExtLibs/DroneCAN/out/include/dronecan.sensors.magnetometer.MagneticFieldStrengthHiRes.cs new file mode 100644 index 0000000000..2e37c3b1d2 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/dronecan.sensors.magnetometer.MagneticFieldStrengthHiRes.cs @@ -0,0 +1,48 @@ +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; + +namespace DroneCAN +{ + public partial class DroneCAN + { + public partial class dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes: IDroneCANSerialize + { + public const int DRONECAN_SENSORS_MAGNETOMETER_MAGNETICFIELDSTRENGTHHIRES_MAX_PACK_SIZE = 13; + public const ulong DRONECAN_SENSORS_MAGNETOMETER_MAGNETICFIELDSTRENGTHHIRES_DT_SIG = 0x3053EBE3D750286F; + public const int DRONECAN_SENSORS_MAGNETOMETER_MAGNETICFIELDSTRENGTHHIRES_DT_ID = 1043; + + public uint8_t sensor_id = new uint8_t(); + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] public Single[] magnetic_field_ga = new Single[3]; + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes(transfer, this, fdcan); + } + + public static dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes(); + ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()), fdcan); + return ans; + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/include/dronecan.sensors.rpm.RPM.cs b/ExtLibs/DroneCAN/out/include/dronecan.sensors.rpm.RPM.cs new file mode 100644 index 0000000000..d2da29a928 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/dronecan.sensors.rpm.RPM.cs @@ -0,0 +1,51 @@ +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; + +namespace DroneCAN +{ + public partial class DroneCAN + { + public partial class dronecan_sensors_rpm_RPM: IDroneCANSerialize + { + public const int DRONECAN_SENSORS_RPM_RPM_MAX_PACK_SIZE = 7; + public const ulong DRONECAN_SENSORS_RPM_RPM_DT_SIG = 0x140707C09274F6E7; + public const int DRONECAN_SENSORS_RPM_RPM_DT_ID = 1045; + + public const double DRONECAN_SENSORS_RPM_RPM_FLAGS_UNHEALTHY = 1; // saturated uint16 + + public uint8_t sensor_id = new uint8_t(); + public uint16_t flags = new uint16_t(); + public Single rpm = new Single(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_dronecan_sensors_rpm_RPM(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_dronecan_sensors_rpm_RPM(transfer, this, fdcan); + } + + public static dronecan_sensors_rpm_RPM ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new dronecan_sensors_rpm_RPM(); + ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()), fdcan); + return ans; + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.StatusExtended.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.StatusExtended.cs new file mode 100644 index 0000000000..49ccf54652 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.StatusExtended.cs @@ -0,0 +1,52 @@ +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; + +namespace DroneCAN +{ + public partial class DroneCAN + { + public partial class uavcan_equipment_esc_StatusExtended: IDroneCANSerialize + { + public const int UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_MAX_PACK_SIZE = 7; + public const ulong UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_DT_SIG = 0x2DC203C50960EDC; + public const int UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_DT_ID = 1036; + + public uint8_t input_pct = new uint8_t(); + public uint8_t output_pct = new uint8_t(); + public int16_t motor_temperature_degC = new int16_t(); + public uint16_t motor_angle = new uint16_t(); + public uint32_t status_flags = new uint32_t(); + public uint8_t esc_index = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_uavcan_equipment_esc_StatusExtended(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_uavcan_equipment_esc_StatusExtended(transfer, this, fdcan); + } + + public static uavcan_equipment_esc_StatusExtended ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new uavcan_equipment_esc_StatusExtended(); + ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()), fdcan); + return ans; + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix2.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix2.cs index 108c206747..c80fff89b6 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix2.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix2.cs @@ -18,8 +18,8 @@ namespace DroneCAN { public partial class DroneCAN { -//using uavcan.equipment.gnss.ECEFPositionVelocity.cs //using uavcan.Timestamp.cs +//using uavcan.equipment.gnss.ECEFPositionVelocity.cs public partial class uavcan_equipment_gnss_Fix2: IDroneCANSerialize { public const int UAVCAN_EQUIPMENT_GNSS_FIX2_MAX_PACK_SIZE = 222; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.range_sensor.Measurement.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.range_sensor.Measurement.cs index 4f78114433..7c6bd5b9c9 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.range_sensor.Measurement.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.range_sensor.Measurement.cs @@ -18,8 +18,8 @@ namespace DroneCAN { public partial class DroneCAN { -//using uavcan.Timestamp.cs //using uavcan.CoarseOrientation.cs +//using uavcan.Timestamp.cs public partial class uavcan_equipment_range_sensor_Measurement: IDroneCANSerialize { public const int UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_MAX_PACK_SIZE = 15; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_res.cs index 7ce7cbe442..8b12508bd7 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_res.cs @@ -18,9 +18,9 @@ namespace DroneCAN { public partial class DroneCAN { +//using uavcan.protocol.NodeStatus.cs //using uavcan.protocol.HardwareVersion.cs //using uavcan.protocol.SoftwareVersion.cs -//using uavcan.protocol.NodeStatus.cs public partial class uavcan_protocol_GetNodeInfo_res: IDroneCANSerialize { public const int UAVCAN_PROTOCOL_GETNODEINFO_RES_MAX_PACK_SIZE = 377; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetDirectoryEntryInfo_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetDirectoryEntryInfo_res.cs index a042c780a3..9672b31228 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetDirectoryEntryInfo_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetDirectoryEntryInfo_res.cs @@ -19,8 +19,8 @@ namespace DroneCAN public partial class DroneCAN { //using uavcan.protocol.file.Path.cs -//using uavcan.protocol.file.Error.cs //using uavcan.protocol.file.EntryType.cs +//using uavcan.protocol.file.Error.cs public partial class uavcan_protocol_file_GetDirectoryEntryInfo_res: IDroneCANSerialize { public const int UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_RES_MAX_PACK_SIZE = 204; diff --git a/ExtLibs/DroneCAN/out/src/com.tmotor.esc.FocCtrl.cs b/ExtLibs/DroneCAN/out/src/com.tmotor.esc.FocCtrl.cs new file mode 100644 index 0000000000..cb621a5dfb --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.tmotor.esc.FocCtrl.cs @@ -0,0 +1,74 @@ + +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + + public partial class com_tmotor_esc_FocCtrl : IDroneCANSerialize + { + public static void encode_com_tmotor_esc_FocCtrl(com_tmotor_esc_FocCtrl msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_tmotor_esc_FocCtrl(buffer, msg, chunk_cb, ctx, !fdcan); + } + + public static uint32_t decode_com_tmotor_esc_FocCtrl(CanardRxTransfer transfer, com_tmotor_esc_FocCtrl msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_tmotor_esc_FocCtrl(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + internal static void _encode_com_tmotor_esc_FocCtrl(uint8_t[] buffer, com_tmotor_esc_FocCtrl msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_index); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_mode); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_fdb_rate); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_cmd); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.esc_cmd_val); + chunk_cb(buffer, 32, ctx); + } + + internal static void _decode_com_tmotor_esc_FocCtrl(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_tmotor_esc_FocCtrl msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_index); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_mode); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_fdb_rate); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_cmd); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 32, true, ref msg.esc_cmd_val); + bit_ofs += 32; + + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.tmotor.esc.PUSHCAN.cs b/ExtLibs/DroneCAN/out/src/com.tmotor.esc.PUSHCAN.cs new file mode 100644 index 0000000000..b71d6e67f2 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.tmotor.esc.PUSHCAN.cs @@ -0,0 +1,73 @@ + +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + + public partial class com_tmotor_esc_PUSHCAN : IDroneCANSerialize + { + public static void encode_com_tmotor_esc_PUSHCAN(com_tmotor_esc_PUSHCAN msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_tmotor_esc_PUSHCAN(buffer, msg, chunk_cb, ctx, !fdcan); + } + + public static uint32_t decode_com_tmotor_esc_PUSHCAN(CanardRxTransfer transfer, com_tmotor_esc_PUSHCAN msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_tmotor_esc_PUSHCAN(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + internal static void _encode_com_tmotor_esc_PUSHCAN(uint8_t[] buffer, com_tmotor_esc_PUSHCAN msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.data_sequence); + chunk_cb(buffer, 32, ctx); + if (!tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.data_len); + chunk_cb(buffer, 8, ctx); + } + for (int i=0; i < msg.data_len; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.data[i]); + chunk_cb(buffer, 8, ctx); + } + } + + internal static void _decode_com_tmotor_esc_PUSHCAN(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_tmotor_esc_PUSHCAN msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.data_sequence); + bit_ofs += 32; + + if (!tao) { + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.data_len); + bit_ofs += 8; + } else { + msg.data_len = (uint8_t)(((transfer.payload_len*8)-bit_ofs)/8); + } + + msg.data = new uint8_t[msg.data_len]; + for (int i=0; i < msg.data_len; i++) { + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.data[i]); + bit_ofs += 8; + } + + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.tmotor.esc.PUSHSCI.cs b/ExtLibs/DroneCAN/out/src/com.tmotor.esc.PUSHSCI.cs new file mode 100644 index 0000000000..c6af7ff2c7 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.tmotor.esc.PUSHSCI.cs @@ -0,0 +1,73 @@ + +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + + public partial class com_tmotor_esc_PUSHSCI : IDroneCANSerialize + { + public static void encode_com_tmotor_esc_PUSHSCI(com_tmotor_esc_PUSHSCI msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_tmotor_esc_PUSHSCI(buffer, msg, chunk_cb, ctx, !fdcan); + } + + public static uint32_t decode_com_tmotor_esc_PUSHSCI(CanardRxTransfer transfer, com_tmotor_esc_PUSHSCI msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_tmotor_esc_PUSHSCI(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + internal static void _encode_com_tmotor_esc_PUSHSCI(uint8_t[] buffer, com_tmotor_esc_PUSHSCI msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.data_sequence); + chunk_cb(buffer, 32, ctx); + if (!tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.data_len); + chunk_cb(buffer, 8, ctx); + } + for (int i=0; i < msg.data_len; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.data[i]); + chunk_cb(buffer, 8, ctx); + } + } + + internal static void _decode_com_tmotor_esc_PUSHSCI(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_tmotor_esc_PUSHSCI msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.data_sequence); + bit_ofs += 32; + + if (!tao) { + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.data_len); + bit_ofs += 8; + } else { + msg.data_len = (uint8_t)(((transfer.payload_len*8)-bit_ofs)/8); + } + + msg.data = new uint8_t[msg.data_len]; + for (int i=0; i < msg.data_len; i++) { + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.data[i]); + bit_ofs += 8; + } + + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.tmotor.esc.ParamCfg.cs b/ExtLibs/DroneCAN/out/src/com.tmotor.esc.ParamCfg.cs new file mode 100644 index 0000000000..97b36eee05 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.tmotor.esc.ParamCfg.cs @@ -0,0 +1,134 @@ + +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + + public partial class com_tmotor_esc_ParamCfg : IDroneCANSerialize + { + public static void encode_com_tmotor_esc_ParamCfg(com_tmotor_esc_ParamCfg msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_tmotor_esc_ParamCfg(buffer, msg, chunk_cb, ctx, !fdcan); + } + + public static uint32_t decode_com_tmotor_esc_ParamCfg(CanardRxTransfer transfer, com_tmotor_esc_ParamCfg msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_tmotor_esc_ParamCfg(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + internal static void _encode_com_tmotor_esc_ParamCfg(uint8_t[] buffer, com_tmotor_esc_ParamCfg msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_index); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.esc_uuid); + chunk_cb(buffer, 32, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_id_set); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_ov_threshold); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_oc_threshold); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_ot_threshold); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_acc_threshold); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_dacc_threshold); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_rotate_dir); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_timing); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_signal_priority); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_led_mode); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_can_rate); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_fdb_rate); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_save_option); + chunk_cb(buffer, 8, ctx); + } + + internal static void _decode_com_tmotor_esc_ParamCfg(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_tmotor_esc_ParamCfg msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_index); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.esc_uuid); + bit_ofs += 32; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_id_set); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_ov_threshold); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_oc_threshold); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_ot_threshold); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_acc_threshold); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_dacc_threshold); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.esc_rotate_dir); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_timing); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_signal_priority); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_led_mode); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_can_rate); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_fdb_rate); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_save_option); + bit_ofs += 8; + + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.tmotor.esc.ParamGet.cs b/ExtLibs/DroneCAN/out/src/com.tmotor.esc.ParamGet.cs new file mode 100644 index 0000000000..99f3623fd4 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.tmotor.esc.ParamGet.cs @@ -0,0 +1,181 @@ + +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + + public partial class com_tmotor_esc_ParamGet : IDroneCANSerialize + { + public static void encode_com_tmotor_esc_ParamGet(com_tmotor_esc_ParamGet msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_tmotor_esc_ParamGet(buffer, msg, chunk_cb, ctx, !fdcan); + } + + public static uint32_t decode_com_tmotor_esc_ParamGet(CanardRxTransfer transfer, com_tmotor_esc_ParamGet msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_tmotor_esc_ParamGet(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + internal static void _encode_com_tmotor_esc_ParamGet(uint8_t[] buffer, com_tmotor_esc_ParamGet msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_index); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.esc_uuid); + chunk_cb(buffer, 32, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_id_req); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_ov_threshold); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_oc_threshold); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_ot_threshold); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_acc_threshold); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_dacc_threshold); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_rotate_dir); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_timing); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_startup_times); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.esc_startup_duration); + chunk_cb(buffer, 32, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.esc_product_date); + chunk_cb(buffer, 32, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.esc_error_count); + chunk_cb(buffer, 32, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_signal_priority); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_led_mode); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_can_rate); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.esc_fdb_rate); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.esc_save_option); + chunk_cb(buffer, 8, ctx); + if (!tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 6, msg.rsvd_len); + chunk_cb(buffer, 6, ctx); + } + for (int i=0; i < msg.rsvd_len; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.rsvd[i]); + chunk_cb(buffer, 8, ctx); + } + } + + internal static void _decode_com_tmotor_esc_ParamGet(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_tmotor_esc_ParamGet msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_index); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.esc_uuid); + bit_ofs += 32; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_id_req); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_ov_threshold); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_oc_threshold); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_ot_threshold); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_acc_threshold); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_dacc_threshold); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.esc_rotate_dir); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_timing); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_startup_times); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.esc_startup_duration); + bit_ofs += 32; + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.esc_product_date); + bit_ofs += 32; + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.esc_error_count); + bit_ofs += 32; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_signal_priority); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_led_mode); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_can_rate); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.esc_fdb_rate); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.esc_save_option); + bit_ofs += 8; + + if (!tao) { + canardDecodeScalar(transfer, bit_ofs, 6, false, ref msg.rsvd_len); + bit_ofs += 6; + } else { + msg.rsvd_len = (uint8_t)(((transfer.payload_len*8)-bit_ofs)/8); + } + + msg.rsvd = new uint8_t[msg.rsvd_len]; + for (int i=0; i < msg.rsvd_len; i++) { + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.rsvd[i]); + bit_ofs += 8; + } + + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/dronecan.protocol.FlexDebug.cs b/ExtLibs/DroneCAN/out/src/dronecan.protocol.FlexDebug.cs new file mode 100644 index 0000000000..39b4fb5865 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/dronecan.protocol.FlexDebug.cs @@ -0,0 +1,73 @@ + +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + + public partial class dronecan_protocol_FlexDebug : IDroneCANSerialize + { + public static void encode_dronecan_protocol_FlexDebug(dronecan_protocol_FlexDebug msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_dronecan_protocol_FlexDebug(buffer, msg, chunk_cb, ctx, !fdcan); + } + + public static uint32_t decode_dronecan_protocol_FlexDebug(CanardRxTransfer transfer, dronecan_protocol_FlexDebug msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_dronecan_protocol_FlexDebug(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + internal static void _encode_dronecan_protocol_FlexDebug(uint8_t[] buffer, dronecan_protocol_FlexDebug msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.id); + chunk_cb(buffer, 16, ctx); + if (!tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.u8_len); + chunk_cb(buffer, 8, ctx); + } + for (int i=0; i < msg.u8_len; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.u8[i]); + chunk_cb(buffer, 8, ctx); + } + } + + internal static void _decode_dronecan_protocol_FlexDebug(CanardRxTransfer transfer,ref uint32_t bit_ofs, dronecan_protocol_FlexDebug msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.id); + bit_ofs += 16; + + if (!tao) { + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.u8_len); + bit_ofs += 8; + } else { + msg.u8_len = (uint8_t)(((transfer.payload_len*8)-bit_ofs)/8); + } + + msg.u8 = new uint8_t[msg.u8_len]; + for (int i=0; i < msg.u8_len; i++) { + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.u8[i]); + bit_ofs += 8; + } + + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/dronecan.sensors.magnetometer.MagneticFieldStrengthHiRes.cs b/ExtLibs/DroneCAN/out/src/dronecan.sensors.magnetometer.MagneticFieldStrengthHiRes.cs new file mode 100644 index 0000000000..c12a59e2b8 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/dronecan.sensors.magnetometer.MagneticFieldStrengthHiRes.cs @@ -0,0 +1,60 @@ + +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + + public partial class dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes : IDroneCANSerialize + { + public static void encode_dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes(dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes(buffer, msg, chunk_cb, ctx, !fdcan); + } + + public static uint32_t decode_dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes(CanardRxTransfer transfer, dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + internal static void _encode_dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes(uint8_t[] buffer, dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.sensor_id); + chunk_cb(buffer, 8, ctx); + for (int i=0; i < 3; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.magnetic_field_ga[i]); + chunk_cb(buffer, 32, ctx); + } + } + + internal static void _decode_dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes(CanardRxTransfer transfer,ref uint32_t bit_ofs, dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.sensor_id); + bit_ofs += 8; + + for (int i=0; i < 3; i++) { + canardDecodeScalar(transfer, bit_ofs, 32, true, ref msg.magnetic_field_ga[i]); + bit_ofs += 32; + } + + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/dronecan.sensors.rpm.RPM.cs b/ExtLibs/DroneCAN/out/src/dronecan.sensors.rpm.RPM.cs new file mode 100644 index 0000000000..1e2a54f6b8 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/dronecan.sensors.rpm.RPM.cs @@ -0,0 +1,62 @@ + +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + + public partial class dronecan_sensors_rpm_RPM : IDroneCANSerialize + { + public static void encode_dronecan_sensors_rpm_RPM(dronecan_sensors_rpm_RPM msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_dronecan_sensors_rpm_RPM(buffer, msg, chunk_cb, ctx, !fdcan); + } + + public static uint32_t decode_dronecan_sensors_rpm_RPM(CanardRxTransfer transfer, dronecan_sensors_rpm_RPM msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_dronecan_sensors_rpm_RPM(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + internal static void _encode_dronecan_sensors_rpm_RPM(uint8_t[] buffer, dronecan_sensors_rpm_RPM msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.sensor_id); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.flags); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.rpm); + chunk_cb(buffer, 32, ctx); + } + + internal static void _decode_dronecan_sensors_rpm_RPM(CanardRxTransfer transfer,ref uint32_t bit_ofs, dronecan_sensors_rpm_RPM msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.sensor_id); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.flags); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 32, true, ref msg.rpm); + bit_ofs += 32; + + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/uavcan.equipment.esc.StatusExtended.cs b/ExtLibs/DroneCAN/out/src/uavcan.equipment.esc.StatusExtended.cs new file mode 100644 index 0000000000..ac03118920 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/uavcan.equipment.esc.StatusExtended.cs @@ -0,0 +1,80 @@ + +using uint8_t = System.Byte; +using uint16_t = System.UInt16; +using uint32_t = System.UInt32; +using uint64_t = System.UInt64; + +using int8_t = System.SByte; +using int16_t = System.Int16; +using int32_t = System.Int32; +using int64_t = System.Int64; + +using float32 = System.Single; + +using System; +using System.Linq; +using System.Runtime.InteropServices; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + + public partial class uavcan_equipment_esc_StatusExtended : IDroneCANSerialize + { + public static void encode_uavcan_equipment_esc_StatusExtended(uavcan_equipment_esc_StatusExtended msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_uavcan_equipment_esc_StatusExtended(buffer, msg, chunk_cb, ctx, !fdcan); + } + + public static uint32_t decode_uavcan_equipment_esc_StatusExtended(CanardRxTransfer transfer, uavcan_equipment_esc_StatusExtended msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_uavcan_equipment_esc_StatusExtended(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + internal static void _encode_uavcan_equipment_esc_StatusExtended(uint8_t[] buffer, uavcan_equipment_esc_StatusExtended msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 7, msg.input_pct); + chunk_cb(buffer, 7, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 7, msg.output_pct); + chunk_cb(buffer, 7, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 9, msg.motor_temperature_degC); + chunk_cb(buffer, 9, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 9, msg.motor_angle); + chunk_cb(buffer, 9, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 19, msg.status_flags); + chunk_cb(buffer, 19, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 5, msg.esc_index); + chunk_cb(buffer, 5, ctx); + } + + internal static void _decode_uavcan_equipment_esc_StatusExtended(CanardRxTransfer transfer,ref uint32_t bit_ofs, uavcan_equipment_esc_StatusExtended msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 7, false, ref msg.input_pct); + bit_ofs += 7; + + canardDecodeScalar(transfer, bit_ofs, 7, false, ref msg.output_pct); + bit_ofs += 7; + + canardDecodeScalar(transfer, bit_ofs, 9, true, ref msg.motor_temperature_degC); + bit_ofs += 9; + + canardDecodeScalar(transfer, bit_ofs, 9, false, ref msg.motor_angle); + bit_ofs += 9; + + canardDecodeScalar(transfer, bit_ofs, 19, false, ref msg.status_flags); + bit_ofs += 19; + + canardDecodeScalar(transfer, bit_ofs, 5, false, ref msg.esc_index); + bit_ofs += 5; + + } + } + } +} \ No newline at end of file