Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion ExtLibs/DroneCAN/build.bat
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,6 @@

python3 -m pip install dronecan empy pexpect --user

python3 ./canard_dsdlc/canard_dsdlc.py dsdl/dronecan dsdl/org dsdl/com dsdl/ardupilot dsdl/cuav dsdl/uavcan dsdl/mppt out
python3 ./canard_dsdlc/canard_dsdlc.py dsdl/dronecan dsdl/com dsdl/ardupilot dsdl/cuav dsdl/uavcan dsdl/mppt out

pause
14 changes: 7 additions & 7 deletions ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,9 @@
namespace_paths = [os.path.abspath(path) for path in args.namespace_dir]
build_dir = os.path.abspath(args.build_dir[0])

print(namespace_paths)
print(build_dir)
print(buildlist)
print("namespace_paths",namespace_paths)
print("build_dir",build_dir)
print("buildlist",buildlist)

os.chdir(os.path.dirname(__file__))
templates_dir = 'templates'
Expand Down Expand Up @@ -90,9 +90,9 @@ def build_message(msg_name):

buildlist = new_buildlist

from multiprocessing import Pool
#from multiprocessing import Pool

pool = Pool(2)
#pool = Pool(2)
builtlist = set()
if buildlist is not None:
for msg_name in buildlist:
Expand Down Expand Up @@ -122,8 +122,8 @@ def build_message(msg_name):
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('.','_'))

pool.close()
pool.join()
#pool.close()
#pool.join()

assert buildlist is None or not buildlist-builtlist, "%s not built" % (buildlist-builtlist,)

