Skip to content

Commit

Permalink
DroneCan: move functions to inside repective class
Browse files Browse the repository at this point in the history
  • Loading branch information
meee1 committed Jul 13, 2023
1 parent 5ae72df commit 340a531
Show file tree
Hide file tree
Showing 168 changed files with 7,790 additions and 7,153 deletions.
70 changes: 21 additions & 49 deletions ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@

def build_message(msg_name):
print ('building %s' % (msg_name))
print(f'{os.getpid()}: {os.getcwd()}')
msg = message_dict[msg_name]
#with open('%s.json' % (msg_name), 'w') as f:
# f.write(json.dumps(msg, default=lambda x: x.__dict__))
Expand All @@ -71,59 +72,30 @@ def build_message(msg_name):
with open(output_file, 'w') as f:
f.write(output)

# error callback function
def handler(error):
print(error)
raise Exception('Something bad happened')

if __name__ == '__main__':
print("start main")
if buildlist is not None:
print("buildlist is not None")
while True:
new_buildlist = set(buildlist)
for msg_name in buildlist:
msg = message_dict[msg_name]
fields = getattr(msg, 'fields', []) + getattr(msg, 'request_fields', []) + getattr(msg, 'response_fields', [])
for field in fields:
if field.type.category == field.type.CATEGORY_COMPOUND:
new_buildlist.add(field.type.full_name)
elif field.type.category == field.type.CATEGORY_ARRAY and field.type.value_type.category == field.type.CATEGORY_COMPOUND:
new_buildlist.add(field.type.value_type.full_name)

if not new_buildlist-buildlist:
break

buildlist = new_buildlist

from multiprocessing import Pool

