Skip to content

Commit

Permalink
DroneCAN: update cs from dsdl
Browse files Browse the repository at this point in the history
  • Loading branch information
meee1 committed Dec 18, 2024
1 parent bcca100 commit d645d5b
Show file tree
Hide file tree
Showing 25 changed files with 1,323 additions and 20 deletions.
2 changes: 1 addition & 1 deletion ExtLibs/DroneCAN/build.bat
Original file line number Diff line number Diff line change
@@ -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

Expand Down
37 changes: 22 additions & 15 deletions ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import em
import json
from canard_dsdlc_helpers import *
from multiprocessing import Pool

templates = [
{'source_file': 'request.h',
Expand Down Expand Up @@ -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:
Expand All @@ -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):
Expand All @@ -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:
Expand All @@ -96,15 +105,13 @@ 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,)

print ('test')
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<Byte[],int, bool, object> convert)[] MSG_INFO = { \n%s};}}' % (message_names_enum))

print (message_names_enum)
#print (message_names_enum)

9 changes: 9 additions & 0 deletions ExtLibs/DroneCAN/canard_dsdlc/messages.cs
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
namespace DroneCAN {
public partial class DroneCAN {
public static (Type type,UInt16 msgid, ulong crcseed, Func<Byte[],int, bool, object> 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)),
Expand All @@ -13,7 +14,9 @@ public static (Type type,UInt16 msgid, ulong crcseed, Func<Byte[],int, bool, obj
(typeof(dronecan_remoteid_SecureCommand_req), 64, 0x126A47C9C17A8BD7, (b,s,fd) => 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)),
Expand Down Expand Up @@ -42,6 +45,11 @@ public static (Type type,UInt16 msgid, ulong crcseed, Func<Byte[],int, bool, obj
(typeof(com_hobbywing_esc_GetMaintenanceInformation_res), 241, 0xB81DBD4EC9A5977D, (b,s,fd) => 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)),
Expand Down Expand Up @@ -82,6 +90,7 @@ public static (Type type,UInt16 msgid, ulong crcseed, Func<Byte[],int, bool, obj
(typeof(uavcan_equipment_esc_RawCommand), 1030, 0x217F5C87D7EC951D, (b,s,fd) => 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)),
Expand Down
51 changes: 51 additions & 0 deletions ExtLibs/DroneCAN/out/include/com.tmotor.esc.FocCtrl.cs
Original file line number Diff line number Diff line change
@@ -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;
}
}
}
}
48 changes: 48 additions & 0 deletions ExtLibs/DroneCAN/out/include/com.tmotor.esc.PUSHCAN.cs
Original file line number Diff line number Diff line change
@@ -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;
}
}
}
}
48 changes: 48 additions & 0 deletions ExtLibs/DroneCAN/out/include/com.tmotor.esc.PUSHSCI.cs
Original file line number Diff line number Diff line change
@@ -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;
}
}
}
}
61 changes: 61 additions & 0 deletions ExtLibs/DroneCAN/out/include/com.tmotor.esc.ParamCfg.cs
Original file line number Diff line number Diff line change
@@ -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;
}
}
}
}
Loading

0 comments on commit d645d5b

Please sign in to comment.