Expand Down
2 changes: 2 additions & 0 deletions ExtLibs/DroneCAN/canard_dsdlc/messages.cs
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@ public static (Type type,UInt16 msgid, ulong crcseed, Func<Byte[],int, object> c
(typeof(dronecan_remoteid_System), 20033, 0x9AC872F49BF32437, (b,s) => dronecan_remoteid_System.ByteArrayToDroneCANMsg(b,s)),
(typeof(dronecan_remoteid_OperatorID), 20034, 0x581E7FC7F03AF935, (b,s) => dronecan_remoteid_OperatorID.ByteArrayToDroneCANMsg(b,s)),
(typeof(dronecan_remoteid_ArmStatus), 20035, 0xFEDF72CCF06F3BDD, (b,s) => dronecan_remoteid_ArmStatus.ByteArrayToDroneCANMsg(b,s)),
(typeof(dronecan_remoteid_SecureCommand_req), 64, 0x126A47C9C17A8BD7, (b,s) => dronecan_remoteid_SecureCommand_req.ByteArrayToDroneCANMsg(b,s)),
(typeof(dronecan_remoteid_SecureCommand_res), 64, 0x126A47C9C17A8BD7, (b,s) => dronecan_remoteid_SecureCommand_res.ByteArrayToDroneCANMsg(b,s)),
(typeof(dronecan_sensors_hygrometer_Hygrometer), 1032, 0xCEB308892BF163E8, (b,s) => dronecan_sensors_hygrometer_Hygrometer.ByteArrayToDroneCANMsg(b,s)),
(typeof(com_hex_equipment_flow_Measurement), 20200, 0x6A908866BCB49C18, (b,s) => com_hex_equipment_flow_Measurement.ByteArrayToDroneCANMsg(b,s)),
(typeof(ardupilot_equipment_power_BatteryInfoAux), 20004, 0x7D7F49FC75484882, (b,s) => ardupilot_equipment_power_BatteryInfoAux.ByteArrayToDroneCANMsg(b,s)),
Expand Down
29 changes: 29 additions & 0 deletions ExtLibs/DroneCAN/dsdl/dronecan/remoteid/64.SecureCommand.uavcan
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
# DroneCAN version of MAVLink2 SECURE_COMMAND. Please see MAVLink2 spec for more details

uint32 sequence

uint32 SECURE_COMMAND_GET_SESSION_KEY = 0
uint32 SECURE_COMMAND_GET_REMOTEID_SESSION_KEY = 1
uint32 SECURE_COMMAND_REMOVE_PUBLIC_KEYS = 2
uint32 SECURE_COMMAND_GET_PUBLIC_KEYS = 3
uint32 SECURE_COMMAND_SET_PUBLIC_KEYS = 4
uint32 SECURE_COMMAND_GET_REMOTEID_CONFIG = 5
uint32 SECURE_COMMAND_SET_REMOTEID_CONFIG = 6
uint32 operation

uint8 sig_length
uint8[<=220] data

---

uint32 sequence
uint32 operation

uint8 RESULT_ACCEPTED = 0
uint8 RESULT_TEMPORARILY_REJECTED = 1
uint8 RESULT_DENIED = 2
uint8 RESULT_UNSUPPORTED = 3
uint8 RESULT_FAILED = 4
uint8 result

uint8[<=220] data
2 changes: 1 addition & 1 deletion ExtLibs/DroneCAN/dsdl/test.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

logging.basicConfig(stream=sys.stderr, level='DEBUG', format='%(levelname)s: %(message)s')

from uavcan import dsdl
from dronecan import dsdl

parsed = dsdl.parse_namespaces(['uavcan','com','ardupilot', 'dronecan']);
if parsed:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ uint8 COMMAND_TYPE_UNITLESS = 0 # [-1, 1]
uint8 COMMAND_TYPE_POSITION = 1 # meter or radian
uint8 COMMAND_TYPE_FORCE = 2 # Newton or Newton metre
uint8 COMMAND_TYPE_SPEED = 3 # meter per second or radian per second
uint8 COMMAND_TYPE_PWM = 4 # PWM microsecond signal
uint8 command_type

#
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
namespace DroneCAN
{
public partial class DroneCAN {

const double DRONECAN_REMOTEID_SECURECOMMAND_DT_ID = 64;
const double DRONECAN_REMOTEID_SECURECOMMAND_DT_SIG = 0x126A47C9C17A8BD7;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@

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_remoteid_SecureCommand_req: IDroneCANSerialize
{
public const int DRONECAN_REMOTEID_SECURECOMMAND_REQ_MAX_PACK_SIZE = 230;
public const ulong DRONECAN_REMOTEID_SECURECOMMAND_REQ_DT_SIG = 0x126A47C9C17A8BD7;
public const int DRONECAN_REMOTEID_SECURECOMMAND_REQ_DT_ID = 64;

public const double DRONECAN_REMOTEID_SECURECOMMAND_REQ_SECURE_COMMAND_GET_SESSION_KEY = 0; // saturated uint32
public const double DRONECAN_REMOTEID_SECURECOMMAND_REQ_SECURE_COMMAND_GET_REMOTEID_SESSION_KEY = 1; // saturated uint32
public const double DRONECAN_REMOTEID_SECURECOMMAND_REQ_SECURE_COMMAND_REMOVE_PUBLIC_KEYS = 2; // saturated uint32
public const double DRONECAN_REMOTEID_SECURECOMMAND_REQ_SECURE_COMMAND_GET_PUBLIC_KEYS = 3; // saturated uint32
public const double DRONECAN_REMOTEID_SECURECOMMAND_REQ_SECURE_COMMAND_SET_PUBLIC_KEYS = 4; // saturated uint32
public const double DRONECAN_REMOTEID_SECURECOMMAND_REQ_SECURE_COMMAND_GET_REMOTEID_CONFIG = 5; // saturated uint32
public const double DRONECAN_REMOTEID_SECURECOMMAND_REQ_SECURE_COMMAND_SET_REMOTEID_CONFIG = 6; // saturated uint32

public uint32_t sequence = new uint32_t();
public uint32_t operation = new uint32_t();
public uint8_t sig_length = new uint8_t();
public uint8_t data_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=220)] public uint8_t[] data = Enumerable.Range(1, 220).Select(i => new uint8_t()).ToArray();

public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx)
{
encode_dronecan_remoteid_SecureCommand_req(this, chunk_cb, ctx);
}

public void decode(CanardRxTransfer transfer)
{
decode_dronecan_remoteid_SecureCommand_req(transfer, this);
}

public static dronecan_remoteid_SecureCommand_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset)
{
var ans = new dronecan_remoteid_SecureCommand_req();
ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()));
return ans;
}
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@

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_remoteid_SecureCommand_res: IDroneCANSerialize
{
public const int DRONECAN_REMOTEID_SECURECOMMAND_RES_MAX_PACK_SIZE = 230;
public const ulong DRONECAN_REMOTEID_SECURECOMMAND_RES_DT_SIG = 0x126A47C9C17A8BD7;
public const int DRONECAN_REMOTEID_SECURECOMMAND_RES_DT_ID = 64;

public const double DRONECAN_REMOTEID_SECURECOMMAND_RES_RESULT_ACCEPTED = 0; // saturated uint8
public const double DRONECAN_REMOTEID_SECURECOMMAND_RES_RESULT_TEMPORARILY_REJECTED = 1; // saturated uint8
public const double DRONECAN_REMOTEID_SECURECOMMAND_RES_RESULT_DENIED = 2; // saturated uint8
public const double DRONECAN_REMOTEID_SECURECOMMAND_RES_RESULT_UNSUPPORTED = 3; // saturated uint8
public const double DRONECAN_REMOTEID_SECURECOMMAND_RES_RESULT_FAILED = 4; // saturated uint8

public uint32_t sequence = new uint32_t();
public uint32_t operation = new uint32_t();
public uint8_t result = new uint8_t();
public uint8_t data_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=220)] public uint8_t[] data = Enumerable.Range(1, 220).Select(i => new uint8_t()).ToArray();