pool = Pool(8)
builtlist = set()
if buildlist is not None:
for msg_name in buildlist:
builtlist.add(msg_name)
pool.apply_async(build_message, (msg_name,))
#build_message(msg_name)
msg = message_dict[msg_name]
print (dir(msg))
if not msg.default_dtid is None and msg.kind == msg.KIND_MESSAGE:
message_names_enum += '\t(typeof(%s), %s, 0x%08X, (b,s) => %s.ByteArrayToDroneCANMsg(b,s)),\n' % (msg.full_name.replace('.','_'), msg.default_dtid, msg.get_data_type_signature(),msg.full_name.replace('.','_'))

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) => %s_req.ByteArrayToDroneCANMsg(b,s)),\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) => %s_res.ByteArrayToDroneCANMsg(b,s)),\n' % (msg.full_name.replace('.','_'), msg.default_dtid, msg.get_data_type_signature(),msg.full_name.replace('.','_'))
else:
print("buildlist is None")
print(f'{os.getpid()}: {os.getcwd()}')
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,))
build_message(msg_name)
msg = message_dict[msg_name]
print (dir(msg))
if not msg.default_dtid is None and msg.kind == msg.KIND_MESSAGE:
message_names_enum += '\t(typeof(%s), %s, 0x%08X, (b,s,fd) => %s.ByteArrayToDroneCANMsg(b,s,fd)),\n' % (msg.full_name.replace('.','_'), msg.default_dtid, msg.get_data_type_signature(),msg.full_name.replace('.','_'))

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 = 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)
msg = message_dict[msg_name]
#print (dir(msg))
if not msg.default_dtid is None and msg.kind == msg.KIND_MESSAGE:
message_names_enum += '\t(typeof(%s), %s, 0x%08X, (b,s,fd) => %s.ByteArrayToDroneCANMsg(b,s,fd)),\n' % (msg.full_name.replace('.','_'), msg.default_dtid, msg.get_data_type_signature(),msg.full_name.replace('.','_'))

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()
Expand Down
37 changes: 21 additions & 16 deletions ExtLibs/DroneCAN/canard_dsdlc/templates/msg.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,19 +22,23 @@ namespace DroneCAN
{
@{indent += 1}@{ind = ' '*indent}@
public partial class DroneCAN {
static void encode_@(msg_underscored_name)(@(msg_c_type) msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) {
uint8_t[] buffer = new uint8_t[8];
_encode_@(msg_underscored_name)(buffer, msg, chunk_cb, ctx, !fdcan);
}

static uint32_t decode_@(msg_underscored_name)(CanardRxTransfer transfer, @(msg_c_type) msg, bool fdcan) {
uint32_t bit_ofs = 0;
_decode_@(msg_underscored_name)(transfer, ref bit_ofs, msg, !fdcan);
return (bit_ofs+7)/8;
}
public partial class @(msg_c_type) : IDroneCANSerialize
{
public static void encode_@(msg_underscored_name)(@(msg_c_type) msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) {
uint8_t[] buffer = new uint8_t[8];
_encode_@(msg_underscored_name)(buffer, msg, chunk_cb, ctx, !fdcan);
}

static void _encode_@(msg_underscored_name)(uint8_t[] buffer, @(msg_c_type) msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) {
public static uint32_t decode_@(msg_underscored_name)(CanardRxTransfer transfer, @(msg_c_type) msg, bool fdcan) {
uint32_t bit_ofs = 0;
_decode_@(msg_underscored_name)(transfer, ref bit_ofs, msg, !fdcan);
return (bit_ofs+7)/8;
}

internal static void _encode_@(msg_underscored_name)(uint8_t[] buffer, @(msg_c_type) msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) {
@{indent += 1}@{ind = ' '*indent}@
@{indent += 1}@{ind = ' ' * indent}@
@{indent += 1}@{ind = ' '*indent}@
@[ if msg_union]@
@(ind)@(union_msg_tag_uint_type_from_num_fields(len(msg_fields))) @(msg_underscored_name)_type = (@(union_msg_tag_uint_type_from_num_fields(len(msg_fields))))msg.@(msg_underscored_name)_type;
Expand All @@ -51,7 +55,7 @@ namespace DroneCAN
@{indent += 1}@{ind = ' '*indent}@
@[ end if]@
@[ if field.type.category == field.type.CATEGORY_COMPOUND]@
@(ind)_encode_@(underscored_name(field.type))(buffer, msg.@('union.' if msg_union else '')@(field.name), chunk_cb, ctx, @('tao' if field == msg_fields[-1] else 'false'));
@(ind)@(underscored_name(field.type))._encode_@(underscored_name(field.type))(buffer, msg.@('union.' if msg_union else '')@(field.name), chunk_cb, ctx, @('tao' if field == msg_fields[-1] else 'false'));
@[ elif field.type.category == field.type.CATEGORY_PRIMITIVE]@
@(ind)memset(buffer,0,8);
@[ if field.type.kind == field.type.KIND_FLOAT and field.type.bitlen == 16]@
Expand Down Expand Up @@ -93,7 +97,7 @@ namespace DroneCAN
@[ end if]@
@(ind) chunk_cb(buffer, @(field.type.value_type.bitlen), ctx);
@[ elif field.type.value_type.category == field.type.value_type.CATEGORY_COMPOUND]@
@(ind) _encode_@(underscored_name(field.type.value_type))(buffer, msg.@('union.' if msg_union else '')@(field.name)[i], chunk_cb, ctx, @[if field == msg_fields[-1] and field.type.value_type.get_min_bitlen() < 8]tao && i==msg.@('union.' if msg_union else '')@(field.name)_len@[else]false@[end if]@);
@(ind) @(underscored_name(field.type.value_type))._encode_@(underscored_name(field.type.value_type))(buffer, msg.@('union.' if msg_union else '')@(field.name)[i], chunk_cb, ctx, @[if field == msg_fields[-1] and field.type.value_type.get_min_bitlen() < 8]tao&& i == msg.@('union.' if msg_union else '')@(field.name)_len@[else]false@[end if]@);
@[ end if]@
@{indent -= 1}@{ind = ' '*indent}@
@(ind)}
Expand All @@ -113,7 +117,7 @@ namespace DroneCAN
@{indent -= 1}@{ind = ' '*indent}@
@(ind)}

static void _decode_@(msg_underscored_name)(CanardRxTransfer transfer,ref uint32_t bit_ofs, @(msg_c_type) msg, bool tao) {
internal static void _decode_@(msg_underscored_name)(CanardRxTransfer transfer,ref uint32_t bit_ofs, @(msg_c_type) msg, bool tao) {
@{indent += 1}@{ind = ' '*indent}@

@[ if msg_union]@
Expand All @@ -131,7 +135,7 @@ namespace DroneCAN
@{indent += 1}@{ind = ' '*indent}@
@[ end if]@
@[ if field.type.category == field.type.CATEGORY_COMPOUND]@
@(ind)_decode_@(underscored_name(field.type))(transfer, ref bit_ofs, msg.@('union.' if msg_union else '')@(field.name), @('tao' if field == msg_fields[-1] else 'false'));
@(ind)@(underscored_name(field.type))._decode_@(underscored_name(field.type))(transfer, ref bit_ofs, msg.@('union.' if msg_union else '')@(field.name), @('tao' if field == msg_fields[-1] else 'false'));
@[ elif field.type.category == field.type.CATEGORY_PRIMITIVE]@
@[ if field.type.kind == field.type.KIND_FLOAT and field.type.bitlen == 16]@
@(ind){
Expand Down Expand Up @@ -176,7 +180,7 @@ namespace DroneCAN
@{indent += 1}@{ind = ' '*indent}@
@(ind)msg.@('union.' if msg_union else '')@(field.name)_len++;
@(ind)temp.Add(new @(dronecan_type_to_ctype(field.type.value_type))());
@(ind)_decode_@(underscored_name(field.type.value_type))(transfer, ref bit_ofs, temp[msg.@(field.name)_len - 1], @[if field == msg_fields[-1] and field.type.value_type.get_min_bitlen() < 8]tao && i==msg.@('union.' if msg_union else '')@(field.name)_len@[else]false@[end if]@);
@(ind)@(dronecan_type_to_ctype(field.type.value_type))._decode_@(underscored_name(field.type.value_type))(transfer, ref bit_ofs, temp[msg.@(field.name)_len - 1], @[if field == msg_fields[-1] and field.type.value_type.get_min_bitlen() < 8]tao && i==msg.@('union.' if msg_union else '')@(field.name)_len@[else]false@[end if]@);
@{indent -= 1}@{ind = ' '*indent}@
@(ind)}
@(ind)msg.@('union.' if msg_union else '')@(field.name) = temp.ToArray();
Expand All @@ -202,7 +206,7 @@ namespace DroneCAN
@[ end if]@
@(ind)bit_ofs += @(field.type.value_type.bitlen);
@[ elif field.type.value_type.category == field.type.value_type.CATEGORY_COMPOUND]@
@(ind)_decode_@(underscored_name(field.type.value_type))(transfer, ref bit_ofs, msg.@('union.' if msg_union else '')@(field.name)[i], @[if field == msg_fields[-1] and field.type.value_type.get_min_bitlen() < 8]tao && i==msg.@('union.' if msg_union else '')@(field.name)_len@[else]false@[end if]@);
@(ind)@(underscored_name(field.type.value_type))._decode_@(underscored_name(field.type.value_type))(transfer, ref bit_ofs, msg.@('union.' if msg_union else '')@(field.name)[i], @[if field == msg_fields[-1] and field.type.value_type.get_min_bitlen() < 8]tao && i==msg.@('union.' if msg_union else '')@(field.name)_len@[else]false@[end if]@);
@[ end if]@
@{indent -= 1}@{ind = ' '*indent}@
@(ind)}
Expand All @@ -229,4 +233,5 @@ namespace DroneCAN
@{indent -= 1}@{ind = ' '*indent}@
@(ind)}
@{indent -= 1}@{ind = ' '*indent}@
@(ind)}
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@ namespace DroneCAN
public partial class DroneCAN
{
//using uavcan.protocol.file.Path.cs
//using uavcan.protocol.file.EntryType.cs
//using uavcan.protocol.file.Error.cs
//using uavcan.protocol.file.EntryType.cs
public partial class uavcan_protocol_file_GetDirectoryEntryInfo_res: IDroneCANSerialize
{
public const int UAVCAN_PROTOCOL_FILE_GETDIRECTORYENTRYINFO_RES_MAX_PACK_SIZE = 204;
Expand Down
78 changes: 41 additions & 37 deletions ExtLibs/DroneCAN/out/src/ardupilot.equipment.power.BatteryCells.cs
Original file line number Diff line number Diff line change
Expand Up @@ -19,51 +19,55 @@
namespace DroneCAN
{
public partial class DroneCAN {
static void encode_ardupilot_equipment_power_BatteryCells(ardupilot_equipment_power_BatteryCells msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) {
uint8_t[] buffer = new uint8_t[8];
_encode_ardupilot_equipment_power_BatteryCells(buffer, msg, chunk_cb, ctx, !fdcan);
}

static uint32_t decode_ardupilot_equipment_power_BatteryCells(CanardRxTransfer transfer, ardupilot_equipment_power_BatteryCells msg, bool fdcan) {
uint32_t bit_ofs = 0;
_decode_ardupilot_equipment_power_BatteryCells(transfer, ref bit_ofs, msg, !fdcan);
return (bit_ofs+7)/8;
}

static void _encode_ardupilot_equipment_power_BatteryCells(uint8_t[] buffer, ardupilot_equipment_power_BatteryCells msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) {
memset(buffer,0,8);
canardEncodeScalar(buffer, 0, 5, msg.voltages_len);
chunk_cb(buffer, 5, ctx);
for (int i=0; i < msg.voltages_len; i++) {
memset(buffer,0,8);
{
uint16_t float16_val = canardConvertNativeFloatToFloat16(msg.voltages[i]);
canardEncodeScalar(buffer, 0, 16, float16_val);
}
chunk_cb(buffer, 16, ctx);
public partial class ardupilot_equipment_power_BatteryCells : IDroneCANSerialize
{
public static void encode_ardupilot_equipment_power_BatteryCells(ardupilot_equipment_power_BatteryCells msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) {
uint8_t[] buffer = new uint8_t[8];
_encode_ardupilot_equipment_power_BatteryCells(buffer, msg, chunk_cb, ctx, !fdcan);
}
memset(buffer,0,8);
canardEncodeScalar(buffer, 0, 16, msg.index);
chunk_cb(buffer, 16, ctx);
}

static void _decode_ardupilot_equipment_power_BatteryCells(CanardRxTransfer transfer,ref uint32_t bit_ofs, ardupilot_equipment_power_BatteryCells msg, bool tao) {
public static uint32_t decode_ardupilot_equipment_power_BatteryCells(CanardRxTransfer transfer, ardupilot_equipment_power_BatteryCells msg, bool fdcan) {
uint32_t bit_ofs = 0;
_decode_ardupilot_equipment_power_BatteryCells(transfer, ref bit_ofs, msg, !fdcan);
return (bit_ofs+7)/8;
}

canardDecodeScalar(transfer, bit_ofs, 5, false, ref msg.voltages_len);
bit_ofs += 5;
msg.voltages = new Single[msg.voltages_len];
for (int i=0; i < msg.voltages_len; i++) {
{
uint16_t float16_val = 0;
canardDecodeScalar(transfer, bit_ofs, 16, true, ref float16_val);
msg.voltages[i] = canardConvertFloat16ToNativeFloat(float16_val);
internal static void _encode_ardupilot_equipment_power_BatteryCells(uint8_t[] buffer, ardupilot_equipment_power_BatteryCells msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) {
memset(buffer,0,8);
canardEncodeScalar(buffer, 0, 5, msg.voltages_len);
chunk_cb(buffer, 5, ctx);
for (int i=0; i < msg.voltages_len; i++) {
memset(buffer,0,8);
{
uint16_t float16_val = canardConvertNativeFloatToFloat16(msg.voltages[i]);
canardEncodeScalar(buffer, 0, 16, float16_val);
}
chunk_cb(buffer, 16, ctx);
}
bit_ofs += 16;
memset(buffer,0,8);
canardEncodeScalar(buffer, 0, 16, msg.index);
chunk_cb(buffer, 16, ctx);
}

canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.index);
bit_ofs += 16;
internal static void _decode_ardupilot_equipment_power_BatteryCells(CanardRxTransfer transfer,ref uint32_t bit_ofs, ardupilot_equipment_power_BatteryCells msg, bool tao) {

canardDecodeScalar(transfer, bit_ofs, 5, false, ref msg.voltages_len);
bit_ofs += 5;
msg.voltages = new Single[msg.voltages_len];
for (int i=0; i < msg.voltages_len; i++) {
{
uint16_t float16_val = 0;
canardDecodeScalar(transfer, bit_ofs, 16, true, ref float16_val);
msg.voltages[i] = canardConvertFloat16ToNativeFloat(float16_val);
}
bit_ofs += 16;
}

canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.index);
bit_ofs += 16;

}
}
}
}
Loading

0 comments on commit 340a531

Please sign in to comment.