public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx)
{
encode_dronecan_remoteid_SecureCommand_res(this, chunk_cb, ctx);
}

public void decode(CanardRxTransfer transfer)
{
decode_dronecan_remoteid_SecureCommand_res(transfer, this);
}

public static dronecan_remoteid_SecureCommand_res ByteArrayToDroneCANMsg(byte[] transfer, int startoffset)
{
var ans = new dronecan_remoteid_SecureCommand_res();
ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()));
return ans;
}
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ public partial class uavcan_equipment_actuator_Command: IDroneCANSerialize
public const double UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_POSITION = 1; // saturated uint8
public const double UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_FORCE = 2; // saturated uint8
public const double UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_SPEED = 3; // saturated uint8
public const double UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_PWM = 4; // saturated uint8

public uint8_t actuator_id = new uint8_t();
public uint8_t command_type = new uint8_t();
Expand Down
2 changes: 1 addition & 1 deletion ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix2.cs
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@ namespace DroneCAN
{
public partial class DroneCAN
{
//using uavcan.CoarseOrientation.cs
//using uavcan.Timestamp.cs
//using uavcan.CoarseOrientation.cs
public partial class uavcan_equipment_range_sensor_Measurement: IDroneCANSerialize
{
public const int UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_MAX_PACK_SIZE = 15;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,9 @@ namespace DroneCAN
{
public partial class DroneCAN
{
//using uavcan.protocol.HardwareVersion.cs
//using uavcan.protocol.SoftwareVersion.cs
//using uavcan.protocol.NodeStatus.cs
//using uavcan.protocol.HardwareVersion.cs
public partial class uavcan_protocol_GetNodeInfo_res: IDroneCANSerialize
{
public const int UAVCAN_PROTOCOL_GETNODEINFO_RES_MAX_PACK_SIZE = 377;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@ namespace DroneCAN
public partial class DroneCAN
{
//using uavcan.protocol.file.Error.cs
//using uavcan.protocol.file.EntryType.cs
//using uavcan.protocol.file.Path.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
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.param.NumericValue.cs
//using uavcan.protocol.param.Value.cs
//using uavcan.protocol.param.NumericValue.cs
public partial class uavcan_protocol_param_GetSet_res: IDroneCANSerialize
{
public const int UAVCAN_PROTOCOL_PARAM_GETSET_RES_MAX_PACK_SIZE = 371;
Expand Down
81 changes: 81 additions & 0 deletions ExtLibs/DroneCAN/out/src/dronecan.remoteid.SecureCommand_req.cs
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@

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 {
static void encode_dronecan_remoteid_SecureCommand_req(dronecan_remoteid_SecureCommand_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx) {
uint8_t[] buffer = new uint8_t[8];
_encode_dronecan_remoteid_SecureCommand_req(buffer, msg, chunk_cb, ctx, true);
}

static uint32_t decode_dronecan_remoteid_SecureCommand_req(CanardRxTransfer transfer, dronecan_remoteid_SecureCommand_req msg) {
uint32_t bit_ofs = 0;
_decode_dronecan_remoteid_SecureCommand_req(transfer, ref bit_ofs, msg, true);
return (bit_ofs+7)/8;
}

static void _encode_dronecan_remoteid_SecureCommand_req(uint8_t[] buffer, dronecan_remoteid_SecureCommand_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) {
memset(buffer,0,8);
canardEncodeScalar(buffer, 0, 32, msg.sequence);
chunk_cb(buffer, 32, ctx);
memset(buffer,0,8);
canardEncodeScalar(buffer, 0, 32, msg.operation);
chunk_cb(buffer, 32, ctx);
memset(buffer,0,8);
canardEncodeScalar(buffer, 0, 8, msg.sig_length);
chunk_cb(buffer, 8, 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);
}
}

static void _decode_dronecan_remoteid_SecureCommand_req(CanardRxTransfer transfer,ref uint32_t bit_ofs, dronecan_remoteid_SecureCommand_req msg, bool tao) {

canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.sequence);
bit_ofs += 32;

canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.operation);
bit_ofs += 32;

canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.sig_length);
bit_ofs += 8;

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;
}

}
}
}
Loading