From a521dda91599ee20047930c07e1172460a2334c6 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Tue, 11 Jul 2023 10:24:49 +1000 Subject: [PATCH] DroneCan: update from dsdl --- ExtLibs/DroneCAN/DroneCAN.cs | 12 +- ExtLibs/DroneCAN/build.bat | 6 +- ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py | 19 +-- ExtLibs/DroneCAN/canard_dsdlc/messages.cs | 36 ++++++ ExtLibs/DroneCAN/canard_dsdlc/templates/msg.h | 6 +- .../.github/workflows/test_regression.yml | 27 +++++ ExtLibs/DroneCAN/dsdl/README.md | 17 +++ .../indication/20007.NotifyState.uavcan | 2 + .../com/himark/servo/2018.ServoCmd.uavcan | 9 ++ .../com/himark/servo/2019.ServoInfo.uavcan | 34 ++++++ .../com/hobbywing/esc/20013.GetEscID.uavcan | 5 + .../com/hobbywing/esc/20050.StatusMsg1.uavcan | 5 + .../com/hobbywing/esc/20051.StatusMsg2.uavcan | 6 + .../com/hobbywing/esc/20052.StatusMsg3.uavcan | 5 + .../com/hobbywing/esc/20100.RawCommand.uavcan | 3 + .../dsdl/com/hobbywing/esc/210.SetID.uavcan | 9 ++ .../dsdl/com/hobbywing/esc/211.SetBaud.uavcan | 11 ++ .../dsdl/com/hobbywing/esc/212.SetLED.uavcan | 21 ++++ .../com/hobbywing/esc/213.SetDirection.uavcan | 9 ++ .../esc/214.SetReportingFrequency.uavcan | 25 ++++ .../esc/215.SetThrottleSource.uavcan | 9 ++ .../com/hobbywing/esc/216.SelfTest.uavcan | 7 ++ .../com/hobbywing/esc/217.SetAngle.uavcan | 9 ++ .../esc/241.GetMaintenanceInformation.uavcan | 9 ++ .../hobbywing/esc/242.GetMajorConfig.uavcan | 19 +++ .../DroneCAN/dsdl/com/hobbywing/esc/README.md | 12 ++ .../dsdl/com/xacti/20305.GnssStatus.uavcan | 44 +++++++ .../dsdl/com/xacti/20306.GnssStatusReq.uavcan | 13 ++ .../xacti/20402.GimbalAttitudeStatus.uavcan | 14 +++ .../com/xacti/20407.CopterAttStatus.uavcan | 22 ++++ .../com/xacti/20554.GimbalControlData.uavcan | 34 ++++++ .../dsdl/dronecan/protocol/342.Stats.uavcan | 17 +++ .../dronecan/protocol/343.CanStats.uavcan | 15 +++ .../dronecan/sensors/rc/1140.RCInput.uavcan | 9 ++ .../DroneCAN/dsdl/tests/test_regression.sh | 16 +++ .../uavcan/equipment/esc/1034.Status.uavcan | 2 +- .../protocol/param/10.ExecuteOpcode.uavcan | 5 + .../uavcan/protocol/param/11.GetSet.uavcan | 3 + .../dsdl/uavcan/tunnel/3001.Targetted.uavcan | 23 ++++ .../ardupilot.equipment.power.BatteryCells.cs | 1 - ...pilot.equipment.power.BatteryContinuous.cs | 1 - ...rdupilot.equipment.power.BatteryInfoAux.cs | 1 - ...dupilot.equipment.power.BatteryPeriodic.cs | 1 - ...ot.equipment.proximity_sensor.Proximity.cs | 1 - ....equipment.trafficmonitor.TrafficReport.cs | 1 - .../out/include/ardupilot.gnss.Heading.cs | 1 - .../ardupilot.gnss.MovingBaselineData.cs | 1 - .../include/ardupilot.gnss.RelPosHeading.cs | 1 - .../out/include/ardupilot.gnss.Status.cs | 1 - .../include/ardupilot.indication.Button.cs | 1 - .../ardupilot.indication.NotifyState.cs | 3 +- .../ardupilot.indication.SafetyState.cs | 1 - .../com.hex.equipment.flow.Measurement.cs | 1 - .../out/include/com.himark.servo.ServoCmd.cs | 47 ++++++++ .../out/include/com.himark.servo.ServoInfo.cs | 58 +++++++++ .../out/include/com.hobbywing.esc.GetEscID.cs | 47 ++++++++ ...hobbywing.esc.GetMaintenanceInformation.cs | 8 ++ ...ywing.esc.GetMaintenanceInformation_req.cs | 49 ++++++++ ...ywing.esc.GetMaintenanceInformation_res.cs | 48 ++++++++ .../com.hobbywing.esc.GetMajorConfig.cs | 8 ++ .../com.hobbywing.esc.GetMajorConfig_req.cs | 47 ++++++++ .../com.hobbywing.esc.GetMajorConfig_res.cs | 55 +++++++++ .../include/com.hobbywing.esc.RawCommand.cs | 47 ++++++++ .../out/include/com.hobbywing.esc.SelfTest.cs | 8 ++ .../include/com.hobbywing.esc.SelfTest_req.cs | 46 +++++++ .../include/com.hobbywing.esc.SelfTest_res.cs | 50 ++++++++ .../out/include/com.hobbywing.esc.SetAngle.cs | 8 ++ .../include/com.hobbywing.esc.SetAngle_req.cs | 48 ++++++++ .../include/com.hobbywing.esc.SetAngle_res.cs | 48 ++++++++ .../out/include/com.hobbywing.esc.SetBaud.cs | 8 ++ .../include/com.hobbywing.esc.SetBaud_req.cs | 54 +++++++++ .../include/com.hobbywing.esc.SetBaud_res.cs | 46 +++++++ .../include/com.hobbywing.esc.SetDirection.cs | 8 ++ .../com.hobbywing.esc.SetDirection_req.cs | 51 ++++++++ .../com.hobbywing.esc.SetDirection_res.cs | 47 ++++++++ .../out/include/com.hobbywing.esc.SetID.cs | 8 ++ .../include/com.hobbywing.esc.SetID_req.cs | 48 ++++++++ .../include/com.hobbywing.esc.SetID_res.cs | 48 ++++++++ .../out/include/com.hobbywing.esc.SetLED.cs | 8 ++ .../include/com.hobbywing.esc.SetLED_req.cs | 58 +++++++++ .../include/com.hobbywing.esc.SetLED_res.cs | 49 ++++++++ ...com.hobbywing.esc.SetReportingFrequency.cs | 8 ++ ...hobbywing.esc.SetReportingFrequency_req.cs | 61 ++++++++++ ...hobbywing.esc.SetReportingFrequency_res.cs | 49 ++++++++ .../com.hobbywing.esc.SetThrottleSource.cs | 8 ++ ...com.hobbywing.esc.SetThrottleSource_req.cs | 50 ++++++++ ...com.hobbywing.esc.SetThrottleSource_res.cs | 47 ++++++++ .../include/com.hobbywing.esc.StatusMsg1.cs | 49 ++++++++ .../include/com.hobbywing.esc.StatusMsg2.cs | 49 ++++++++ .../include/com.hobbywing.esc.StatusMsg3.cs | 49 ++++++++ .../include/com.volz.servo.ActuatorStatus.cs | 1 - .../out/include/com.xacti.CopterAttStatus.cs | 48 ++++++++ .../include/com.xacti.GimbalAttitudeStatus.cs | 52 ++++++++ .../include/com.xacti.GimbalControlData.cs | 50 ++++++++ .../out/include/com.xacti.GnssStatus.cs | 58 +++++++++ .../out/include/com.xacti.GnssStatusReq.cs | 47 ++++++++ .../out/include/cuav.equipment.power.CBAT.cs | 1 - .../out/include/dronecan.protocol.CanStats.cs | 57 +++++++++ .../out/include/dronecan.protocol.Stats.cs | 58 +++++++++ .../include/dronecan.remoteid.ArmStatus.cs | 1 - .../out/include/dronecan.remoteid.BasicID.cs | 1 - .../out/include/dronecan.remoteid.Location.cs | 1 - .../include/dronecan.remoteid.OperatorID.cs | 1 - .../dronecan.remoteid.SecureCommand_req.cs | 1 - .../dronecan.remoteid.SecureCommand_res.cs | 1 - .../out/include/dronecan.remoteid.SelfID.cs | 1 - .../out/include/dronecan.remoteid.System.cs | 1 - .../dronecan.sensors.hygrometer.Hygrometer.cs | 1 - .../include/dronecan.sensors.rc.RCInput.cs | 53 +++++++++ .../out/include/mppt.OutputEnable_req.cs | 1 - .../out/include/mppt.OutputEnable_res.cs | 1 - ExtLibs/DroneCAN/out/include/mppt.Stream.cs | 1 - .../out/include/uavcan.CoarseOrientation.cs | 1 - .../DroneCAN/out/include/uavcan.Timestamp.cs | 1 - .../uavcan.equipment.actuator.ArrayCommand.cs | 1 - .../uavcan.equipment.actuator.Command.cs | 1 - .../uavcan.equipment.actuator.Status.cs | 1 - ...an.equipment.ahrs.MagneticFieldStrength.cs | 1 - ...n.equipment.ahrs.MagneticFieldStrength2.cs | 1 - .../include/uavcan.equipment.ahrs.RawIMU.cs | 1 - .../include/uavcan.equipment.ahrs.Solution.cs | 1 - ...uavcan.equipment.air_data.AngleOfAttack.cs | 1 - ...an.equipment.air_data.IndicatedAirspeed.cs | 1 - .../uavcan.equipment.air_data.RawAirData.cs | 1 - .../uavcan.equipment.air_data.Sideslip.cs | 1 - ...avcan.equipment.air_data.StaticPressure.cs | 1 - ...an.equipment.air_data.StaticTemperature.cs | 1 - .../uavcan.equipment.air_data.TrueAirspeed.cs | 1 - ....equipment.camera_gimbal.AngularCommand.cs | 1 - ...n.equipment.camera_gimbal.GEOPOICommand.cs | 1 - .../uavcan.equipment.camera_gimbal.Mode.cs | 1 - .../uavcan.equipment.camera_gimbal.Status.cs | 1 - .../uavcan.equipment.device.Temperature.cs | 1 - .../uavcan.equipment.esc.RPMCommand.cs | 1 - .../uavcan.equipment.esc.RawCommand.cs | 1 - .../include/uavcan.equipment.esc.Status.cs | 1 - .../uavcan.equipment.gnss.Auxiliary.cs | 1 - ...can.equipment.gnss.ECEFPositionVelocity.cs | 1 - .../out/include/uavcan.equipment.gnss.Fix.cs | 1 - .../out/include/uavcan.equipment.gnss.Fix2.cs | 3 +- .../uavcan.equipment.gnss.RTCMStream.cs | 1 - .../uavcan.equipment.hardpoint.Command.cs | 1 - .../uavcan.equipment.hardpoint.Status.cs | 1 - .../uavcan.equipment.ice.FuelTankStatus.cs | 1 - ...ipment.ice.reciprocating.CylinderStatus.cs | 1 - ...vcan.equipment.ice.reciprocating.Status.cs | 1 - ...uavcan.equipment.indication.BeepCommand.cs | 1 - ...vcan.equipment.indication.LightsCommand.cs | 1 - .../uavcan.equipment.indication.RGB565.cs | 1 - ...equipment.indication.SingleLightCommand.cs | 1 - .../uavcan.equipment.power.BatteryInfo.cs | 1 - .../uavcan.equipment.power.CircuitStatus.cs | 1 - ...quipment.power.PrimaryPowerSupplyStatus.cs | 1 - ...vcan.equipment.range_sensor.Measurement.cs | 1 - .../uavcan.equipment.safety.ArmingStatus.cs | 1 - ...can.navigation.GlobalNavigationSolution.cs | 1 - .../uavcan.protocol.AccessCommandShell_req.cs | 1 - .../uavcan.protocol.AccessCommandShell_res.cs | 1 - .../include/uavcan.protocol.CANIfaceStats.cs | 1 - .../include/uavcan.protocol.DataTypeKind.cs | 1 - .../uavcan.protocol.GetDataTypeInfo_req.cs | 1 - .../uavcan.protocol.GetDataTypeInfo_res.cs | 1 - .../uavcan.protocol.GetNodeInfo_req.cs | 1 - .../uavcan.protocol.GetNodeInfo_res.cs | 3 +- .../uavcan.protocol.GetTransportStats_req.cs | 1 - .../uavcan.protocol.GetTransportStats_res.cs | 1 - .../include/uavcan.protocol.GlobalTimeSync.cs | 1 - .../uavcan.protocol.HardwareVersion.cs | 1 - .../out/include/uavcan.protocol.NodeStatus.cs | 1 - .../out/include/uavcan.protocol.Panic.cs | 1 - .../uavcan.protocol.RestartNode_req.cs | 1 - .../uavcan.protocol.RestartNode_res.cs | 1 - .../uavcan.protocol.SoftwareVersion.cs | 1 - .../include/uavcan.protocol.debug.KeyValue.cs | 1 - .../include/uavcan.protocol.debug.LogLevel.cs | 1 - .../uavcan.protocol.debug.LogMessage.cs | 1 - ...can.protocol.dynamic_node_id.Allocation.cs | 1 - ...ynamic_node_id.server.AppendEntries_req.cs | 1 - ...ynamic_node_id.server.AppendEntries_res.cs | 1 - ...otocol.dynamic_node_id.server.Discovery.cs | 1 - ...n.protocol.dynamic_node_id.server.Entry.cs | 1 - ....dynamic_node_id.server.RequestVote_req.cs | 1 - ....dynamic_node_id.server.RequestVote_res.cs | 1 - .../uavcan.protocol.enumeration.Begin_req.cs | 1 - .../uavcan.protocol.enumeration.Begin_res.cs | 1 - .../uavcan.protocol.enumeration.Indication.cs | 1 - ...n.protocol.file.BeginFirmwareUpdate_req.cs | 1 - ...n.protocol.file.BeginFirmwareUpdate_res.cs | 1 - .../uavcan.protocol.file.Delete_req.cs | 1 - .../uavcan.protocol.file.Delete_res.cs | 1 - .../include/uavcan.protocol.file.EntryType.cs | 1 - .../out/include/uavcan.protocol.file.Error.cs | 1 - ...protocol.file.GetDirectoryEntryInfo_req.cs | 1 - ...protocol.file.GetDirectoryEntryInfo_res.cs | 3 +- .../uavcan.protocol.file.GetInfo_req.cs | 1 - .../uavcan.protocol.file.GetInfo_res.cs | 1 - .../out/include/uavcan.protocol.file.Path.cs | 1 - .../include/uavcan.protocol.file.Read_req.cs | 1 - .../include/uavcan.protocol.file.Read_res.cs | 1 - .../include/uavcan.protocol.file.Write_req.cs | 1 - .../include/uavcan.protocol.file.Write_res.cs | 1 - .../include/uavcan.protocol.param.Empty.cs | 1 - ...uavcan.protocol.param.ExecuteOpcode_req.cs | 1 - ...uavcan.protocol.param.ExecuteOpcode_res.cs | 1 - .../uavcan.protocol.param.GetSet_req.cs | 1 - .../uavcan.protocol.param.GetSet_res.cs | 3 +- .../uavcan.protocol.param.NumericValue.cs | 1 - .../include/uavcan.protocol.param.Value.cs | 1 - .../out/include/uavcan.tunnel.Broadcast.cs | 1 - .../out/include/uavcan.tunnel.Call_req.cs | 1 - .../out/include/uavcan.tunnel.Call_res.cs | 1 - .../out/include/uavcan.tunnel.Protocol.cs | 1 - .../out/include/uavcan.tunnel.SerialConfig.cs | 1 - .../out/include/uavcan.tunnel.Targetted.cs | 55 +++++++++ .../out/src/com.himark.servo.ServoCmd.cs | 63 ++++++++++ .../out/src/com.himark.servo.ServoInfo.cs | 94 +++++++++++++++ .../out/src/com.hobbywing.esc.GetEscID.cs | 63 ++++++++++ ...ywing.esc.GetMaintenanceInformation_req.cs | 46 +++++++ ...ywing.esc.GetMaintenanceInformation_res.cs | 52 ++++++++ .../com.hobbywing.esc.GetMajorConfig_req.cs | 46 +++++++ .../com.hobbywing.esc.GetMajorConfig_res.cs | 98 +++++++++++++++ .../out/src/com.hobbywing.esc.RawCommand.cs | 63 ++++++++++ .../out/src/com.hobbywing.esc.SelfTest_req.cs | 40 +++++++ .../out/src/com.hobbywing.esc.SelfTest_res.cs | 46 +++++++ .../out/src/com.hobbywing.esc.SetAngle_req.cs | 52 ++++++++ .../out/src/com.hobbywing.esc.SetAngle_res.cs | 69 +++++++++++ .../out/src/com.hobbywing.esc.SetBaud_req.cs | 46 +++++++ .../out/src/com.hobbywing.esc.SetBaud_res.cs | 40 +++++++ .../src/com.hobbywing.esc.SetDirection_req.cs | 46 +++++++ .../src/com.hobbywing.esc.SetDirection_res.cs | 46 +++++++ .../out/src/com.hobbywing.esc.SetID_req.cs | 52 ++++++++ .../out/src/com.hobbywing.esc.SetID_res.cs | 52 ++++++++ .../out/src/com.hobbywing.esc.SetLED_req.cs | 58 +++++++++ .../out/src/com.hobbywing.esc.SetLED_res.cs | 58 +++++++++ ...hobbywing.esc.SetReportingFrequency_req.cs | 58 +++++++++ ...hobbywing.esc.SetReportingFrequency_res.cs | 58 +++++++++ ...com.hobbywing.esc.SetThrottleSource_req.cs | 46 +++++++ ...com.hobbywing.esc.SetThrottleSource_res.cs | 46 +++++++ .../out/src/com.hobbywing.esc.StatusMsg1.cs | 58 +++++++++ .../out/src/com.hobbywing.esc.StatusMsg2.cs | 58 +++++++++ .../out/src/com.hobbywing.esc.StatusMsg3.cs | 58 +++++++++ .../out/src/com.xacti.CopterAttStatus.cs | 80 +++++++++++++ .../out/src/com.xacti.GimbalAttitudeStatus.cs | 76 ++++++++++++ .../out/src/com.xacti.GimbalControlData.cs | 64 ++++++++++ .../DroneCAN/out/src/com.xacti.GnssStatus.cs | 112 ++++++++++++++++++ .../out/src/com.xacti.GnssStatusReq.cs | 46 +++++++ .../out/src/dronecan.protocol.CanStats.cs | 106 +++++++++++++++++ .../out/src/dronecan.protocol.Stats.cs | 112 ++++++++++++++++++ .../out/src/dronecan.sensors.rc.RCInput.cs | 81 +++++++++++++ .../out/src/uavcan.tunnel.Targetted.cs | 90 ++++++++++++++ 250 files changed, 4723 insertions(+), 147 deletions(-) create mode 100644 ExtLibs/DroneCAN/dsdl/.github/workflows/test_regression.yml create mode 100644 ExtLibs/DroneCAN/dsdl/com/himark/servo/2018.ServoCmd.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/himark/servo/2019.ServoInfo.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20013.GetEscID.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20050.StatusMsg1.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20051.StatusMsg2.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20052.StatusMsg3.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20100.RawCommand.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/210.SetID.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/211.SetBaud.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/212.SetLED.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/213.SetDirection.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/214.SetReportingFrequency.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/215.SetThrottleSource.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/216.SelfTest.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/217.SetAngle.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/241.GetMaintenanceInformation.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/242.GetMajorConfig.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/README.md create mode 100644 ExtLibs/DroneCAN/dsdl/com/xacti/20305.GnssStatus.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/xacti/20306.GnssStatusReq.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/xacti/20402.GimbalAttitudeStatus.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/xacti/20407.CopterAttStatus.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/com/xacti/20554.GimbalControlData.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/dronecan/protocol/342.Stats.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/dronecan/protocol/343.CanStats.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/dronecan/sensors/rc/1140.RCInput.uavcan create mode 100644 ExtLibs/DroneCAN/dsdl/tests/test_regression.sh create mode 100644 ExtLibs/DroneCAN/dsdl/uavcan/tunnel/3001.Targetted.uavcan create mode 100644 ExtLibs/DroneCAN/out/include/com.himark.servo.ServoCmd.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.himark.servo.ServoInfo.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetEscID.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMaintenanceInformation.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMaintenanceInformation_req.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMaintenanceInformation_res.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMajorConfig.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMajorConfig_req.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMajorConfig_res.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.RawCommand.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SelfTest.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SelfTest_req.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SelfTest_res.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetAngle.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetAngle_req.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetAngle_res.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetBaud.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetBaud_req.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetBaud_res.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetDirection.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetDirection_req.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetDirection_res.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetID.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetID_req.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetID_res.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetLED.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetLED_req.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetLED_res.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetReportingFrequency.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetReportingFrequency_req.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetReportingFrequency_res.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetThrottleSource.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetThrottleSource_req.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetThrottleSource_res.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.StatusMsg1.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.StatusMsg2.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.hobbywing.esc.StatusMsg3.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.xacti.CopterAttStatus.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.xacti.GimbalAttitudeStatus.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.xacti.GimbalControlData.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.xacti.GnssStatus.cs create mode 100644 ExtLibs/DroneCAN/out/include/com.xacti.GnssStatusReq.cs create mode 100644 ExtLibs/DroneCAN/out/include/dronecan.protocol.CanStats.cs create mode 100644 ExtLibs/DroneCAN/out/include/dronecan.protocol.Stats.cs create mode 100644 ExtLibs/DroneCAN/out/include/dronecan.sensors.rc.RCInput.cs create mode 100644 ExtLibs/DroneCAN/out/include/uavcan.tunnel.Targetted.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.himark.servo.ServoCmd.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.himark.servo.ServoInfo.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetEscID.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMaintenanceInformation_req.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMaintenanceInformation_res.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMajorConfig_req.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMajorConfig_res.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.RawCommand.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SelfTest_req.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SelfTest_res.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetAngle_req.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetAngle_res.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetBaud_req.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetBaud_res.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetDirection_req.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetDirection_res.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetID_req.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetID_res.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetLED_req.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetLED_res.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetReportingFrequency_req.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetReportingFrequency_res.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetThrottleSource_req.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetThrottleSource_res.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg1.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg2.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg3.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.xacti.CopterAttStatus.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.xacti.GimbalAttitudeStatus.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.xacti.GimbalControlData.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.xacti.GnssStatus.cs create mode 100644 ExtLibs/DroneCAN/out/src/com.xacti.GnssStatusReq.cs create mode 100644 ExtLibs/DroneCAN/out/src/dronecan.protocol.CanStats.cs create mode 100644 ExtLibs/DroneCAN/out/src/dronecan.protocol.Stats.cs create mode 100644 ExtLibs/DroneCAN/out/src/dronecan.sensors.rc.RCInput.cs create mode 100644 ExtLibs/DroneCAN/out/src/uavcan.tunnel.Targetted.cs diff --git a/ExtLibs/DroneCAN/DroneCAN.cs b/ExtLibs/DroneCAN/DroneCAN.cs index 7900d20d11..53da20fa1b 100644 --- a/ExtLibs/DroneCAN/DroneCAN.cs +++ b/ExtLibs/DroneCAN/DroneCAN.cs @@ -73,6 +73,12 @@ public static bool testconversion(T input, byte bitlength, bool signed, byte private Stream sr; DateTime uptime = DateTime.Now; + public byte TransferID + { + get { return transferID; } + set { transferID = value; } + } + /// /// Read a line from the underlying stream /// @@ -1326,10 +1332,10 @@ public void WriteToStreamSLCAN(string slcan) { var lines = slcan.Split(new[] { '\r' }, StringSplitOptions.RemoveEmptyEntries); - lines = lines.Select((x, i) => new {index = i, value = x}) + /*lines = lines.Select((x, i) => new {index = i, value = x}) .GroupBy(x => x.index / 10) .Select(x => x.Select(v => v.value).Aggregate((i, j) => i + "\r" + j)).ToArray(); - + */ foreach (var line in lines) { lock (sr_lock) @@ -1337,7 +1343,7 @@ public void WriteToStreamSLCAN(string slcan) if (sr.CanWrite) { sr.Write(ASCIIEncoding.ASCII.GetBytes(line + '\r'), 0, line.Length + 1); - + sr.Flush(); try { logfilesemaphore.Wait(); diff --git a/ExtLibs/DroneCAN/build.bat b/ExtLibs/DroneCAN/build.bat index 4987b0408d..2100443753 100644 --- a/ExtLibs/DroneCAN/build.bat +++ b/ExtLibs/DroneCAN/build.bat @@ -2,6 +2,10 @@ python3 -m pip install dronecan empy pexpect --user -python3 ./canard_dsdlc/canard_dsdlc.py dsdl/dronecan dsdl/com dsdl/ardupilot dsdl/cuav dsdl/uavcan dsdl/mppt out +python3 -m pip install --upgrade dronecan + +cd canard_dsdlc + +python3 canard_dsdlc.py ../dsdl/dronecan ../dsdl/com ../dsdl/ardupilot ../dsdl/cuav ../dsdl/uavcan ../dsdl/mppt ../out pause \ No newline at end of file diff --git a/ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py b/ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py index f7d4e42e9e..7ebdfd0a9d 100644 --- a/ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py +++ b/ExtLibs/DroneCAN/canard_dsdlc/canard_dsdlc.py @@ -74,6 +74,7 @@ def build_message(msg_name): 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: @@ -90,15 +91,15 @@ def build_message(msg_name): buildlist = new_buildlist - #from multiprocessing import Pool + from multiprocessing import Pool - #pool = Pool(2) + 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) + 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: @@ -108,10 +109,12 @@ 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('.','_')) 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,)) + #builtlist.add(msg_name) + pool.apply_async(build_message, (msg_name,)) build_message(msg_name) msg = message_dict[msg_name] print (dir(msg)) @@ -122,8 +125,8 @@ def build_message(msg_name): 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() + pool.close() + pool.join() assert buildlist is None or not buildlist-builtlist, "%s not built" % (buildlist-builtlist,) diff --git a/ExtLibs/DroneCAN/canard_dsdlc/messages.cs b/ExtLibs/DroneCAN/canard_dsdlc/messages.cs index fdb2c14439..15e6385890 100644 --- a/ExtLibs/DroneCAN/canard_dsdlc/messages.cs +++ b/ExtLibs/DroneCAN/canard_dsdlc/messages.cs @@ -2,6 +2,8 @@ namespace DroneCAN { public partial class DroneCAN { public static (Type type,UInt16 msgid, ulong crcseed, Func convert)[] MSG_INFO = { + (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)), (typeof(dronecan_remoteid_Location), 20031, 0xEAA3A2C5BCB14CAA, (b,s,fd) => dronecan_remoteid_Location.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(dronecan_remoteid_SelfID), 20032, 0x59BE81DC4C06A185, (b,s,fd) => dronecan_remoteid_SelfID.ByteArrayToDroneCANMsg(b,s,fd)), @@ -11,8 +13,41 @@ 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_rc_RCInput), 1140, 0x771555E596AAB4CF, (b,s,fd) => dronecan_sensors_rc_RCInput.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)), + (typeof(com_hobbywing_esc_GetEscID), 20013, 0x00004E2D, (b,s,fd) => com_hobbywing_esc_GetEscID.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_StatusMsg1), 20050, 0x813B3E2C4AD670E, (b,s,fd) => com_hobbywing_esc_StatusMsg1.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_StatusMsg2), 20051, 0x1675DA01C3B91297, (b,s,fd) => com_hobbywing_esc_StatusMsg2.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_StatusMsg3), 20052, 0x24919CD1EB34ECE9, (b,s,fd) => com_hobbywing_esc_StatusMsg3.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_RawCommand), 20100, 0xBDF086C79F6640AD, (b,s,fd) => com_hobbywing_esc_RawCommand.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetID_req), 210, 0xC323CB5E9EC2B6F7, (b,s,fd) => com_hobbywing_esc_SetID_req.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetID_res), 210, 0xC323CB5E9EC2B6F7, (b,s,fd) => com_hobbywing_esc_SetID_res.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetBaud_req), 211, 0xADA98653B52DE435, (b,s,fd) => com_hobbywing_esc_SetBaud_req.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetBaud_res), 211, 0xADA98653B52DE435, (b,s,fd) => com_hobbywing_esc_SetBaud_res.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetLED_req), 212, 0xB493BD48C0853EE5, (b,s,fd) => com_hobbywing_esc_SetLED_req.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetLED_res), 212, 0xB493BD48C0853EE5, (b,s,fd) => com_hobbywing_esc_SetLED_res.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetDirection_req), 213, 0x9D793111D262BA68, (b,s,fd) => com_hobbywing_esc_SetDirection_req.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetDirection_res), 213, 0x9D793111D262BA68, (b,s,fd) => com_hobbywing_esc_SetDirection_res.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetReportingFrequency_req), 214, 0x1FD0404420983DEB, (b,s,fd) => com_hobbywing_esc_SetReportingFrequency_req.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetReportingFrequency_res), 214, 0x1FD0404420983DEB, (b,s,fd) => com_hobbywing_esc_SetReportingFrequency_res.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetThrottleSource_req), 215, 0xC248FAAEFE5E29A, (b,s,fd) => com_hobbywing_esc_SetThrottleSource_req.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetThrottleSource_res), 215, 0xC248FAAEFE5E29A, (b,s,fd) => com_hobbywing_esc_SetThrottleSource_res.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SelfTest_req), 216, 0xC48D4DE61C5295DF, (b,s,fd) => com_hobbywing_esc_SelfTest_req.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SelfTest_res), 216, 0xC48D4DE61C5295DF, (b,s,fd) => com_hobbywing_esc_SelfTest_res.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetAngle_req), 217, 0x81D9B10761C28E0A, (b,s,fd) => com_hobbywing_esc_SetAngle_req.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_SetAngle_res), 217, 0x81D9B10761C28E0A, (b,s,fd) => com_hobbywing_esc_SetAngle_res.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_hobbywing_esc_GetMaintenanceInformation_req), 241, 0xB81DBD4EC9A5977D, (b,s,fd) => com_hobbywing_esc_GetMaintenanceInformation_req.ByteArrayToDroneCANMsg(b,s,fd)), + (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_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)), + (typeof(com_xacti_GimbalAttitudeStatus), 20402, 0xEB428B6C25832692, (b,s,fd) => com_xacti_GimbalAttitudeStatus.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_xacti_CopterAttStatus), 20407, 0x6C1F30F1893763B1, (b,s,fd) => com_xacti_CopterAttStatus.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(com_xacti_GimbalControlData), 20554, 0x3B058FA5B150C5BE, (b,s,fd) => com_xacti_GimbalControlData.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(ardupilot_equipment_power_BatteryInfoAux), 20004, 0x7D7F49FC75484882, (b,s,fd) => ardupilot_equipment_power_BatteryInfoAux.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(ardupilot_equipment_power_BatteryContinuous), 20010, 0x756B561340D5E4AE, (b,s,fd) => ardupilot_equipment_power_BatteryContinuous.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(ardupilot_equipment_power_BatteryPeriodic), 20011, 0xF012494E97358D2, (b,s,fd) => ardupilot_equipment_power_BatteryPeriodic.ByteArrayToDroneCANMsg(b,s,fd)), @@ -105,6 +140,7 @@ public static (Type type,UInt16 msgid, ulong crcseed, Func uavcan_protocol_param_GetSet_res.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(uavcan_tunnel_Broadcast), 2010, 0x5AA2D4D9CF4B1E85, (b,s,fd) => uavcan_tunnel_Broadcast.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(uavcan_tunnel_SerialConfig), 2011, 0x4237AACEE87E82AD, (b,s,fd) => uavcan_tunnel_SerialConfig.ByteArrayToDroneCANMsg(b,s,fd)), + (typeof(uavcan_tunnel_Targetted), 3001, 0xB138E7EA72A2A2E9, (b,s,fd) => uavcan_tunnel_Targetted.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(uavcan_tunnel_Call_req), 63, 0xDB11EDC510502658, (b,s,fd) => uavcan_tunnel_Call_req.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(uavcan_tunnel_Call_res), 63, 0xDB11EDC510502658, (b,s,fd) => uavcan_tunnel_Call_res.ByteArrayToDroneCANMsg(b,s,fd)), (typeof(mppt_Stream), 20009, 0xDD7096B255FB6358, (b,s,fd) => mppt_Stream.ByteArrayToDroneCANMsg(b,s,fd)), diff --git a/ExtLibs/DroneCAN/canard_dsdlc/templates/msg.h b/ExtLibs/DroneCAN/canard_dsdlc/templates/msg.h index 086e354775..0446364186 100644 --- a/ExtLibs/DroneCAN/canard_dsdlc/templates/msg.h +++ b/ExtLibs/DroneCAN/canard_dsdlc/templates/msg.h @@ -1,5 +1,9 @@ @{from canard_dsdlc_helpers import *}@ - +@{ +for field in msg_fields : + if field.name == "interface" : + field.name = "@" + field.name +}@ using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/dsdl/.github/workflows/test_regression.yml b/ExtLibs/DroneCAN/dsdl/.github/workflows/test_regression.yml new file mode 100644 index 0000000000..24c06be77b --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/.github/workflows/test_regression.yml @@ -0,0 +1,27 @@ +name: test regression + +on: [push, pull_request, workflow_dispatch] + +jobs: + test: + runs-on: ubuntu-22.04 + steps: + # git checkout the PR + - uses: actions/checkout@v3 + + - name: Install gcc + run: sudo apt-get install -y gcc libc6-dev + + - name: test DSDL generation and encode/decode + shell: bash + run: | + tests/test_regression.sh + + - name: Archive generated headers + uses: actions/upload-artifact@v3 + with: + name: dsdl_generated + path: | + dsdl_generated/include + dsdl_generated/src + retention-days: 90 diff --git a/ExtLibs/DroneCAN/dsdl/README.md b/ExtLibs/DroneCAN/dsdl/README.md index 7d5a3ea79b..b52d684042 100644 --- a/ExtLibs/DroneCAN/dsdl/README.md +++ b/ExtLibs/DroneCAN/dsdl/README.md @@ -6,4 +6,21 @@ messages and services. This DSDL is based on DroneCAN v1 +For information about the Message type IDs (including how the unqiue IDs are allocated), see [**id distribution**](https://dronecan.github.io/Specification/5._Application_level_conventions/#id-distribution) + +Message ID +---------- + +For broadcast messages the following should be used: + + - [0, 20000) Standard message types + - [20000, 21000) Vendor-specific message types + - [21000, 65536) Reserved for future use + +For service types, the following should be used: + + - [0, 100) Standard service types + - [100, 200) Reserved for future use + - [200, 256) Vendor-specific service types + * [**DroneCAN website**](http://dronecan.org) diff --git a/ExtLibs/DroneCAN/dsdl/ardupilot/indication/20007.NotifyState.uavcan b/ExtLibs/DroneCAN/dsdl/ardupilot/indication/20007.NotifyState.uavcan index a4aadc9c5d..ec36fff416 100644 --- a/ExtLibs/DroneCAN/dsdl/ardupilot/indication/20007.NotifyState.uavcan +++ b/ExtLibs/DroneCAN/dsdl/ardupilot/indication/20007.NotifyState.uavcan @@ -20,6 +20,8 @@ uint8 VEHICLE_STATE_LOST = 18 uint8 VEHICLE_STATE_THROW_READY = 19 uint8 VEHICLE_STATE_POWERING_OFF = 20 uint8 VEHICLE_STATE_VIDEO_RECORDING = 21 +uint8 VEHICLE_STATE_IS_LANDING = 22 +uint8 VEHICLE_STATE_IS_TAKING_OFF = 23 uint8 VEHICLE_YAW_EARTH_CENTIDEGREES = 0 diff --git a/ExtLibs/DroneCAN/dsdl/com/himark/servo/2018.ServoCmd.uavcan b/ExtLibs/DroneCAN/dsdl/com/himark/servo/2018.ServoCmd.uavcan new file mode 100644 index 0000000000..b287fd64b5 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/himark/servo/2018.ServoCmd.uavcan @@ -0,0 +1,9 @@ +# Himark servo commands +# it is not recommended that anyone implement this message. It is here as a placeholder +# for existing Himark servos + +# signature from original file location +OVERRIDE_SIGNATURE 0x5D09E48551CE9194 + +uint10[<=17] cmd + diff --git a/ExtLibs/DroneCAN/dsdl/com/himark/servo/2019.ServoInfo.uavcan b/ExtLibs/DroneCAN/dsdl/com/himark/servo/2019.ServoInfo.uavcan new file mode 100644 index 0000000000..77e294c94f --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/himark/servo/2019.ServoInfo.uavcan @@ -0,0 +1,34 @@ +# Himark servo feedback information +# it is not recommended that anyone implement this message. It is here as a placeholder +# for existing Himark servos + +# signature from original file location +OVERRIDE_SIGNATURE 0xCA8F4B8F97D23B57 + +# servo ID from 0 to 17 +uint5 servo_id + +# current commanded input, range 700 to 2300, 1 LSB/us +uint12 pwm_input + +# commanded position from -18000 to 18000, 1 LSB == 0.01 degrees +int16 pos_cmd + +# sensed position from -18000 to 18000, 1 LSB == 0.01 degrees +int16 pos_sensor + +# voltage, range 0 to 4095, 1 LSB == 0.01V +uint12 voltage + +# current, range 0 to 1023, 1 LSB == 0.01A +uint10 current + +# PCB temperature, range 0 to 1023, 1 LSB == 0.2 degrees Celsius, temp = pcb_tem*0.2-40 +uint10 pcb_temp + +# motor temperature, range 0 to 1023, 1 LSB == 0.2 degrees Celsius, temp = motor_tem*0.2-40 +uint10 motor_temp + +uint5 ERROR_STATUS_NO_ERROR = 0 +uint5 ERROR_STATUS_DATA_ERROR = 1 +uint5 error_status diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20013.GetEscID.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20013.GetEscID.uavcan new file mode 100644 index 0000000000..02a9f10341 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20013.GetEscID.uavcan @@ -0,0 +1,5 @@ +# signature from original file location +OVERRIDE_SIGNATURE 0x4E2D + +uint8[<=3] payload + diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20050.StatusMsg1.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20050.StatusMsg1.uavcan new file mode 100644 index 0000000000..e90202dcd5 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20050.StatusMsg1.uavcan @@ -0,0 +1,5 @@ +OVERRIDE_SIGNATURE 0x0813b3e2c4ad670e + +uint16 rpm +uint16 pwm +uint16 status diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20051.StatusMsg2.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20051.StatusMsg2.uavcan new file mode 100644 index 0000000000..6be17bd4c7 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20051.StatusMsg2.uavcan @@ -0,0 +1,6 @@ +OVERRIDE_SIGNATURE 0x1675da01c3b91297 + +int16 input_voltage # 0.1V +int16 current # 0.1A +uint8 temperature # degC + diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20052.StatusMsg3.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20052.StatusMsg3.uavcan new file mode 100644 index 0000000000..6af4f44f23 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20052.StatusMsg3.uavcan @@ -0,0 +1,5 @@ +OVERRIDE_SIGNATURE 0x24919cd1eb34ece9 + +uint8 MOS_T +uint8 CAP_T +uint8 Motor_T diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20100.RawCommand.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20100.RawCommand.uavcan new file mode 100644 index 0000000000..be7c8d7e1d --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/20100.RawCommand.uavcan @@ -0,0 +1,3 @@ +OVERRIDE_SIGNATURE 0xbdf086c79f6640ad + +int14[<=8] command diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/210.SetID.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/210.SetID.uavcan new file mode 100644 index 0000000000..62749e1326 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/210.SetID.uavcan @@ -0,0 +1,9 @@ +OVERRIDE_SIGNATURE 0xc323cb5e9ec2b6f7 + +uint8 node_id +uint8 throttle_channel + +--- + +uint8 node_id +uint8 throttle_channel diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/211.SetBaud.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/211.SetBaud.uavcan new file mode 100644 index 0000000000..6767998689 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/211.SetBaud.uavcan @@ -0,0 +1,11 @@ +OVERRIDE_SIGNATURE 0xada98653b52de435 + +uint8 BAUD_1MBPS = 0 +uint8 BAUD_500KBPS = 1 +uint8 BAUD_250KBPS = 2 +uint8 BAUD_200KBPS = 3 +uint8 BAUD_100KBPS = 4 +uint8 BAUD_50KBPS = 5 +uint8 baud + +--- diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/212.SetLED.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/212.SetLED.uavcan new file mode 100644 index 0000000000..d74af79317 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/212.SetLED.uavcan @@ -0,0 +1,21 @@ +OVERRIDE_SIGNATURE 0xb493bd48c0853ee5 + +uint8 OPTION_SAVE = 1 +uint8 option + +uint8 COLOR_R = 4 +uint8 COLOR_G = 2 +uint8 COLOR_B = 1 +uint8 color + +uint8 BLINK_OFF = 0 +uint8 BLINK_1HZ = 1 +uint8 BLINK_2HZ = 2 +uint8 BLINK_5HZ = 5 +uint8 blink + +--- + +uint8 option +uint8 color +uint8 blink diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/213.SetDirection.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/213.SetDirection.uavcan new file mode 100644 index 0000000000..8f728b517a --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/213.SetDirection.uavcan @@ -0,0 +1,9 @@ +OVERRIDE_SIGNATURE 0x9d793111d262ba68 + +uint8 DIRECTION_CLOCKWISE = 0 +uint8 DIRECTION_COUNTER_CLOCKWISE = 1 +uint8 DIRECTION_QUERY = 255 +uint8 direction + +--- +uint8 direction diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/214.SetReportingFrequency.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/214.SetReportingFrequency.uavcan new file mode 100644 index 0000000000..ebd68d9d1f --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/214.SetReportingFrequency.uavcan @@ -0,0 +1,25 @@ +OVERRIDE_SIGNATURE 0x1fd0404420983deb + +uint8 OPTION_READ = 0 +uint8 OPTION_WRITE = 1 +uint8 option + +uint16 MSG_ID + +uint8 RATE_500HZ = 1 +uint8 RATE_250HZ = 2 +uint8 RATE_200HZ = 3 +uint8 RATE_100HZ = 4 +uint8 RATE_50HZ = 5 +uint8 RATE_20HZ = 6 +uint8 RATE_10HZ = 7 +uint8 RATE_1HZ = 8 +uint8 RATE_0HZ = 9 +uint8 rate + +--- + +uint8 option +uint16 MSG_ID +uint8 rate + diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/215.SetThrottleSource.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/215.SetThrottleSource.uavcan new file mode 100644 index 0000000000..0c2797fdba --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/215.SetThrottleSource.uavcan @@ -0,0 +1,9 @@ +OVERRIDE_SIGNATURE 0x0c248faaefe5e29a + +uint8 SOURCE_CAN_DIGITAL = 0 +uint8 SOURCE_PWM = 1 +uint8 source + +--- + +uint8 source diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/216.SelfTest.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/216.SelfTest.uavcan new file mode 100644 index 0000000000..fd4f89653e --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/216.SelfTest.uavcan @@ -0,0 +1,7 @@ +OVERRIDE_SIGNATURE 0xc48d4de61c5295df + +--- + +uint8 STATUS_PASS = 0 +uint8 STATUS_FAIL = 1 +uint8 status diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/217.SetAngle.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/217.SetAngle.uavcan new file mode 100644 index 0000000000..de25d3e8bb --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/217.SetAngle.uavcan @@ -0,0 +1,9 @@ +OVERRIDE_SIGNATURE 0x81d9b10761c28e0a + +uint8 option +uint16 angle + +--- + +uint8 option +uint16[<=2] angle diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/241.GetMaintenanceInformation.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/241.GetMaintenanceInformation.uavcan new file mode 100644 index 0000000000..389a898b71 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/241.GetMaintenanceInformation.uavcan @@ -0,0 +1,9 @@ +OVERRIDE_SIGNATURE 0xb81dbd4ec9a5977d + +uint8 OPTION_CLEAR = 1 +uint8 option + +--- + +uint32 total_rotation_time_min +uint24 time_since_maintainence_min diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/242.GetMajorConfig.uavcan b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/242.GetMajorConfig.uavcan new file mode 100644 index 0000000000..d230d83cc2 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/242.GetMajorConfig.uavcan @@ -0,0 +1,19 @@ +OVERRIDE_SIGNATURE 0x1506774da3930bfd + +uint8 option + +--- + +bool direction +bool throttle_source +uint6 throttle_channel + +uint5 led_status +uint3 led_color + +uint4 MSG2_rate +uint4 MSG1_rate + +uint16 positioning_angle + +uint8[2] reserved diff --git a/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/README.md b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/README.md new file mode 100644 index 0000000000..6f71cba69e --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/hobbywing/esc/README.md @@ -0,0 +1,12 @@ +Hobbywing CAN ESC +================= + +These messages are for the Hobbywing DroneCAN ESCs. These ESCs do not +use the standard uavcan.equipment.esc messages and instead implement +their own messages as given in this directory. + +Note that the ESCs default to a CAN baud rate of 500000, but it can be +changed with the SetBaud command. + +The default CAN NodeID is 1, and it can be changed with the SetID +command. diff --git a/ExtLibs/DroneCAN/dsdl/com/xacti/20305.GnssStatus.uavcan b/ExtLibs/DroneCAN/dsdl/com/xacti/20305.GnssStatus.uavcan new file mode 100644 index 0000000000..6edc1f26fe --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/xacti/20305.GnssStatus.uavcan @@ -0,0 +1,44 @@ +# +# Xacti GNSS status +# + +# signature from original file location +OVERRIDE_SIGNATURE 0x3413AC5D3E1DCBE3 + +# +# GPS status +# 0: Invalid. all fields except order and remain_buffer should be zero +# 1: No CAM_SYNC requests. all other fields should be zero +# 2: Valid +# +uint8 gps_status + +# +# order +# request sequence number in range from 0 to 21. incremented each time +# will be 0 in response to a GnssStatusReq with 'requirement' field of 0 (clear buffer) +# +uint8 order + +# +# remain_buffer +# number of buffers remaining in range from 0 to 21. 0 is empty +# +uint8 remain_buffer + +# +# UTCD year, month, day, hour minute and second +# +uint16 utc_year # 2023 ~ +uint8 utc_month # 1 ~ 12 +uint8 utc_day # 1 ~ 31 +uint8 utc_hour # 0 ~ 23 +uint8 utc_minute # 0 ~ 59 +float32 utc_seconds # 0 ~ below 60 + +# +# latitude, longitude, altitude (in meters, AMSL) +# +float64 latitude # degrees -90 ~ +90 +float64 longitude # degrees -180 ~ +180 +float32 altitude # meters above sea level, AMSL diff --git a/ExtLibs/DroneCAN/dsdl/com/xacti/20306.GnssStatusReq.uavcan b/ExtLibs/DroneCAN/dsdl/com/xacti/20306.GnssStatusReq.uavcan new file mode 100644 index 0000000000..2866e24378 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/xacti/20306.GnssStatusReq.uavcan @@ -0,0 +1,13 @@ +# +# Xacti GNSS status request +# + +# signature from original file location +OVERRIDE_SIGNATURE 0x60F5464E1CA03449 + +# +# requirement +# 0: clear buffer command +# 1 ~ 21: request sequence +# +uint8 requirement diff --git a/ExtLibs/DroneCAN/dsdl/com/xacti/20402.GimbalAttitudeStatus.uavcan b/ExtLibs/DroneCAN/dsdl/com/xacti/20402.GimbalAttitudeStatus.uavcan new file mode 100644 index 0000000000..c4df10c1b5 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/xacti/20402.GimbalAttitudeStatus.uavcan @@ -0,0 +1,14 @@ +# +# Xacti camera gimbal attitude status +# + +# signature from original file location +OVERRIDE_SIGNATURE 0xEB428B6C25832692 + +# gimbal attitude in euler centi-degrees from -18000 to +18000 +int16 gimbal_roll +int16 gimbal_pitch +int16 gimbal_yaw +int16 magneticencoder_roll +int16 magneticencoder_pitch +int16 magneticencoder_yaw diff --git a/ExtLibs/DroneCAN/dsdl/com/xacti/20407.CopterAttStatus.uavcan b/ExtLibs/DroneCAN/dsdl/com/xacti/20407.CopterAttStatus.uavcan new file mode 100644 index 0000000000..1fad6811cc --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/xacti/20407.CopterAttStatus.uavcan @@ -0,0 +1,22 @@ +# +# Xacti specific vehicle attitude provided to camera gimbal +# send periodically 5~10Hz. +# +# quaternion_wxyz_e4[0] = q.w (or q.q0) * 1e4f +# quaternion_wxyz_e4[1] = q.x (or q.q1) * 1e4f +# quaternion_wxyz_e4[2] = q.y (or q.q2) * 1e4f +# quaternion_wxyz_e4[3] = q.z (or q.q3) * 1e4f +# + +# signature from original file location +OVERRIDE_SIGNATURE 0x6C1F30F1893763B1 + +# +# vehicle attitude quaternion * 1e4 +# +int16[4] quaternion_wxyz_e4 + +# +# reserved +# +float16[<=2] reserved diff --git a/ExtLibs/DroneCAN/dsdl/com/xacti/20554.GimbalControlData.uavcan b/ExtLibs/DroneCAN/dsdl/com/xacti/20554.GimbalControlData.uavcan new file mode 100644 index 0000000000..af4153d56b --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/com/xacti/20554.GimbalControlData.uavcan @@ -0,0 +1,34 @@ +# +# Xacti camera gimbal control +# +# + +# signature from original file location +OVERRIDE_SIGNATURE 0x3B058FA5B150C5BE + +# +# pitch and yaw command type +# 0: unused +# 2: angle control +# 3: angular velocity control +# +uint8 pitch_cmd_type +uint8 yaw_cmd_type + +# +# pitch command value +# if cmd_type is 0 these values are ignored +# if cmd_type is 2 (angle control) scale is centi-degrees. Range is -115 deg (e.g. -11500) to 45 (e.g. 4500). Positive values point gimbal upwards +# if cmd_type is 3 (angular velocity control), scale is centi-degrees/sec +# values are unsigned but gimbal will cast to signed +# +uint16 pitch_cmd_value + +# +# yaw command value +# if cmd_type is 0 these values are ignored +# if cmd_type is 2 (angle control) scale is centi-degrees. Yaw range is -85 deg (e.g. -8500) to +85 deg (e.g. +8500). Positive is clockwise +# if cmd_type is 3 (angular velocity control), scale is centi-degrees/sec +# values are unsigned but gimbal will cast to signed +# +uint16 yaw_cmd_value diff --git a/ExtLibs/DroneCAN/dsdl/dronecan/protocol/342.Stats.uavcan b/ExtLibs/DroneCAN/dsdl/dronecan/protocol/342.Stats.uavcan new file mode 100644 index 0000000000..4e36bcb6e3 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/dronecan/protocol/342.Stats.uavcan @@ -0,0 +1,17 @@ + +# +# monitor the status of the DroneCAN Protocol decoder on the node +# + +uint32 tx_frames # Number of transmitted frames +uint16 tx_errors # Number of errors during transmission +uint32 rx_frames # Number of received frames +uint16 rx_error_oom # Number of out-of-memory errors +uint16 rx_error_internal # Number of internal errors +uint16 rx_error_missed_start # Number of missed start bits +uint16 rx_error_wrong_toggle # Number of wrong toggle bits +uint16 rx_error_short_frame # Number of frames that were too short +uint16 rx_error_bad_crc # Number of frames with bad CRC +uint16 rx_ignored_wrong_address # Number of frames with wrong address +uint16 rx_ignored_not_wanted # Number of frames that were not wanted +uint16 rx_ignored_unexpected_tid # Number of frames with unexpected TID diff --git a/ExtLibs/DroneCAN/dsdl/dronecan/protocol/343.CanStats.uavcan b/ExtLibs/DroneCAN/dsdl/dronecan/protocol/343.CanStats.uavcan new file mode 100644 index 0000000000..7979364023 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/dronecan/protocol/343.CanStats.uavcan @@ -0,0 +1,15 @@ +# +# Monitor the stats of physical layer on the node +# + +uint8 interface # interface number +uint32 tx_requests # number of tx requests +uint16 tx_rejected # number of tx requests rejected +uint16 tx_overflow # number of tx requests overflow +uint16 tx_success # number of tx requests success +uint16 tx_timedout # number of tx requests timedout +uint16 tx_abort # number of tx requests aborted +uint32 rx_received # number of rx received +uint16 rx_overflow # number of rx overflow +uint16 rx_errors # number of rx errors +uint16 busoff_errors # number of busoff errors diff --git a/ExtLibs/DroneCAN/dsdl/dronecan/sensors/rc/1140.RCInput.uavcan b/ExtLibs/DroneCAN/dsdl/dronecan/sensors/rc/1140.RCInput.uavcan new file mode 100644 index 0000000000..479d203466 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/dronecan/sensors/rc/1140.RCInput.uavcan @@ -0,0 +1,9 @@ +uint8 STATUS_QUALITY_VALID = 1 # quality field is valid +uint8 STATUS_FAILSAFE = 2 # receiver has lost contact with transmitter + +uint16 status # bitmask of status bits, enumerated above with STATUS_* + +uint8 quality # scaled, 0 is no signal, 255 is "full" signal +uint4 id # ID of this RC input device + +uint12[<=32] rcin # RC channel values between 0 and 4095 diff --git a/ExtLibs/DroneCAN/dsdl/tests/test_regression.sh b/ExtLibs/DroneCAN/dsdl/tests/test_regression.sh new file mode 100644 index 0000000000..26ae625231 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/tests/test_regression.sh @@ -0,0 +1,16 @@ +#!/bin/bash +# test of DSDL compilation for linux with full regression test of all messages + +set -e +set -x + +# test compiler on linux +python3 -m pip install -U empy pexpect dronecan + +pushd .. +[ -d dronecan_dsdlc ] || git clone https://github.com/DroneCAN/dronecan_dsdlc +[ -d libcanard ] || git clone https://github.com/DroneCAN/libcanard +popd + +echo "Testing generation with regression testing" +python3 ../dronecan_dsdlc/dronecan_dsdlc.py --output dsdl_generated dronecan uavcan com ardupilot --run-test diff --git a/ExtLibs/DroneCAN/dsdl/uavcan/equipment/esc/1034.Status.uavcan b/ExtLibs/DroneCAN/dsdl/uavcan/equipment/esc/1034.Status.uavcan index fad4159a32..b15947bf31 100644 --- a/ExtLibs/DroneCAN/dsdl/uavcan/equipment/esc/1034.Status.uavcan +++ b/ExtLibs/DroneCAN/dsdl/uavcan/equipment/esc/1034.Status.uavcan @@ -13,4 +13,4 @@ int18 rpm # Negative value indicates reverse rotation uint7 power_rating_pct # Instant demand factor in percent (percent of maximum power); range 0% to 127%. -uint5 esc_index +uint5 esc_index # zero is first ESC. This should match the index into the cmd[] array in RawCommand diff --git a/ExtLibs/DroneCAN/dsdl/uavcan/protocol/param/10.ExecuteOpcode.uavcan b/ExtLibs/DroneCAN/dsdl/uavcan/protocol/param/10.ExecuteOpcode.uavcan index 204cd12c6f..cfa8fc8511 100644 --- a/ExtLibs/DroneCAN/dsdl/uavcan/protocol/param/10.ExecuteOpcode.uavcan +++ b/ExtLibs/DroneCAN/dsdl/uavcan/protocol/param/10.ExecuteOpcode.uavcan @@ -10,6 +10,11 @@ # with their default values. The node may require a restart in order for some changes to take effect. # # Other opcodes may be added in the future (for example, an opcode for switching between multiple configurations). + +# note that implementors may choose to make parameter set operations +# be immediately persistent, or can choose to make them temporary, +# requiring a ExecuteOpcode with OPCODE_SAVE to put into persistent +# storage # uint8 OPCODE_SAVE = 0 # Save all parameters to non-volatile storage. uint8 OPCODE_ERASE = 1 # Clear the non-volatile storage; some changes may take effect only after reboot. diff --git a/ExtLibs/DroneCAN/dsdl/uavcan/protocol/param/11.GetSet.uavcan b/ExtLibs/DroneCAN/dsdl/uavcan/protocol/param/11.GetSet.uavcan index 5a9db6bd18..02f9ad6d94 100644 --- a/ExtLibs/DroneCAN/dsdl/uavcan/protocol/param/11.GetSet.uavcan +++ b/ExtLibs/DroneCAN/dsdl/uavcan/protocol/param/11.GetSet.uavcan @@ -4,6 +4,9 @@ # discouraged to use it for anything else, because persistent ordering is not guaranteed. # +# implementors may choose to make parameter set operations be immediately persistent, or can choose +# to make them temporary, requiring a ExecuteOpcode with OPCODE_SAVE to put into persistent storage + # # Index of the parameter starting from 0; ignored if name is nonempty. # Use index only to retrieve the list of parameters. diff --git a/ExtLibs/DroneCAN/dsdl/uavcan/tunnel/3001.Targetted.uavcan b/ExtLibs/DroneCAN/dsdl/uavcan/tunnel/3001.Targetted.uavcan new file mode 100644 index 0000000000..438746dce8 --- /dev/null +++ b/ExtLibs/DroneCAN/dsdl/uavcan/tunnel/3001.Targetted.uavcan @@ -0,0 +1,23 @@ +# This message struct carries arbitrary data in the format of the specified high-level protocol. +# The message is sent as a broadcast but it is expected that the target_node to select which node +# will process the data. This is used instead of a service request to avoid the round trip which +# impacts high rate messages +# a send with a buffer length of 0 can be used as a keepalive or to trigger initial +# setup of the link on the target node + +Protocol protocol + +# target CAN node ID +uint7 target_node + +# ID of serial device, -1 means the default device +int5 serial_id + +# option flags +uint4 OPTION_LOCK_PORT = 1 + +uint4 options + +uint24 baudrate + +uint8[<=120] buffer diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryCells.cs b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryCells.cs index 303e3d1912..575868dab7 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryCells.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryCells.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryContinuous.cs b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryContinuous.cs index 96d6211a4d..07a49c507c 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryContinuous.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryContinuous.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryInfoAux.cs b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryInfoAux.cs index 5cc08ebb0b..ca09dee7a9 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryInfoAux.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryInfoAux.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryPeriodic.cs b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryPeriodic.cs index b3d15543a5..41a608ce36 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryPeriodic.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.power.BatteryPeriodic.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.proximity_sensor.Proximity.cs b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.proximity_sensor.Proximity.cs index e6915dd897..7c2dbffc5a 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.proximity_sensor.Proximity.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.proximity_sensor.Proximity.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.trafficmonitor.TrafficReport.cs b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.trafficmonitor.TrafficReport.cs index 8dc0fbe157..531a276983 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.equipment.trafficmonitor.TrafficReport.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.equipment.trafficmonitor.TrafficReport.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.gnss.Heading.cs b/ExtLibs/DroneCAN/out/include/ardupilot.gnss.Heading.cs index 767fbe62c2..bc4baf6e8a 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.gnss.Heading.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.gnss.Heading.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.gnss.MovingBaselineData.cs b/ExtLibs/DroneCAN/out/include/ardupilot.gnss.MovingBaselineData.cs index eff7ba70bf..35a07c9917 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.gnss.MovingBaselineData.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.gnss.MovingBaselineData.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.gnss.RelPosHeading.cs b/ExtLibs/DroneCAN/out/include/ardupilot.gnss.RelPosHeading.cs index 0361b084ce..bc667cf155 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.gnss.RelPosHeading.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.gnss.RelPosHeading.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.gnss.Status.cs b/ExtLibs/DroneCAN/out/include/ardupilot.gnss.Status.cs index 08f592327c..61bb36301b 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.gnss.Status.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.gnss.Status.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.indication.Button.cs b/ExtLibs/DroneCAN/out/include/ardupilot.indication.Button.cs index 7f70a1d95c..b5e8a2d92c 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.indication.Button.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.indication.Button.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.indication.NotifyState.cs b/ExtLibs/DroneCAN/out/include/ardupilot.indication.NotifyState.cs index e8c5b62c3e..39b0ba0287 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.indication.NotifyState.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.indication.NotifyState.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; @@ -47,6 +46,8 @@ public partial class ardupilot_indication_NotifyState: IDroneCANSerialize public const double ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_THROW_READY = 19; // saturated uint8 public const double ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_POWERING_OFF = 20; // saturated uint8 public const double ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_VIDEO_RECORDING = 21; // saturated uint8 + public const double ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_IS_LANDING = 22; // saturated uint8 + public const double ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_IS_TAKING_OFF = 23; // saturated uint8 public const double ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES = 0; // saturated uint8 public uint8_t aux_data_type = new uint8_t(); diff --git a/ExtLibs/DroneCAN/out/include/ardupilot.indication.SafetyState.cs b/ExtLibs/DroneCAN/out/include/ardupilot.indication.SafetyState.cs index e2342d98c2..804557c4b9 100644 --- a/ExtLibs/DroneCAN/out/include/ardupilot.indication.SafetyState.cs +++ b/ExtLibs/DroneCAN/out/include/ardupilot.indication.SafetyState.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/com.hex.equipment.flow.Measurement.cs b/ExtLibs/DroneCAN/out/include/com.hex.equipment.flow.Measurement.cs index 1661cb78f5..cf0a749b3e 100644 --- a/ExtLibs/DroneCAN/out/include/com.hex.equipment.flow.Measurement.cs +++ b/ExtLibs/DroneCAN/out/include/com.hex.equipment.flow.Measurement.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/com.himark.servo.ServoCmd.cs b/ExtLibs/DroneCAN/out/include/com.himark.servo.ServoCmd.cs new file mode 100644 index 0000000000..ad18b9ca88 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.himark.servo.ServoCmd.cs @@ -0,0 +1,47 @@ +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_himark_servo_ServoCmd: IDroneCANSerialize + { + public const int COM_HIMARK_SERVO_SERVOCMD_MAX_PACK_SIZE = 22; + public const ulong COM_HIMARK_SERVO_SERVOCMD_DT_SIG = 0x5D09E48551CE9194; + public const int COM_HIMARK_SERVO_SERVOCMD_DT_ID = 2018; + + public uint8_t cmd_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=17)] public uint16_t[] cmd = Enumerable.Range(1, 17).Select(i => new uint16_t()).ToArray(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_himark_servo_ServoCmd(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_himark_servo_ServoCmd(transfer, this, fdcan); + } + + public static com_himark_servo_ServoCmd ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_himark_servo_ServoCmd(); + 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.himark.servo.ServoInfo.cs b/ExtLibs/DroneCAN/out/include/com.himark.servo.ServoInfo.cs new file mode 100644 index 0000000000..8f10211523 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.himark.servo.ServoInfo.cs @@ -0,0 +1,58 @@ +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_himark_servo_ServoInfo: IDroneCANSerialize + { + public const int COM_HIMARK_SERVO_SERVOINFO_MAX_PACK_SIZE = 12; + public const ulong COM_HIMARK_SERVO_SERVOINFO_DT_SIG = 0xCA8F4B8F97D23B57; + public const int COM_HIMARK_SERVO_SERVOINFO_DT_ID = 2019; + + public const double COM_HIMARK_SERVO_SERVOINFO_ERROR_STATUS_NO_ERROR = 0; // saturated uint5 + public const double COM_HIMARK_SERVO_SERVOINFO_ERROR_STATUS_DATA_ERROR = 1; // saturated uint5 + + public uint8_t servo_id = new uint8_t(); + public uint16_t pwm_input = new uint16_t(); + public int16_t pos_cmd = new int16_t(); + public int16_t pos_sensor = new int16_t(); + public uint16_t voltage = new uint16_t(); + public uint16_t current = new uint16_t(); + public uint16_t pcb_temp = new uint16_t(); + public uint16_t motor_temp = new uint16_t(); + public uint8_t error_status = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_himark_servo_ServoInfo(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_himark_servo_ServoInfo(transfer, this, fdcan); + } + + public static com_himark_servo_ServoInfo ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_himark_servo_ServoInfo(); + 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.hobbywing.esc.GetEscID.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetEscID.cs new file mode 100644 index 0000000000..bdc8f62901 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetEscID.cs @@ -0,0 +1,47 @@ +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_hobbywing_esc_GetEscID: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_GETESCID_MAX_PACK_SIZE = 4; + public const ulong COM_HOBBYWING_ESC_GETESCID_DT_SIG = 0x00004E2D; + public const int COM_HOBBYWING_ESC_GETESCID_DT_ID = 20013; + + public uint8_t payload_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] public uint8_t[] payload = Enumerable.Range(1, 3).Select(i => new uint8_t()).ToArray(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_GetEscID(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_GetEscID(transfer, this, fdcan); + } + + public static com_hobbywing_esc_GetEscID ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_GetEscID(); + 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.hobbywing.esc.GetMaintenanceInformation.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMaintenanceInformation.cs new file mode 100644 index 0000000000..714ed59da1 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMaintenanceInformation.cs @@ -0,0 +1,8 @@ +namespace DroneCAN +{ + public partial class DroneCAN { + + const double COM_HOBBYWING_ESC_GETMAINTENANCEINFORMATION_DT_ID = 241; + const double COM_HOBBYWING_ESC_GETMAINTENANCEINFORMATION_DT_SIG = 0xB81DBD4EC9A5977D; + } +} diff --git a/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMaintenanceInformation_req.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMaintenanceInformation_req.cs new file mode 100644 index 0000000000..0303778335 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMaintenanceInformation_req.cs @@ -0,0 +1,49 @@ +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_hobbywing_esc_GetMaintenanceInformation_req: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_GETMAINTENANCEINFORMATION_REQ_MAX_PACK_SIZE = 1; + public const ulong COM_HOBBYWING_ESC_GETMAINTENANCEINFORMATION_REQ_DT_SIG = 0xB81DBD4EC9A5977D; + public const int COM_HOBBYWING_ESC_GETMAINTENANCEINFORMATION_REQ_DT_ID = 241; + + public const double COM_HOBBYWING_ESC_GETMAINTENANCEINFORMATION_REQ_OPTION_CLEAR = 1; // saturated uint8 + + public uint8_t option = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_GetMaintenanceInformation_req(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_GetMaintenanceInformation_req(transfer, this, fdcan); + } + + public static com_hobbywing_esc_GetMaintenanceInformation_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_GetMaintenanceInformation_req(); + 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.hobbywing.esc.GetMaintenanceInformation_res.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMaintenanceInformation_res.cs new file mode 100644 index 0000000000..14decf0271 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMaintenanceInformation_res.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_hobbywing_esc_GetMaintenanceInformation_res: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_GETMAINTENANCEINFORMATION_RES_MAX_PACK_SIZE = 7; + public const ulong COM_HOBBYWING_ESC_GETMAINTENANCEINFORMATION_RES_DT_SIG = 0xB81DBD4EC9A5977D; + public const int COM_HOBBYWING_ESC_GETMAINTENANCEINFORMATION_RES_DT_ID = 241; + + public uint32_t total_rotation_time_min = new uint32_t(); + public uint32_t time_since_maintainence_min = new uint32_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_GetMaintenanceInformation_res(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_GetMaintenanceInformation_res(transfer, this, fdcan); + } + + public static com_hobbywing_esc_GetMaintenanceInformation_res ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_GetMaintenanceInformation_res(); + 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.hobbywing.esc.GetMajorConfig.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMajorConfig.cs new file mode 100644 index 0000000000..301fc741f7 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMajorConfig.cs @@ -0,0 +1,8 @@ +namespace DroneCAN +{ + public partial class DroneCAN { + + const double COM_HOBBYWING_ESC_GETMAJORCONFIG_DT_ID = 242; + const double COM_HOBBYWING_ESC_GETMAJORCONFIG_DT_SIG = 0x1506774DA3930BFD; + } +} diff --git a/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMajorConfig_req.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMajorConfig_req.cs new file mode 100644 index 0000000000..f61e9a1e82 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMajorConfig_req.cs @@ -0,0 +1,47 @@ +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_hobbywing_esc_GetMajorConfig_req: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_GETMAJORCONFIG_REQ_MAX_PACK_SIZE = 1; + public const ulong COM_HOBBYWING_ESC_GETMAJORCONFIG_REQ_DT_SIG = 0x1506774DA3930BFD; + public const int COM_HOBBYWING_ESC_GETMAJORCONFIG_REQ_DT_ID = 242; + + public uint8_t option = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_GetMajorConfig_req(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_GetMajorConfig_req(transfer, this, fdcan); + } + + public static com_hobbywing_esc_GetMajorConfig_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_GetMajorConfig_req(); + 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.hobbywing.esc.GetMajorConfig_res.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMajorConfig_res.cs new file mode 100644 index 0000000000..851d203b3c --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.GetMajorConfig_res.cs @@ -0,0 +1,55 @@ +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_hobbywing_esc_GetMajorConfig_res: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_GETMAJORCONFIG_RES_MAX_PACK_SIZE = 7; + public const ulong COM_HOBBYWING_ESC_GETMAJORCONFIG_RES_DT_SIG = 0x1506774DA3930BFD; + public const int COM_HOBBYWING_ESC_GETMAJORCONFIG_RES_DT_ID = 242; + + public bool direction = new bool(); + public bool throttle_source = new bool(); + public uint8_t throttle_channel = new uint8_t(); + public uint8_t led_status = new uint8_t(); + public uint8_t led_color = new uint8_t(); + public uint8_t MSG2_rate = new uint8_t(); + public uint8_t MSG1_rate = new uint8_t(); + public uint16_t positioning_angle = new uint16_t(); + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] public uint8_t[] reserved = new uint8_t[2]; + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_GetMajorConfig_res(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_GetMajorConfig_res(transfer, this, fdcan); + } + + public static com_hobbywing_esc_GetMajorConfig_res ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_GetMajorConfig_res(); + 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.hobbywing.esc.RawCommand.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.RawCommand.cs new file mode 100644 index 0000000000..401c6e95d4 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.RawCommand.cs @@ -0,0 +1,47 @@ +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_hobbywing_esc_RawCommand: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_RAWCOMMAND_MAX_PACK_SIZE = 15; + public const ulong COM_HOBBYWING_ESC_RAWCOMMAND_DT_SIG = 0xBDF086C79F6640AD; + public const int COM_HOBBYWING_ESC_RAWCOMMAND_DT_ID = 20100; + + public uint8_t command_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] public int16_t[] command = Enumerable.Range(1, 8).Select(i => new int16_t()).ToArray(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_RawCommand(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_RawCommand(transfer, this, fdcan); + } + + public static com_hobbywing_esc_RawCommand ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_RawCommand(); + 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.hobbywing.esc.SelfTest.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SelfTest.cs new file mode 100644 index 0000000000..53369400f4 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SelfTest.cs @@ -0,0 +1,8 @@ +namespace DroneCAN +{ + public partial class DroneCAN { + + const double COM_HOBBYWING_ESC_SELFTEST_DT_ID = 216; + const double COM_HOBBYWING_ESC_SELFTEST_DT_SIG = 0xC48D4DE61C5295DF; + } +} diff --git a/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SelfTest_req.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SelfTest_req.cs new file mode 100644 index 0000000000..31984fc6fc --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SelfTest_req.cs @@ -0,0 +1,46 @@ +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_hobbywing_esc_SelfTest_req: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SELFTEST_REQ_MAX_PACK_SIZE = 0; + public const ulong COM_HOBBYWING_ESC_SELFTEST_REQ_DT_SIG = 0xC48D4DE61C5295DF; + public const int COM_HOBBYWING_ESC_SELFTEST_REQ_DT_ID = 216; + + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SelfTest_req(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SelfTest_req(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SelfTest_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SelfTest_req(); + 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.hobbywing.esc.SelfTest_res.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SelfTest_res.cs new file mode 100644 index 0000000000..16157fc5e9 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SelfTest_res.cs @@ -0,0 +1,50 @@ +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_hobbywing_esc_SelfTest_res: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SELFTEST_RES_MAX_PACK_SIZE = 1; + public const ulong COM_HOBBYWING_ESC_SELFTEST_RES_DT_SIG = 0xC48D4DE61C5295DF; + public const int COM_HOBBYWING_ESC_SELFTEST_RES_DT_ID = 216; + + public const double COM_HOBBYWING_ESC_SELFTEST_RES_STATUS_PASS = 0; // saturated uint8 + public const double COM_HOBBYWING_ESC_SELFTEST_RES_STATUS_FAIL = 1; // saturated uint8 + + public uint8_t status = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SelfTest_res(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SelfTest_res(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SelfTest_res ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SelfTest_res(); + 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.hobbywing.esc.SetAngle.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetAngle.cs new file mode 100644 index 0000000000..482561ff90 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetAngle.cs @@ -0,0 +1,8 @@ +namespace DroneCAN +{ + public partial class DroneCAN { + + const double COM_HOBBYWING_ESC_SETANGLE_DT_ID = 217; + const double COM_HOBBYWING_ESC_SETANGLE_DT_SIG = 0x81D9B10761C28E0A; + } +} diff --git a/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetAngle_req.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetAngle_req.cs new file mode 100644 index 0000000000..6a64d2c9f4 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetAngle_req.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_hobbywing_esc_SetAngle_req: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETANGLE_REQ_MAX_PACK_SIZE = 3; + public const ulong COM_HOBBYWING_ESC_SETANGLE_REQ_DT_SIG = 0x81D9B10761C28E0A; + public const int COM_HOBBYWING_ESC_SETANGLE_REQ_DT_ID = 217; + + public uint8_t option = new uint8_t(); + public uint16_t angle = new uint16_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetAngle_req(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetAngle_req(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetAngle_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetAngle_req(); + 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.hobbywing.esc.SetAngle_res.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetAngle_res.cs new file mode 100644 index 0000000000..4548b07231 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetAngle_res.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_hobbywing_esc_SetAngle_res: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETANGLE_RES_MAX_PACK_SIZE = 6; + public const ulong COM_HOBBYWING_ESC_SETANGLE_RES_DT_SIG = 0x81D9B10761C28E0A; + public const int COM_HOBBYWING_ESC_SETANGLE_RES_DT_ID = 217; + + public uint8_t option = new uint8_t(); + public uint8_t angle_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] public uint16_t[] angle = Enumerable.Range(1, 2).Select(i => new uint16_t()).ToArray(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetAngle_res(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetAngle_res(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetAngle_res ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetAngle_res(); + 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.hobbywing.esc.SetBaud.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetBaud.cs new file mode 100644 index 0000000000..57b17c4562 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetBaud.cs @@ -0,0 +1,8 @@ +namespace DroneCAN +{ + public partial class DroneCAN { + + const double COM_HOBBYWING_ESC_SETBAUD_DT_ID = 211; + const double COM_HOBBYWING_ESC_SETBAUD_DT_SIG = 0xADA98653B52DE435; + } +} diff --git a/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetBaud_req.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetBaud_req.cs new file mode 100644 index 0000000000..9bfb401ccf --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetBaud_req.cs @@ -0,0 +1,54 @@ +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_hobbywing_esc_SetBaud_req: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETBAUD_REQ_MAX_PACK_SIZE = 1; + public const ulong COM_HOBBYWING_ESC_SETBAUD_REQ_DT_SIG = 0xADA98653B52DE435; + public const int COM_HOBBYWING_ESC_SETBAUD_REQ_DT_ID = 211; + + public const double COM_HOBBYWING_ESC_SETBAUD_REQ_BAUD_1MBPS = 0; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETBAUD_REQ_BAUD_500KBPS = 1; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETBAUD_REQ_BAUD_250KBPS = 2; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETBAUD_REQ_BAUD_200KBPS = 3; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETBAUD_REQ_BAUD_100KBPS = 4; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETBAUD_REQ_BAUD_50KBPS = 5; // saturated uint8 + + public uint8_t baud = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetBaud_req(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetBaud_req(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetBaud_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetBaud_req(); + 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.hobbywing.esc.SetBaud_res.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetBaud_res.cs new file mode 100644 index 0000000000..97dc28fd4c --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetBaud_res.cs @@ -0,0 +1,46 @@ +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_hobbywing_esc_SetBaud_res: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETBAUD_RES_MAX_PACK_SIZE = 0; + public const ulong COM_HOBBYWING_ESC_SETBAUD_RES_DT_SIG = 0xADA98653B52DE435; + public const int COM_HOBBYWING_ESC_SETBAUD_RES_DT_ID = 211; + + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetBaud_res(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetBaud_res(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetBaud_res ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetBaud_res(); + 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.hobbywing.esc.SetDirection.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetDirection.cs new file mode 100644 index 0000000000..85f7106559 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetDirection.cs @@ -0,0 +1,8 @@ +namespace DroneCAN +{ + public partial class DroneCAN { + + const double COM_HOBBYWING_ESC_SETDIRECTION_DT_ID = 213; + const double COM_HOBBYWING_ESC_SETDIRECTION_DT_SIG = 0x9D793111D262BA68; + } +} diff --git a/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetDirection_req.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetDirection_req.cs new file mode 100644 index 0000000000..c5027d0848 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetDirection_req.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_hobbywing_esc_SetDirection_req: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETDIRECTION_REQ_MAX_PACK_SIZE = 1; + public const ulong COM_HOBBYWING_ESC_SETDIRECTION_REQ_DT_SIG = 0x9D793111D262BA68; + public const int COM_HOBBYWING_ESC_SETDIRECTION_REQ_DT_ID = 213; + + public const double COM_HOBBYWING_ESC_SETDIRECTION_REQ_DIRECTION_CLOCKWISE = 0; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETDIRECTION_REQ_DIRECTION_COUNTER_CLOCKWISE = 1; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETDIRECTION_REQ_DIRECTION_QUERY = 255; // saturated uint8 + + public uint8_t direction = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetDirection_req(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetDirection_req(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetDirection_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetDirection_req(); + 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.hobbywing.esc.SetDirection_res.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetDirection_res.cs new file mode 100644 index 0000000000..bdbc41a1c6 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetDirection_res.cs @@ -0,0 +1,47 @@ +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_hobbywing_esc_SetDirection_res: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETDIRECTION_RES_MAX_PACK_SIZE = 1; + public const ulong COM_HOBBYWING_ESC_SETDIRECTION_RES_DT_SIG = 0x9D793111D262BA68; + public const int COM_HOBBYWING_ESC_SETDIRECTION_RES_DT_ID = 213; + + public uint8_t direction = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetDirection_res(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetDirection_res(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetDirection_res ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetDirection_res(); + 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.hobbywing.esc.SetID.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetID.cs new file mode 100644 index 0000000000..ba2badd7a9 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetID.cs @@ -0,0 +1,8 @@ +namespace DroneCAN +{ + public partial class DroneCAN { + + const double COM_HOBBYWING_ESC_SETID_DT_ID = 210; + const double COM_HOBBYWING_ESC_SETID_DT_SIG = 0xC323CB5E9EC2B6F7; + } +} diff --git a/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetID_req.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetID_req.cs new file mode 100644 index 0000000000..a36c730983 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetID_req.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_hobbywing_esc_SetID_req: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETID_REQ_MAX_PACK_SIZE = 2; + public const ulong COM_HOBBYWING_ESC_SETID_REQ_DT_SIG = 0xC323CB5E9EC2B6F7; + public const int COM_HOBBYWING_ESC_SETID_REQ_DT_ID = 210; + + public uint8_t node_id = new uint8_t(); + public uint8_t throttle_channel = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetID_req(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetID_req(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetID_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetID_req(); + 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.hobbywing.esc.SetID_res.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetID_res.cs new file mode 100644 index 0000000000..2b92b006f8 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetID_res.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_hobbywing_esc_SetID_res: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETID_RES_MAX_PACK_SIZE = 2; + public const ulong COM_HOBBYWING_ESC_SETID_RES_DT_SIG = 0xC323CB5E9EC2B6F7; + public const int COM_HOBBYWING_ESC_SETID_RES_DT_ID = 210; + + public uint8_t node_id = new uint8_t(); + public uint8_t throttle_channel = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetID_res(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetID_res(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetID_res ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetID_res(); + 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.hobbywing.esc.SetLED.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetLED.cs new file mode 100644 index 0000000000..2de01d6ae1 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetLED.cs @@ -0,0 +1,8 @@ +namespace DroneCAN +{ + public partial class DroneCAN { + + const double COM_HOBBYWING_ESC_SETLED_DT_ID = 212; + const double COM_HOBBYWING_ESC_SETLED_DT_SIG = 0xB493BD48C0853EE5; + } +} diff --git a/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetLED_req.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetLED_req.cs new file mode 100644 index 0000000000..afe1a6d8c6 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetLED_req.cs @@ -0,0 +1,58 @@ +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_hobbywing_esc_SetLED_req: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETLED_REQ_MAX_PACK_SIZE = 3; + public const ulong COM_HOBBYWING_ESC_SETLED_REQ_DT_SIG = 0xB493BD48C0853EE5; + public const int COM_HOBBYWING_ESC_SETLED_REQ_DT_ID = 212; + + public const double COM_HOBBYWING_ESC_SETLED_REQ_OPTION_SAVE = 1; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETLED_REQ_COLOR_R = 4; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETLED_REQ_COLOR_G = 2; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETLED_REQ_COLOR_B = 1; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETLED_REQ_BLINK_OFF = 0; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETLED_REQ_BLINK_1HZ = 1; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETLED_REQ_BLINK_2HZ = 2; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETLED_REQ_BLINK_5HZ = 5; // saturated uint8 + + public uint8_t option = new uint8_t(); + public uint8_t color = new uint8_t(); + public uint8_t blink = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetLED_req(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetLED_req(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetLED_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetLED_req(); + 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.hobbywing.esc.SetLED_res.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetLED_res.cs new file mode 100644 index 0000000000..83f3b54928 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetLED_res.cs @@ -0,0 +1,49 @@ +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_hobbywing_esc_SetLED_res: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETLED_RES_MAX_PACK_SIZE = 3; + public const ulong COM_HOBBYWING_ESC_SETLED_RES_DT_SIG = 0xB493BD48C0853EE5; + public const int COM_HOBBYWING_ESC_SETLED_RES_DT_ID = 212; + + public uint8_t option = new uint8_t(); + public uint8_t color = new uint8_t(); + public uint8_t blink = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetLED_res(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetLED_res(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetLED_res ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetLED_res(); + 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.hobbywing.esc.SetReportingFrequency.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetReportingFrequency.cs new file mode 100644 index 0000000000..f0db7a4e18 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetReportingFrequency.cs @@ -0,0 +1,8 @@ +namespace DroneCAN +{ + public partial class DroneCAN { + + const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_DT_ID = 214; + const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_DT_SIG = 0x1FD0404420983DEB; + } +} diff --git a/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetReportingFrequency_req.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetReportingFrequency_req.cs new file mode 100644 index 0000000000..5ed0d89554 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetReportingFrequency_req.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_hobbywing_esc_SetReportingFrequency_req: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_MAX_PACK_SIZE = 4; + public const ulong COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_DT_SIG = 0x1FD0404420983DEB; + public const int COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_DT_ID = 214; + + public const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_OPTION_READ = 0; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_OPTION_WRITE = 1; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_RATE_500HZ = 1; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_RATE_250HZ = 2; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_RATE_200HZ = 3; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_RATE_100HZ = 4; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_RATE_50HZ = 5; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_RATE_20HZ = 6; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_RATE_10HZ = 7; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_RATE_1HZ = 8; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_REQ_RATE_0HZ = 9; // saturated uint8 + + public uint8_t option = new uint8_t(); + public uint16_t MSG_ID = new uint16_t(); + public uint8_t rate = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetReportingFrequency_req(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetReportingFrequency_req(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetReportingFrequency_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetReportingFrequency_req(); + 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.hobbywing.esc.SetReportingFrequency_res.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetReportingFrequency_res.cs new file mode 100644 index 0000000000..61a4f4067d --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetReportingFrequency_res.cs @@ -0,0 +1,49 @@ +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_hobbywing_esc_SetReportingFrequency_res: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_RES_MAX_PACK_SIZE = 4; + public const ulong COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_RES_DT_SIG = 0x1FD0404420983DEB; + public const int COM_HOBBYWING_ESC_SETREPORTINGFREQUENCY_RES_DT_ID = 214; + + public uint8_t option = new uint8_t(); + public uint16_t MSG_ID = new uint16_t(); + public uint8_t rate = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetReportingFrequency_res(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetReportingFrequency_res(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetReportingFrequency_res ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetReportingFrequency_res(); + 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.hobbywing.esc.SetThrottleSource.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetThrottleSource.cs new file mode 100644 index 0000000000..bbd3e8e3da --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetThrottleSource.cs @@ -0,0 +1,8 @@ +namespace DroneCAN +{ + public partial class DroneCAN { + + const double COM_HOBBYWING_ESC_SETTHROTTLESOURCE_DT_ID = 215; + const double COM_HOBBYWING_ESC_SETTHROTTLESOURCE_DT_SIG = 0xC248FAAEFE5E29A; + } +} diff --git a/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetThrottleSource_req.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetThrottleSource_req.cs new file mode 100644 index 0000000000..c4a7a634b1 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetThrottleSource_req.cs @@ -0,0 +1,50 @@ +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_hobbywing_esc_SetThrottleSource_req: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETTHROTTLESOURCE_REQ_MAX_PACK_SIZE = 1; + public const ulong COM_HOBBYWING_ESC_SETTHROTTLESOURCE_REQ_DT_SIG = 0xC248FAAEFE5E29A; + public const int COM_HOBBYWING_ESC_SETTHROTTLESOURCE_REQ_DT_ID = 215; + + public const double COM_HOBBYWING_ESC_SETTHROTTLESOURCE_REQ_SOURCE_CAN_DIGITAL = 0; // saturated uint8 + public const double COM_HOBBYWING_ESC_SETTHROTTLESOURCE_REQ_SOURCE_PWM = 1; // saturated uint8 + + public uint8_t source = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetThrottleSource_req(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetThrottleSource_req(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetThrottleSource_req ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetThrottleSource_req(); + 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.hobbywing.esc.SetThrottleSource_res.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetThrottleSource_res.cs new file mode 100644 index 0000000000..2b52e93cd9 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.SetThrottleSource_res.cs @@ -0,0 +1,47 @@ +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_hobbywing_esc_SetThrottleSource_res: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_SETTHROTTLESOURCE_RES_MAX_PACK_SIZE = 1; + public const ulong COM_HOBBYWING_ESC_SETTHROTTLESOURCE_RES_DT_SIG = 0xC248FAAEFE5E29A; + public const int COM_HOBBYWING_ESC_SETTHROTTLESOURCE_RES_DT_ID = 215; + + public uint8_t source = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_SetThrottleSource_res(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_SetThrottleSource_res(transfer, this, fdcan); + } + + public static com_hobbywing_esc_SetThrottleSource_res ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_SetThrottleSource_res(); + 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.hobbywing.esc.StatusMsg1.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.StatusMsg1.cs new file mode 100644 index 0000000000..d4bff97873 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.StatusMsg1.cs @@ -0,0 +1,49 @@ +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_hobbywing_esc_StatusMsg1: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_STATUSMSG1_MAX_PACK_SIZE = 6; + public const ulong COM_HOBBYWING_ESC_STATUSMSG1_DT_SIG = 0x813B3E2C4AD670E; + public const int COM_HOBBYWING_ESC_STATUSMSG1_DT_ID = 20050; + + public uint16_t rpm = new uint16_t(); + public uint16_t pwm = new uint16_t(); + public uint16_t status = new uint16_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_StatusMsg1(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_StatusMsg1(transfer, this, fdcan); + } + + public static com_hobbywing_esc_StatusMsg1 ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_StatusMsg1(); + 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.hobbywing.esc.StatusMsg2.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.StatusMsg2.cs new file mode 100644 index 0000000000..12e03a6c7b --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.StatusMsg2.cs @@ -0,0 +1,49 @@ +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_hobbywing_esc_StatusMsg2: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_STATUSMSG2_MAX_PACK_SIZE = 5; + public const ulong COM_HOBBYWING_ESC_STATUSMSG2_DT_SIG = 0x1675DA01C3B91297; + public const int COM_HOBBYWING_ESC_STATUSMSG2_DT_ID = 20051; + + public int16_t input_voltage = new int16_t(); + public int16_t current = new int16_t(); + public uint8_t temperature = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_StatusMsg2(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_StatusMsg2(transfer, this, fdcan); + } + + public static com_hobbywing_esc_StatusMsg2 ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_StatusMsg2(); + 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.hobbywing.esc.StatusMsg3.cs b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.StatusMsg3.cs new file mode 100644 index 0000000000..1543f59d4a --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.hobbywing.esc.StatusMsg3.cs @@ -0,0 +1,49 @@ +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_hobbywing_esc_StatusMsg3: IDroneCANSerialize + { + public const int COM_HOBBYWING_ESC_STATUSMSG3_MAX_PACK_SIZE = 3; + public const ulong COM_HOBBYWING_ESC_STATUSMSG3_DT_SIG = 0x24919CD1EB34ECE9; + public const int COM_HOBBYWING_ESC_STATUSMSG3_DT_ID = 20052; + + public uint8_t MOS_T = new uint8_t(); + public uint8_t CAP_T = new uint8_t(); + public uint8_t Motor_T = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_hobbywing_esc_StatusMsg3(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_hobbywing_esc_StatusMsg3(transfer, this, fdcan); + } + + public static com_hobbywing_esc_StatusMsg3 ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_hobbywing_esc_StatusMsg3(); + 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.volz.servo.ActuatorStatus.cs b/ExtLibs/DroneCAN/out/include/com.volz.servo.ActuatorStatus.cs index fef69684de..aafe173478 100644 --- a/ExtLibs/DroneCAN/out/include/com.volz.servo.ActuatorStatus.cs +++ b/ExtLibs/DroneCAN/out/include/com.volz.servo.ActuatorStatus.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/com.xacti.CopterAttStatus.cs b/ExtLibs/DroneCAN/out/include/com.xacti.CopterAttStatus.cs new file mode 100644 index 0000000000..73fa7fd845 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.xacti.CopterAttStatus.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_xacti_CopterAttStatus: IDroneCANSerialize + { + public const int COM_XACTI_COPTERATTSTATUS_MAX_PACK_SIZE = 13; + public const ulong COM_XACTI_COPTERATTSTATUS_DT_SIG = 0x6C1F30F1893763B1; + public const int COM_XACTI_COPTERATTSTATUS_DT_ID = 20407; + + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] public int16_t[] quaternion_wxyz_e4 = new int16_t[4]; + public uint8_t reserved_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] public Single[] reserved = Enumerable.Range(1, 2).Select(i => new Single()).ToArray(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_xacti_CopterAttStatus(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_xacti_CopterAttStatus(transfer, this, fdcan); + } + + public static com_xacti_CopterAttStatus ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_xacti_CopterAttStatus(); + 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.xacti.GimbalAttitudeStatus.cs b/ExtLibs/DroneCAN/out/include/com.xacti.GimbalAttitudeStatus.cs new file mode 100644 index 0000000000..51cf33f85e --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.xacti.GimbalAttitudeStatus.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 com_xacti_GimbalAttitudeStatus: IDroneCANSerialize + { + public const int COM_XACTI_GIMBALATTITUDESTATUS_MAX_PACK_SIZE = 12; + public const ulong COM_XACTI_GIMBALATTITUDESTATUS_DT_SIG = 0xEB428B6C25832692; + public const int COM_XACTI_GIMBALATTITUDESTATUS_DT_ID = 20402; + + public int16_t gimbal_roll = new int16_t(); + public int16_t gimbal_pitch = new int16_t(); + public int16_t gimbal_yaw = new int16_t(); + public int16_t magneticencoder_roll = new int16_t(); + public int16_t magneticencoder_pitch = new int16_t(); + public int16_t magneticencoder_yaw = new int16_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_xacti_GimbalAttitudeStatus(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_xacti_GimbalAttitudeStatus(transfer, this, fdcan); + } + + public static com_xacti_GimbalAttitudeStatus ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_xacti_GimbalAttitudeStatus(); + 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.xacti.GimbalControlData.cs b/ExtLibs/DroneCAN/out/include/com.xacti.GimbalControlData.cs new file mode 100644 index 0000000000..0fc12504bf --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.xacti.GimbalControlData.cs @@ -0,0 +1,50 @@ +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_xacti_GimbalControlData: IDroneCANSerialize + { + public const int COM_XACTI_GIMBALCONTROLDATA_MAX_PACK_SIZE = 6; + public const ulong COM_XACTI_GIMBALCONTROLDATA_DT_SIG = 0x3B058FA5B150C5BE; + public const int COM_XACTI_GIMBALCONTROLDATA_DT_ID = 20554; + + public uint8_t pitch_cmd_type = new uint8_t(); + public uint8_t yaw_cmd_type = new uint8_t(); + public uint16_t pitch_cmd_value = new uint16_t(); + public uint16_t yaw_cmd_value = new uint16_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_xacti_GimbalControlData(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_xacti_GimbalControlData(transfer, this, fdcan); + } + + public static com_xacti_GimbalControlData ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_xacti_GimbalControlData(); + 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.xacti.GnssStatus.cs b/ExtLibs/DroneCAN/out/include/com.xacti.GnssStatus.cs new file mode 100644 index 0000000000..4173657d95 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.xacti.GnssStatus.cs @@ -0,0 +1,58 @@ +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_xacti_GnssStatus: IDroneCANSerialize + { + public const int COM_XACTI_GNSSSTATUS_MAX_PACK_SIZE = 33; + public const ulong COM_XACTI_GNSSSTATUS_DT_SIG = 0x3413AC5D3E1DCBE3; + public const int COM_XACTI_GNSSSTATUS_DT_ID = 20305; + + public uint8_t gps_status = new uint8_t(); + public uint8_t order = new uint8_t(); + public uint8_t remain_buffer = new uint8_t(); + public uint16_t utc_year = new uint16_t(); + public uint8_t utc_month = new uint8_t(); + public uint8_t utc_day = new uint8_t(); + public uint8_t utc_hour = new uint8_t(); + public uint8_t utc_minute = new uint8_t(); + public Single utc_seconds = new Single(); + public Double latitude = new Double(); + public Double longitude = new Double(); + public Single altitude = new Single(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_xacti_GnssStatus(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_xacti_GnssStatus(transfer, this, fdcan); + } + + public static com_xacti_GnssStatus ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_xacti_GnssStatus(); + 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.xacti.GnssStatusReq.cs b/ExtLibs/DroneCAN/out/include/com.xacti.GnssStatusReq.cs new file mode 100644 index 0000000000..1b6ff20ed1 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/com.xacti.GnssStatusReq.cs @@ -0,0 +1,47 @@ +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_xacti_GnssStatusReq: IDroneCANSerialize + { + public const int COM_XACTI_GNSSSTATUSREQ_MAX_PACK_SIZE = 1; + public const ulong COM_XACTI_GNSSSTATUSREQ_DT_SIG = 0x60F5464E1CA03449; + public const int COM_XACTI_GNSSSTATUSREQ_DT_ID = 20306; + + public uint8_t requirement = new uint8_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_com_xacti_GnssStatusReq(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_com_xacti_GnssStatusReq(transfer, this, fdcan); + } + + public static com_xacti_GnssStatusReq ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new com_xacti_GnssStatusReq(); + 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/cuav.equipment.power.CBAT.cs b/ExtLibs/DroneCAN/out/include/cuav.equipment.power.CBAT.cs index 56aa284fec..11444fc926 100644 --- a/ExtLibs/DroneCAN/out/include/cuav.equipment.power.CBAT.cs +++ b/ExtLibs/DroneCAN/out/include/cuav.equipment.power.CBAT.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/dronecan.protocol.CanStats.cs b/ExtLibs/DroneCAN/out/include/dronecan.protocol.CanStats.cs new file mode 100644 index 0000000000..d60387e01a --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/dronecan.protocol.CanStats.cs @@ -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_protocol_CanStats: IDroneCANSerialize + { + public const int DRONECAN_PROTOCOL_CANSTATS_MAX_PACK_SIZE = 25; + public const ulong DRONECAN_PROTOCOL_CANSTATS_DT_SIG = 0xCE080CAE3CA33C75; + public const int DRONECAN_PROTOCOL_CANSTATS_DT_ID = 343; + + public uint8_t @interface = new uint8_t(); + public uint32_t tx_requests = new uint32_t(); + public uint16_t tx_rejected = new uint16_t(); + public uint16_t tx_overflow = new uint16_t(); + public uint16_t tx_success = new uint16_t(); + public uint16_t tx_timedout = new uint16_t(); + public uint16_t tx_abort = new uint16_t(); + public uint32_t rx_received = new uint32_t(); + public uint16_t rx_overflow = new uint16_t(); + public uint16_t rx_errors = new uint16_t(); + public uint16_t busoff_errors = new uint16_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_dronecan_protocol_CanStats(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_dronecan_protocol_CanStats(transfer, this, fdcan); + } + + public static dronecan_protocol_CanStats ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new dronecan_protocol_CanStats(); + 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.Stats.cs b/ExtLibs/DroneCAN/out/include/dronecan.protocol.Stats.cs new file mode 100644 index 0000000000..a4435c9bec --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/dronecan.protocol.Stats.cs @@ -0,0 +1,58 @@ +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_Stats: IDroneCANSerialize + { + public const int DRONECAN_PROTOCOL_STATS_MAX_PACK_SIZE = 28; + public const ulong DRONECAN_PROTOCOL_STATS_DT_SIG = 0x763AE3B8A986F8D1; + public const int DRONECAN_PROTOCOL_STATS_DT_ID = 342; + + public uint32_t tx_frames = new uint32_t(); + public uint16_t tx_errors = new uint16_t(); + public uint32_t rx_frames = new uint32_t(); + public uint16_t rx_error_oom = new uint16_t(); + public uint16_t rx_error_internal = new uint16_t(); + public uint16_t rx_error_missed_start = new uint16_t(); + public uint16_t rx_error_wrong_toggle = new uint16_t(); + public uint16_t rx_error_short_frame = new uint16_t(); + public uint16_t rx_error_bad_crc = new uint16_t(); + public uint16_t rx_ignored_wrong_address = new uint16_t(); + public uint16_t rx_ignored_not_wanted = new uint16_t(); + public uint16_t rx_ignored_unexpected_tid = new uint16_t(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_dronecan_protocol_Stats(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_dronecan_protocol_Stats(transfer, this, fdcan); + } + + public static dronecan_protocol_Stats ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new dronecan_protocol_Stats(); + 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.remoteid.ArmStatus.cs b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.ArmStatus.cs index 2ebfffe25d..ce586c26f2 100644 --- a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.ArmStatus.cs +++ b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.ArmStatus.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.BasicID.cs b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.BasicID.cs index c17dbb9945..6bf7ea1d11 100644 --- a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.BasicID.cs +++ b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.BasicID.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.Location.cs b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.Location.cs index 25852a9d8f..c9757a1397 100644 --- a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.Location.cs +++ b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.Location.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.OperatorID.cs b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.OperatorID.cs index 5ba1922dd4..fa9b8f32f0 100644 --- a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.OperatorID.cs +++ b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.OperatorID.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SecureCommand_req.cs b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SecureCommand_req.cs index 4d7137eae7..421719ddb8 100644 --- a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SecureCommand_req.cs +++ b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SecureCommand_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SecureCommand_res.cs b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SecureCommand_res.cs index b4cd4e6bcf..d267cc574d 100644 --- a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SecureCommand_res.cs +++ b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SecureCommand_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SelfID.cs b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SelfID.cs index e920cdb441..b078262574 100644 --- a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SelfID.cs +++ b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.SelfID.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.System.cs b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.System.cs index b673004c93..46750ab592 100644 --- a/ExtLibs/DroneCAN/out/include/dronecan.remoteid.System.cs +++ b/ExtLibs/DroneCAN/out/include/dronecan.remoteid.System.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/dronecan.sensors.hygrometer.Hygrometer.cs b/ExtLibs/DroneCAN/out/include/dronecan.sensors.hygrometer.Hygrometer.cs index 64e5666949..6d8ca5c0c0 100644 --- a/ExtLibs/DroneCAN/out/include/dronecan.sensors.hygrometer.Hygrometer.cs +++ b/ExtLibs/DroneCAN/out/include/dronecan.sensors.hygrometer.Hygrometer.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/dronecan.sensors.rc.RCInput.cs b/ExtLibs/DroneCAN/out/include/dronecan.sensors.rc.RCInput.cs new file mode 100644 index 0000000000..b98fb87f19 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/dronecan.sensors.rc.RCInput.cs @@ -0,0 +1,53 @@ +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_rc_RCInput: IDroneCANSerialize + { + public const int DRONECAN_SENSORS_RC_RCINPUT_MAX_PACK_SIZE = 53; + public const ulong DRONECAN_SENSORS_RC_RCINPUT_DT_SIG = 0x771555E596AAB4CF; + public const int DRONECAN_SENSORS_RC_RCINPUT_DT_ID = 1140; + + public const double DRONECAN_SENSORS_RC_RCINPUT_STATUS_QUALITY_VALID = 1; // saturated uint8 + public const double DRONECAN_SENSORS_RC_RCINPUT_STATUS_FAILSAFE = 2; // saturated uint8 + + public uint16_t status = new uint16_t(); + public uint8_t quality = new uint8_t(); + public uint8_t id = new uint8_t(); + public uint8_t rcin_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] public uint16_t[] rcin = Enumerable.Range(1, 32).Select(i => new uint16_t()).ToArray(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_dronecan_sensors_rc_RCInput(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_dronecan_sensors_rc_RCInput(transfer, this, fdcan); + } + + public static dronecan_sensors_rc_RCInput ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new dronecan_sensors_rc_RCInput(); + 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/mppt.OutputEnable_req.cs b/ExtLibs/DroneCAN/out/include/mppt.OutputEnable_req.cs index 590a2ee48c..bf64892335 100644 --- a/ExtLibs/DroneCAN/out/include/mppt.OutputEnable_req.cs +++ b/ExtLibs/DroneCAN/out/include/mppt.OutputEnable_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/mppt.OutputEnable_res.cs b/ExtLibs/DroneCAN/out/include/mppt.OutputEnable_res.cs index 73939619da..9420d84a16 100644 --- a/ExtLibs/DroneCAN/out/include/mppt.OutputEnable_res.cs +++ b/ExtLibs/DroneCAN/out/include/mppt.OutputEnable_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/mppt.Stream.cs b/ExtLibs/DroneCAN/out/include/mppt.Stream.cs index 8fb5ece567..aaf32cba27 100644 --- a/ExtLibs/DroneCAN/out/include/mppt.Stream.cs +++ b/ExtLibs/DroneCAN/out/include/mppt.Stream.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.CoarseOrientation.cs b/ExtLibs/DroneCAN/out/include/uavcan.CoarseOrientation.cs index e48ab6742b..b2e7d29007 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.CoarseOrientation.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.CoarseOrientation.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.Timestamp.cs b/ExtLibs/DroneCAN/out/include/uavcan.Timestamp.cs index 881910ea52..65ce29c3e4 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.Timestamp.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.Timestamp.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.ArrayCommand.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.ArrayCommand.cs index a0680817a5..e42f4a8764 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.ArrayCommand.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.ArrayCommand.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.Command.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.Command.cs index a43a85dbc5..b00ae56af7 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.Command.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.Command.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.Status.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.Status.cs index 1fce5cfa03..a92d8c414b 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.Status.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.actuator.Status.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.MagneticFieldStrength.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.MagneticFieldStrength.cs index 45114b2be0..fb1394af1b 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.MagneticFieldStrength.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.MagneticFieldStrength.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.MagneticFieldStrength2.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.MagneticFieldStrength2.cs index 5dce944519..e2a17b60a7 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.MagneticFieldStrength2.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.MagneticFieldStrength2.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.RawIMU.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.RawIMU.cs index c7a9ad9e19..debd3f477c 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.RawIMU.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.RawIMU.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.Solution.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.Solution.cs index 36e3e2843f..d9bdb0b9b4 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.Solution.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ahrs.Solution.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.AngleOfAttack.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.AngleOfAttack.cs index c40078c194..da25703cb4 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.AngleOfAttack.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.AngleOfAttack.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.IndicatedAirspeed.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.IndicatedAirspeed.cs index e9547a8b1a..d019996b3a 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.IndicatedAirspeed.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.IndicatedAirspeed.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.RawAirData.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.RawAirData.cs index 23420d9216..9483e3b24f 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.RawAirData.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.RawAirData.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.Sideslip.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.Sideslip.cs index 3b7397e667..9b34f5a303 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.Sideslip.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.Sideslip.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.StaticPressure.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.StaticPressure.cs index 81629cc297..02d8b3ff8c 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.StaticPressure.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.StaticPressure.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.StaticTemperature.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.StaticTemperature.cs index 374243941d..5fbd5abc7a 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.StaticTemperature.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.StaticTemperature.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.TrueAirspeed.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.TrueAirspeed.cs index d89abc70f1..3e4af19f96 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.TrueAirspeed.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.air_data.TrueAirspeed.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.AngularCommand.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.AngularCommand.cs index baae2eb8c3..658b24d332 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.AngularCommand.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.AngularCommand.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.GEOPOICommand.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.GEOPOICommand.cs index a2dfed953e..0273139e14 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.GEOPOICommand.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.GEOPOICommand.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.Mode.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.Mode.cs index 9bd9e6af04..e6ddb4c8a2 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.Mode.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.Mode.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.Status.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.Status.cs index eda6b25b10..8febdcef83 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.Status.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.camera_gimbal.Status.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.device.Temperature.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.device.Temperature.cs index 0e0713575f..1416279e43 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.device.Temperature.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.device.Temperature.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.RPMCommand.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.RPMCommand.cs index 237c8c97b6..212b442ea6 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.RPMCommand.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.RPMCommand.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.RawCommand.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.RawCommand.cs index 60e6b5996e..e51ccf260c 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.RawCommand.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.RawCommand.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.Status.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.Status.cs index cf44264c35..86a162abdc 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.Status.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.esc.Status.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Auxiliary.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Auxiliary.cs index 735f9fa866..d11e562f35 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Auxiliary.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Auxiliary.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.ECEFPositionVelocity.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.ECEFPositionVelocity.cs index 098083a532..5a1fd2f376 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.ECEFPositionVelocity.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.ECEFPositionVelocity.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix.cs index 785c7529b8..3dc77d9c91 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix2.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix2.cs index 282db99d13..108c206747 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix2.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.Fix2.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; @@ -19,8 +18,8 @@ namespace DroneCAN { public partial class DroneCAN { -//using uavcan.Timestamp.cs //using uavcan.equipment.gnss.ECEFPositionVelocity.cs +//using uavcan.Timestamp.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.gnss.RTCMStream.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.RTCMStream.cs index 5cf522e822..cf67c1978c 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.RTCMStream.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.gnss.RTCMStream.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.hardpoint.Command.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.hardpoint.Command.cs index 7646fdf896..adf89a2fc1 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.hardpoint.Command.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.hardpoint.Command.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.hardpoint.Status.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.hardpoint.Status.cs index e032548f15..bfe6c2d938 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.hardpoint.Status.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.hardpoint.Status.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.FuelTankStatus.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.FuelTankStatus.cs index 8a4ef06baf..215fabf31c 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.FuelTankStatus.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.FuelTankStatus.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.reciprocating.CylinderStatus.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.reciprocating.CylinderStatus.cs index ba6614de03..52cae09df4 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.reciprocating.CylinderStatus.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.reciprocating.CylinderStatus.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.reciprocating.Status.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.reciprocating.Status.cs index a18c034ccd..37e57022dc 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.reciprocating.Status.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.ice.reciprocating.Status.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.BeepCommand.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.BeepCommand.cs index 13e13c75b7..b1fd17c2b8 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.BeepCommand.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.BeepCommand.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.LightsCommand.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.LightsCommand.cs index 68e148ac56..8c72a29f78 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.LightsCommand.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.LightsCommand.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.RGB565.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.RGB565.cs index 23e8eb12e0..a27ddaa2c8 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.RGB565.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.RGB565.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.SingleLightCommand.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.SingleLightCommand.cs index fec5a207c1..7e594014e2 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.SingleLightCommand.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.indication.SingleLightCommand.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.BatteryInfo.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.BatteryInfo.cs index 19407e3c86..d41460e6dc 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.BatteryInfo.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.BatteryInfo.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.CircuitStatus.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.CircuitStatus.cs index cb23d60d3a..a93e9ecb81 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.CircuitStatus.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.CircuitStatus.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.PrimaryPowerSupplyStatus.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.PrimaryPowerSupplyStatus.cs index a38e52654f..fd68dc967d 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.PrimaryPowerSupplyStatus.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.power.PrimaryPowerSupplyStatus.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; 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 0fe7a6fc5f..4f78114433 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.range_sensor.Measurement.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.range_sensor.Measurement.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.equipment.safety.ArmingStatus.cs b/ExtLibs/DroneCAN/out/include/uavcan.equipment.safety.ArmingStatus.cs index f1997caf0e..7f0fa7371c 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.equipment.safety.ArmingStatus.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.equipment.safety.ArmingStatus.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.navigation.GlobalNavigationSolution.cs b/ExtLibs/DroneCAN/out/include/uavcan.navigation.GlobalNavigationSolution.cs index fdae317cad..c47bd3c59e 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.navigation.GlobalNavigationSolution.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.navigation.GlobalNavigationSolution.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.AccessCommandShell_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.AccessCommandShell_req.cs index aeb4c6f784..5df1d75661 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.AccessCommandShell_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.AccessCommandShell_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.AccessCommandShell_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.AccessCommandShell_res.cs index 9cc899253b..07905a0ae6 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.AccessCommandShell_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.AccessCommandShell_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.CANIfaceStats.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.CANIfaceStats.cs index 91127660b8..fb807649d2 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.CANIfaceStats.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.CANIfaceStats.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.DataTypeKind.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.DataTypeKind.cs index 04abae6488..cdb3008bb9 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.DataTypeKind.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.DataTypeKind.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetDataTypeInfo_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetDataTypeInfo_req.cs index f188dcd0de..9e79463747 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetDataTypeInfo_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetDataTypeInfo_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetDataTypeInfo_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetDataTypeInfo_res.cs index 240fea1a46..e9d011cbd4 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetDataTypeInfo_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetDataTypeInfo_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_req.cs index 744257636a..4982f7ef17 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_res.cs index 91d39d4b35..7ce7cbe442 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetNodeInfo_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; @@ -19,8 +18,8 @@ namespace DroneCAN { public partial class DroneCAN { -//using uavcan.protocol.SoftwareVersion.cs //using uavcan.protocol.HardwareVersion.cs +//using uavcan.protocol.SoftwareVersion.cs //using uavcan.protocol.NodeStatus.cs public partial class uavcan_protocol_GetNodeInfo_res: IDroneCANSerialize { diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetTransportStats_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetTransportStats_req.cs index 5b8138d2ae..441cc7d6f5 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetTransportStats_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetTransportStats_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetTransportStats_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetTransportStats_res.cs index 9324bc03b9..4307d6c0c5 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetTransportStats_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GetTransportStats_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GlobalTimeSync.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GlobalTimeSync.cs index a56497100d..0433c17aa3 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.GlobalTimeSync.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.GlobalTimeSync.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.HardwareVersion.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.HardwareVersion.cs index 386febc679..08a9f232ef 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.HardwareVersion.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.HardwareVersion.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.NodeStatus.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.NodeStatus.cs index 6ac689884b..e22a14f96e 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.NodeStatus.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.NodeStatus.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.Panic.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.Panic.cs index a3688e0f5e..30b0b61496 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.Panic.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.Panic.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.RestartNode_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.RestartNode_req.cs index d0391e9380..7de54f2df3 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.RestartNode_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.RestartNode_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.RestartNode_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.RestartNode_res.cs index 70079b4995..1cd4690b11 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.RestartNode_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.RestartNode_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.SoftwareVersion.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.SoftwareVersion.cs index 8d39d8b77d..cfc70395b9 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.SoftwareVersion.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.SoftwareVersion.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.KeyValue.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.KeyValue.cs index c03793f337..14b7039669 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.KeyValue.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.KeyValue.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.LogLevel.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.LogLevel.cs index 68d7670401..c73c5e3cb6 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.LogLevel.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.LogLevel.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.LogMessage.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.LogMessage.cs index 5d471573de..c1baa91774 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.LogMessage.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.debug.LogMessage.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.Allocation.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.Allocation.cs index cac4fd6151..d888de9377 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.Allocation.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.Allocation.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.cs index fb8fc82dd4..16e39adf67 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.cs index ab45f83048..76693419d2 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.AppendEntries_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.Discovery.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.Discovery.cs index 4eb517bf5f..3525048a46 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.Discovery.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.Discovery.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.Entry.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.Entry.cs index a4b4e4191f..1c301c281b 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.Entry.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.Entry.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.RequestVote_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.RequestVote_req.cs index 71c363799b..ee4a1e26bc 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.RequestVote_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.RequestVote_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.RequestVote_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.RequestVote_res.cs index 3d2ff25bce..ec42f656a6 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.RequestVote_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.dynamic_node_id.server.RequestVote_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Begin_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Begin_req.cs index 759adfd3d5..e5416abb13 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Begin_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Begin_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Begin_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Begin_res.cs index 4107792c95..2091d0109b 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Begin_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Begin_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Indication.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Indication.cs index 1e06831518..c39ae65dba 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Indication.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.enumeration.Indication.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.BeginFirmwareUpdate_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.BeginFirmwareUpdate_req.cs index b00468cd55..a0228daa9e 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.BeginFirmwareUpdate_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.BeginFirmwareUpdate_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.BeginFirmwareUpdate_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.BeginFirmwareUpdate_res.cs index 8d2698e6ee..e646b5bfb3 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.BeginFirmwareUpdate_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.BeginFirmwareUpdate_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Delete_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Delete_req.cs index 399d7da236..c1bc9486bd 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Delete_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Delete_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Delete_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Delete_res.cs index c80555a82b..a7405ef696 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Delete_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Delete_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.EntryType.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.EntryType.cs index f96611fec6..9a82a072ee 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.EntryType.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.EntryType.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Error.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Error.cs index a08a1c5aea..a2d02b0133 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Error.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Error.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetDirectoryEntryInfo_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetDirectoryEntryInfo_req.cs index 770e70bbf0..8a5fb19608 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetDirectoryEntryInfo_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetDirectoryEntryInfo_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; 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 002453df52..9672b31228 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetDirectoryEntryInfo_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetDirectoryEntryInfo_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; @@ -19,9 +18,9 @@ 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.Path.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/include/uavcan.protocol.file.GetInfo_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetInfo_req.cs index a25e73513e..84444a6fe5 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetInfo_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetInfo_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetInfo_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetInfo_res.cs index da59efbdfb..550fbac196 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetInfo_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.GetInfo_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Path.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Path.cs index adcfb18092..dddc6e3e78 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Path.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Path.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Read_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Read_req.cs index c7c0ca3775..d3c3fcb7ed 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Read_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Read_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Read_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Read_res.cs index ceccd21bb6..2c49a3368a 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Read_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Read_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Write_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Write_req.cs index cd36a7c5d6..44dfa7e592 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Write_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Write_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Write_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Write_res.cs index adff06b3ff..f29c122970 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Write_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.file.Write_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.Empty.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.Empty.cs index 43f8974a65..2c41439fd0 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.Empty.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.Empty.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.ExecuteOpcode_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.ExecuteOpcode_req.cs index bdf1151cee..5d7e1b3f2a 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.ExecuteOpcode_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.ExecuteOpcode_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.ExecuteOpcode_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.ExecuteOpcode_res.cs index e6c4860222..afa7789c48 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.ExecuteOpcode_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.ExecuteOpcode_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.GetSet_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.GetSet_req.cs index 0a65bb25e0..2ce5eefa11 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.GetSet_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.GetSet_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.GetSet_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.GetSet_res.cs index d02375783a..2b78933a9c 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.GetSet_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.GetSet_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; @@ -19,8 +18,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; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.NumericValue.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.NumericValue.cs index 5e0642cdcd..459f56584f 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.NumericValue.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.NumericValue.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.Value.cs b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.Value.cs index 815be9d978..b100522f88 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.Value.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.protocol.param.Value.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Broadcast.cs b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Broadcast.cs index 78a4666349..7b6b9dd067 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Broadcast.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Broadcast.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Call_req.cs b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Call_req.cs index cc2e70ad88..207bc7f890 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Call_req.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Call_req.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Call_res.cs b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Call_res.cs index eb7482356b..fda2cbbe9b 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Call_res.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Call_res.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Protocol.cs b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Protocol.cs index 92b47988ce..e864ea4d2e 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Protocol.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Protocol.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.tunnel.SerialConfig.cs b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.SerialConfig.cs index f242bcdf70..95602762d0 100644 --- a/ExtLibs/DroneCAN/out/include/uavcan.tunnel.SerialConfig.cs +++ b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.SerialConfig.cs @@ -1,4 +1,3 @@ - using uint8_t = System.Byte; using uint16_t = System.UInt16; using uint32_t = System.UInt32; diff --git a/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Targetted.cs b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Targetted.cs new file mode 100644 index 0000000000..636526b177 --- /dev/null +++ b/ExtLibs/DroneCAN/out/include/uavcan.tunnel.Targetted.cs @@ -0,0 +1,55 @@ +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 + { +//using uavcan.tunnel.Protocol.cs + public partial class uavcan_tunnel_Targetted: IDroneCANSerialize + { + public const int UAVCAN_TUNNEL_TARGETTED_MAX_PACK_SIZE = 127; + public const ulong UAVCAN_TUNNEL_TARGETTED_DT_SIG = 0xB138E7EA72A2A2E9; + public const int UAVCAN_TUNNEL_TARGETTED_DT_ID = 3001; + + public const double UAVCAN_TUNNEL_TARGETTED_OPTION_LOCK_PORT = 1; // saturated uint4 + + public uavcan_tunnel_Protocol protocol = new uavcan_tunnel_Protocol(); + public uint8_t target_node = new uint8_t(); + public int8_t serial_id = new int8_t(); + public uint8_t options = new uint8_t(); + public uint32_t baudrate = new uint32_t(); + public uint8_t buffer_len; [MarshalAs(UnmanagedType.ByValArray,SizeConst=120)] public uint8_t[] buffer = Enumerable.Range(1, 120).Select(i => new uint8_t()).ToArray(); + + public void encode(dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan = false) + { + encode_uavcan_tunnel_Targetted(this, chunk_cb, ctx, fdcan); + } + + public void decode(CanardRxTransfer transfer, bool fdcan = false) + { + decode_uavcan_tunnel_Targetted(transfer, this, fdcan); + } + + public static uavcan_tunnel_Targetted ByteArrayToDroneCANMsg(byte[] transfer, int startoffset, bool fdcan = false) + { + var ans = new uavcan_tunnel_Targetted(); + ans.decode(new DroneCAN.CanardRxTransfer(transfer.Skip(startoffset).ToArray()), fdcan); + return ans; + } + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.himark.servo.ServoCmd.cs b/ExtLibs/DroneCAN/out/src/com.himark.servo.ServoCmd.cs new file mode 100644 index 0000000000..f504698737 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.himark.servo.ServoCmd.cs @@ -0,0 +1,63 @@ + +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_com_himark_servo_ServoCmd(com_himark_servo_ServoCmd msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_himark_servo_ServoCmd(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_himark_servo_ServoCmd(CanardRxTransfer transfer, com_himark_servo_ServoCmd msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_himark_servo_ServoCmd(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_himark_servo_ServoCmd(uint8_t[] buffer, com_himark_servo_ServoCmd msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + if (!tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 5, msg.cmd_len); + chunk_cb(buffer, 5, ctx); + } + for (int i=0; i < msg.cmd_len; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 10, msg.cmd[i]); + chunk_cb(buffer, 10, ctx); + } + } + + static void _decode_com_himark_servo_ServoCmd(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_himark_servo_ServoCmd msg, bool tao) { + + if (!tao) { + canardDecodeScalar(transfer, bit_ofs, 5, false, ref msg.cmd_len); + bit_ofs += 5; + } else { + msg.cmd_len = (uint8_t)(((transfer.payload_len*8)-bit_ofs)/10); + } + + msg.cmd = new uint16_t[msg.cmd_len]; + for (int i=0; i < msg.cmd_len; i++) { + canardDecodeScalar(transfer, bit_ofs, 10, false, ref msg.cmd[i]); + bit_ofs += 10; + } + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.himark.servo.ServoInfo.cs b/ExtLibs/DroneCAN/out/src/com.himark.servo.ServoInfo.cs new file mode 100644 index 0000000000..101bfb9c55 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.himark.servo.ServoInfo.cs @@ -0,0 +1,94 @@ + +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_com_himark_servo_ServoInfo(com_himark_servo_ServoInfo msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_himark_servo_ServoInfo(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_himark_servo_ServoInfo(CanardRxTransfer transfer, com_himark_servo_ServoInfo msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_himark_servo_ServoInfo(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_himark_servo_ServoInfo(uint8_t[] buffer, com_himark_servo_ServoInfo msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 5, msg.servo_id); + chunk_cb(buffer, 5, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 12, msg.pwm_input); + chunk_cb(buffer, 12, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.pos_cmd); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.pos_sensor); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 12, msg.voltage); + chunk_cb(buffer, 12, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 10, msg.current); + chunk_cb(buffer, 10, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 10, msg.pcb_temp); + chunk_cb(buffer, 10, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 10, msg.motor_temp); + chunk_cb(buffer, 10, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 5, msg.error_status); + chunk_cb(buffer, 5, ctx); + } + + static void _decode_com_himark_servo_ServoInfo(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_himark_servo_ServoInfo msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 5, false, ref msg.servo_id); + bit_ofs += 5; + + canardDecodeScalar(transfer, bit_ofs, 12, false, ref msg.pwm_input); + bit_ofs += 12; + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.pos_cmd); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.pos_sensor); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 12, false, ref msg.voltage); + bit_ofs += 12; + + canardDecodeScalar(transfer, bit_ofs, 10, false, ref msg.current); + bit_ofs += 10; + + canardDecodeScalar(transfer, bit_ofs, 10, false, ref msg.pcb_temp); + bit_ofs += 10; + + canardDecodeScalar(transfer, bit_ofs, 10, false, ref msg.motor_temp); + bit_ofs += 10; + + canardDecodeScalar(transfer, bit_ofs, 5, false, ref msg.error_status); + bit_ofs += 5; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetEscID.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetEscID.cs new file mode 100644 index 0000000000..114596449e --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetEscID.cs @@ -0,0 +1,63 @@ + +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_com_hobbywing_esc_GetEscID(com_hobbywing_esc_GetEscID msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_GetEscID(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_GetEscID(CanardRxTransfer transfer, com_hobbywing_esc_GetEscID msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_GetEscID(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_GetEscID(uint8_t[] buffer, com_hobbywing_esc_GetEscID msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + if (!tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 2, msg.payload_len); + chunk_cb(buffer, 2, ctx); + } + for (int i=0; i < msg.payload_len; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.payload[i]); + chunk_cb(buffer, 8, ctx); + } + } + + static void _decode_com_hobbywing_esc_GetEscID(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_GetEscID msg, bool tao) { + + if (!tao) { + canardDecodeScalar(transfer, bit_ofs, 2, false, ref msg.payload_len); + bit_ofs += 2; + } else { + msg.payload_len = (uint8_t)(((transfer.payload_len*8)-bit_ofs)/8); + } + + msg.payload = new uint8_t[msg.payload_len]; + for (int i=0; i < msg.payload_len; i++) { + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.payload[i]); + bit_ofs += 8; + } + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMaintenanceInformation_req.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMaintenanceInformation_req.cs new file mode 100644 index 0000000000..7efc4c0880 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMaintenanceInformation_req.cs @@ -0,0 +1,46 @@ + +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_com_hobbywing_esc_GetMaintenanceInformation_req(com_hobbywing_esc_GetMaintenanceInformation_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_GetMaintenanceInformation_req(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_GetMaintenanceInformation_req(CanardRxTransfer transfer, com_hobbywing_esc_GetMaintenanceInformation_req msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_GetMaintenanceInformation_req(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_GetMaintenanceInformation_req(uint8_t[] buffer, com_hobbywing_esc_GetMaintenanceInformation_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.option); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_GetMaintenanceInformation_req(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_GetMaintenanceInformation_req msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.option); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMaintenanceInformation_res.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMaintenanceInformation_res.cs new file mode 100644 index 0000000000..71189643b0 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMaintenanceInformation_res.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; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + static void encode_com_hobbywing_esc_GetMaintenanceInformation_res(com_hobbywing_esc_GetMaintenanceInformation_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_GetMaintenanceInformation_res(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_GetMaintenanceInformation_res(CanardRxTransfer transfer, com_hobbywing_esc_GetMaintenanceInformation_res msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_GetMaintenanceInformation_res(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_GetMaintenanceInformation_res(uint8_t[] buffer, com_hobbywing_esc_GetMaintenanceInformation_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.total_rotation_time_min); + chunk_cb(buffer, 32, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 24, msg.time_since_maintainence_min); + chunk_cb(buffer, 24, ctx); + } + + static void _decode_com_hobbywing_esc_GetMaintenanceInformation_res(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_GetMaintenanceInformation_res msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.total_rotation_time_min); + bit_ofs += 32; + + canardDecodeScalar(transfer, bit_ofs, 24, false, ref msg.time_since_maintainence_min); + bit_ofs += 24; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMajorConfig_req.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMajorConfig_req.cs new file mode 100644 index 0000000000..3a9d294b44 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMajorConfig_req.cs @@ -0,0 +1,46 @@ + +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_com_hobbywing_esc_GetMajorConfig_req(com_hobbywing_esc_GetMajorConfig_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_GetMajorConfig_req(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_GetMajorConfig_req(CanardRxTransfer transfer, com_hobbywing_esc_GetMajorConfig_req msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_GetMajorConfig_req(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_GetMajorConfig_req(uint8_t[] buffer, com_hobbywing_esc_GetMajorConfig_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.option); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_GetMajorConfig_req(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_GetMajorConfig_req msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.option); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMajorConfig_res.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMajorConfig_res.cs new file mode 100644 index 0000000000..a415e4b059 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.GetMajorConfig_res.cs @@ -0,0 +1,98 @@ + +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_com_hobbywing_esc_GetMajorConfig_res(com_hobbywing_esc_GetMajorConfig_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_GetMajorConfig_res(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_GetMajorConfig_res(CanardRxTransfer transfer, com_hobbywing_esc_GetMajorConfig_res msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_GetMajorConfig_res(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_GetMajorConfig_res(uint8_t[] buffer, com_hobbywing_esc_GetMajorConfig_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 1, msg.direction); + chunk_cb(buffer, 1, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 1, msg.throttle_source); + chunk_cb(buffer, 1, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 6, msg.throttle_channel); + chunk_cb(buffer, 6, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 5, msg.led_status); + chunk_cb(buffer, 5, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 3, msg.led_color); + chunk_cb(buffer, 3, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 4, msg.MSG2_rate); + chunk_cb(buffer, 4, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 4, msg.MSG1_rate); + chunk_cb(buffer, 4, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.positioning_angle); + chunk_cb(buffer, 16, ctx); + for (int i=0; i < 2; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.reserved[i]); + chunk_cb(buffer, 8, ctx); + } + } + + static void _decode_com_hobbywing_esc_GetMajorConfig_res(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_GetMajorConfig_res msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 1, false, ref msg.direction); + bit_ofs += 1; + + canardDecodeScalar(transfer, bit_ofs, 1, false, ref msg.throttle_source); + bit_ofs += 1; + + canardDecodeScalar(transfer, bit_ofs, 6, false, ref msg.throttle_channel); + bit_ofs += 6; + + canardDecodeScalar(transfer, bit_ofs, 5, false, ref msg.led_status); + bit_ofs += 5; + + canardDecodeScalar(transfer, bit_ofs, 3, false, ref msg.led_color); + bit_ofs += 3; + + canardDecodeScalar(transfer, bit_ofs, 4, false, ref msg.MSG2_rate); + bit_ofs += 4; + + canardDecodeScalar(transfer, bit_ofs, 4, false, ref msg.MSG1_rate); + bit_ofs += 4; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.positioning_angle); + bit_ofs += 16; + + for (int i=0; i < 2; i++) { + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.reserved[i]); + bit_ofs += 8; + } + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.RawCommand.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.RawCommand.cs new file mode 100644 index 0000000000..403f6ee2f0 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.RawCommand.cs @@ -0,0 +1,63 @@ + +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_com_hobbywing_esc_RawCommand(com_hobbywing_esc_RawCommand msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_RawCommand(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_RawCommand(CanardRxTransfer transfer, com_hobbywing_esc_RawCommand msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_RawCommand(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_RawCommand(uint8_t[] buffer, com_hobbywing_esc_RawCommand msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + if (!tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 4, msg.command_len); + chunk_cb(buffer, 4, ctx); + } + for (int i=0; i < msg.command_len; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 14, msg.command[i]); + chunk_cb(buffer, 14, ctx); + } + } + + static void _decode_com_hobbywing_esc_RawCommand(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_RawCommand msg, bool tao) { + + if (!tao) { + canardDecodeScalar(transfer, bit_ofs, 4, false, ref msg.command_len); + bit_ofs += 4; + } else { + msg.command_len = (uint8_t)(((transfer.payload_len*8)-bit_ofs)/14); + } + + msg.command = new int16_t[msg.command_len]; + for (int i=0; i < msg.command_len; i++) { + canardDecodeScalar(transfer, bit_ofs, 14, true, ref msg.command[i]); + bit_ofs += 14; + } + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SelfTest_req.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SelfTest_req.cs new file mode 100644 index 0000000000..9c6e30fbda --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SelfTest_req.cs @@ -0,0 +1,40 @@ + +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_com_hobbywing_esc_SelfTest_req(com_hobbywing_esc_SelfTest_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SelfTest_req(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SelfTest_req(CanardRxTransfer transfer, com_hobbywing_esc_SelfTest_req msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SelfTest_req(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SelfTest_req(uint8_t[] buffer, com_hobbywing_esc_SelfTest_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + } + + static void _decode_com_hobbywing_esc_SelfTest_req(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SelfTest_req msg, bool tao) { + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SelfTest_res.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SelfTest_res.cs new file mode 100644 index 0000000000..7b08a8d1f3 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SelfTest_res.cs @@ -0,0 +1,46 @@ + +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_com_hobbywing_esc_SelfTest_res(com_hobbywing_esc_SelfTest_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SelfTest_res(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SelfTest_res(CanardRxTransfer transfer, com_hobbywing_esc_SelfTest_res msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SelfTest_res(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SelfTest_res(uint8_t[] buffer, com_hobbywing_esc_SelfTest_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.status); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SelfTest_res(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SelfTest_res msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.status); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetAngle_req.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetAngle_req.cs new file mode 100644 index 0000000000..9590c82558 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetAngle_req.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; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + static void encode_com_hobbywing_esc_SetAngle_req(com_hobbywing_esc_SetAngle_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetAngle_req(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetAngle_req(CanardRxTransfer transfer, com_hobbywing_esc_SetAngle_req msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetAngle_req(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetAngle_req(uint8_t[] buffer, com_hobbywing_esc_SetAngle_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.option); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.angle); + chunk_cb(buffer, 16, ctx); + } + + static void _decode_com_hobbywing_esc_SetAngle_req(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetAngle_req msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.option); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.angle); + bit_ofs += 16; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetAngle_res.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetAngle_res.cs new file mode 100644 index 0000000000..97e2c79c11 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetAngle_res.cs @@ -0,0 +1,69 @@ + +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_com_hobbywing_esc_SetAngle_res(com_hobbywing_esc_SetAngle_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetAngle_res(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetAngle_res(CanardRxTransfer transfer, com_hobbywing_esc_SetAngle_res msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetAngle_res(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetAngle_res(uint8_t[] buffer, com_hobbywing_esc_SetAngle_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.option); + chunk_cb(buffer, 8, ctx); + if (!tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 2, msg.angle_len); + chunk_cb(buffer, 2, ctx); + } + for (int i=0; i < msg.angle_len; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.angle[i]); + chunk_cb(buffer, 16, ctx); + } + } + + static void _decode_com_hobbywing_esc_SetAngle_res(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetAngle_res msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.option); + bit_ofs += 8; + + if (!tao) { + canardDecodeScalar(transfer, bit_ofs, 2, false, ref msg.angle_len); + bit_ofs += 2; + } else { + msg.angle_len = (uint8_t)(((transfer.payload_len*8)-bit_ofs)/16); + } + + msg.angle = new uint16_t[msg.angle_len]; + for (int i=0; i < msg.angle_len; i++) { + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.angle[i]); + bit_ofs += 16; + } + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetBaud_req.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetBaud_req.cs new file mode 100644 index 0000000000..d35c2485c6 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetBaud_req.cs @@ -0,0 +1,46 @@ + +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_com_hobbywing_esc_SetBaud_req(com_hobbywing_esc_SetBaud_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetBaud_req(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetBaud_req(CanardRxTransfer transfer, com_hobbywing_esc_SetBaud_req msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetBaud_req(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetBaud_req(uint8_t[] buffer, com_hobbywing_esc_SetBaud_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.baud); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SetBaud_req(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetBaud_req msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.baud); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetBaud_res.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetBaud_res.cs new file mode 100644 index 0000000000..842f80fb4b --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetBaud_res.cs @@ -0,0 +1,40 @@ + +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_com_hobbywing_esc_SetBaud_res(com_hobbywing_esc_SetBaud_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetBaud_res(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetBaud_res(CanardRxTransfer transfer, com_hobbywing_esc_SetBaud_res msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetBaud_res(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetBaud_res(uint8_t[] buffer, com_hobbywing_esc_SetBaud_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + } + + static void _decode_com_hobbywing_esc_SetBaud_res(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetBaud_res msg, bool tao) { + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetDirection_req.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetDirection_req.cs new file mode 100644 index 0000000000..af345ab354 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetDirection_req.cs @@ -0,0 +1,46 @@ + +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_com_hobbywing_esc_SetDirection_req(com_hobbywing_esc_SetDirection_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetDirection_req(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetDirection_req(CanardRxTransfer transfer, com_hobbywing_esc_SetDirection_req msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetDirection_req(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetDirection_req(uint8_t[] buffer, com_hobbywing_esc_SetDirection_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.direction); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SetDirection_req(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetDirection_req msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.direction); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetDirection_res.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetDirection_res.cs new file mode 100644 index 0000000000..951b131e33 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetDirection_res.cs @@ -0,0 +1,46 @@ + +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_com_hobbywing_esc_SetDirection_res(com_hobbywing_esc_SetDirection_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetDirection_res(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetDirection_res(CanardRxTransfer transfer, com_hobbywing_esc_SetDirection_res msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetDirection_res(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetDirection_res(uint8_t[] buffer, com_hobbywing_esc_SetDirection_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.direction); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SetDirection_res(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetDirection_res msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.direction); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetID_req.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetID_req.cs new file mode 100644 index 0000000000..155805da28 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetID_req.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; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + static void encode_com_hobbywing_esc_SetID_req(com_hobbywing_esc_SetID_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetID_req(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetID_req(CanardRxTransfer transfer, com_hobbywing_esc_SetID_req msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetID_req(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetID_req(uint8_t[] buffer, com_hobbywing_esc_SetID_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.node_id); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.throttle_channel); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SetID_req(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetID_req msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.node_id); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.throttle_channel); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetID_res.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetID_res.cs new file mode 100644 index 0000000000..0cc8ab95c2 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetID_res.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; +using System.Collections.Generic; + +namespace DroneCAN +{ + public partial class DroneCAN { + static void encode_com_hobbywing_esc_SetID_res(com_hobbywing_esc_SetID_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetID_res(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetID_res(CanardRxTransfer transfer, com_hobbywing_esc_SetID_res msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetID_res(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetID_res(uint8_t[] buffer, com_hobbywing_esc_SetID_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.node_id); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.throttle_channel); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SetID_res(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetID_res msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.node_id); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.throttle_channel); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetLED_req.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetLED_req.cs new file mode 100644 index 0000000000..5ecf38b8a0 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetLED_req.cs @@ -0,0 +1,58 @@ + +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_com_hobbywing_esc_SetLED_req(com_hobbywing_esc_SetLED_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetLED_req(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetLED_req(CanardRxTransfer transfer, com_hobbywing_esc_SetLED_req msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetLED_req(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetLED_req(uint8_t[] buffer, com_hobbywing_esc_SetLED_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.option); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.color); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.blink); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SetLED_req(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetLED_req msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.option); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.color); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.blink); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetLED_res.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetLED_res.cs new file mode 100644 index 0000000000..2e240130fd --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetLED_res.cs @@ -0,0 +1,58 @@ + +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_com_hobbywing_esc_SetLED_res(com_hobbywing_esc_SetLED_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetLED_res(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetLED_res(CanardRxTransfer transfer, com_hobbywing_esc_SetLED_res msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetLED_res(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetLED_res(uint8_t[] buffer, com_hobbywing_esc_SetLED_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.option); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.color); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.blink); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SetLED_res(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetLED_res msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.option); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.color); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.blink); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetReportingFrequency_req.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetReportingFrequency_req.cs new file mode 100644 index 0000000000..54276b2d17 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetReportingFrequency_req.cs @@ -0,0 +1,58 @@ + +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_com_hobbywing_esc_SetReportingFrequency_req(com_hobbywing_esc_SetReportingFrequency_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetReportingFrequency_req(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetReportingFrequency_req(CanardRxTransfer transfer, com_hobbywing_esc_SetReportingFrequency_req msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetReportingFrequency_req(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetReportingFrequency_req(uint8_t[] buffer, com_hobbywing_esc_SetReportingFrequency_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.option); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.MSG_ID); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.rate); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SetReportingFrequency_req(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetReportingFrequency_req msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.option); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.MSG_ID); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.rate); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetReportingFrequency_res.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetReportingFrequency_res.cs new file mode 100644 index 0000000000..d8d1db1654 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetReportingFrequency_res.cs @@ -0,0 +1,58 @@ + +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_com_hobbywing_esc_SetReportingFrequency_res(com_hobbywing_esc_SetReportingFrequency_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetReportingFrequency_res(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetReportingFrequency_res(CanardRxTransfer transfer, com_hobbywing_esc_SetReportingFrequency_res msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetReportingFrequency_res(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetReportingFrequency_res(uint8_t[] buffer, com_hobbywing_esc_SetReportingFrequency_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.option); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.MSG_ID); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.rate); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SetReportingFrequency_res(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetReportingFrequency_res msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.option); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.MSG_ID); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.rate); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetThrottleSource_req.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetThrottleSource_req.cs new file mode 100644 index 0000000000..ab8c679eeb --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetThrottleSource_req.cs @@ -0,0 +1,46 @@ + +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_com_hobbywing_esc_SetThrottleSource_req(com_hobbywing_esc_SetThrottleSource_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetThrottleSource_req(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetThrottleSource_req(CanardRxTransfer transfer, com_hobbywing_esc_SetThrottleSource_req msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetThrottleSource_req(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetThrottleSource_req(uint8_t[] buffer, com_hobbywing_esc_SetThrottleSource_req msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.source); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SetThrottleSource_req(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetThrottleSource_req msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.source); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetThrottleSource_res.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetThrottleSource_res.cs new file mode 100644 index 0000000000..afda6e1d32 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.SetThrottleSource_res.cs @@ -0,0 +1,46 @@ + +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_com_hobbywing_esc_SetThrottleSource_res(com_hobbywing_esc_SetThrottleSource_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_SetThrottleSource_res(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_SetThrottleSource_res(CanardRxTransfer transfer, com_hobbywing_esc_SetThrottleSource_res msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_SetThrottleSource_res(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_SetThrottleSource_res(uint8_t[] buffer, com_hobbywing_esc_SetThrottleSource_res msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.source); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_SetThrottleSource_res(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_SetThrottleSource_res msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.source); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg1.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg1.cs new file mode 100644 index 0000000000..66a25eb894 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg1.cs @@ -0,0 +1,58 @@ + +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_com_hobbywing_esc_StatusMsg1(com_hobbywing_esc_StatusMsg1 msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_StatusMsg1(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_StatusMsg1(CanardRxTransfer transfer, com_hobbywing_esc_StatusMsg1 msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_StatusMsg1(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_StatusMsg1(uint8_t[] buffer, com_hobbywing_esc_StatusMsg1 msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rpm); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.pwm); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.status); + chunk_cb(buffer, 16, ctx); + } + + static void _decode_com_hobbywing_esc_StatusMsg1(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_StatusMsg1 msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rpm); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.pwm); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.status); + bit_ofs += 16; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg2.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg2.cs new file mode 100644 index 0000000000..d9056e6e11 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg2.cs @@ -0,0 +1,58 @@ + +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_com_hobbywing_esc_StatusMsg2(com_hobbywing_esc_StatusMsg2 msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_StatusMsg2(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_StatusMsg2(CanardRxTransfer transfer, com_hobbywing_esc_StatusMsg2 msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_StatusMsg2(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_StatusMsg2(uint8_t[] buffer, com_hobbywing_esc_StatusMsg2 msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.input_voltage); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.current); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.temperature); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_StatusMsg2(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_StatusMsg2 msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.input_voltage); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.current); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.temperature); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg3.cs b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg3.cs new file mode 100644 index 0000000000..33c00109ca --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.hobbywing.esc.StatusMsg3.cs @@ -0,0 +1,58 @@ + +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_com_hobbywing_esc_StatusMsg3(com_hobbywing_esc_StatusMsg3 msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_hobbywing_esc_StatusMsg3(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_hobbywing_esc_StatusMsg3(CanardRxTransfer transfer, com_hobbywing_esc_StatusMsg3 msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_hobbywing_esc_StatusMsg3(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_hobbywing_esc_StatusMsg3(uint8_t[] buffer, com_hobbywing_esc_StatusMsg3 msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.MOS_T); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.CAP_T); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.Motor_T); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_hobbywing_esc_StatusMsg3(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_hobbywing_esc_StatusMsg3 msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.MOS_T); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.CAP_T); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.Motor_T); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.xacti.CopterAttStatus.cs b/ExtLibs/DroneCAN/out/src/com.xacti.CopterAttStatus.cs new file mode 100644 index 0000000000..9c52c76cfb --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.xacti.CopterAttStatus.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 { + static void encode_com_xacti_CopterAttStatus(com_xacti_CopterAttStatus msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_xacti_CopterAttStatus(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_xacti_CopterAttStatus(CanardRxTransfer transfer, com_xacti_CopterAttStatus msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_xacti_CopterAttStatus(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_xacti_CopterAttStatus(uint8_t[] buffer, com_xacti_CopterAttStatus msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + for (int i=0; i < 4; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.quaternion_wxyz_e4[i]); + chunk_cb(buffer, 16, ctx); + } + if (!tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 2, msg.reserved_len); + chunk_cb(buffer, 2, ctx); + } + for (int i=0; i < msg.reserved_len; i++) { + memset(buffer,0,8); + { + uint16_t float16_val = canardConvertNativeFloatToFloat16(msg.reserved[i]); + canardEncodeScalar(buffer, 0, 16, float16_val); + } + chunk_cb(buffer, 16, ctx); + } + } + + static void _decode_com_xacti_CopterAttStatus(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_xacti_CopterAttStatus msg, bool tao) { + + for (int i=0; i < 4; i++) { + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.quaternion_wxyz_e4[i]); + bit_ofs += 16; + } + + if (!tao) { + canardDecodeScalar(transfer, bit_ofs, 2, false, ref msg.reserved_len); + bit_ofs += 2; + } else { + msg.reserved_len = (uint8_t)(((transfer.payload_len*8)-bit_ofs)/16); + } + + msg.reserved = new Single[msg.reserved_len]; + for (int i=0; i < msg.reserved_len; i++) { + { + uint16_t float16_val = 0; + canardDecodeScalar(transfer, bit_ofs, 16, true, ref float16_val); + msg.reserved[i] = canardConvertFloat16ToNativeFloat(float16_val); + } + bit_ofs += 16; + } + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.xacti.GimbalAttitudeStatus.cs b/ExtLibs/DroneCAN/out/src/com.xacti.GimbalAttitudeStatus.cs new file mode 100644 index 0000000000..db50b3e923 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.xacti.GimbalAttitudeStatus.cs @@ -0,0 +1,76 @@ + +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_com_xacti_GimbalAttitudeStatus(com_xacti_GimbalAttitudeStatus msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_xacti_GimbalAttitudeStatus(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_xacti_GimbalAttitudeStatus(CanardRxTransfer transfer, com_xacti_GimbalAttitudeStatus msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_xacti_GimbalAttitudeStatus(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_xacti_GimbalAttitudeStatus(uint8_t[] buffer, com_xacti_GimbalAttitudeStatus msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.gimbal_roll); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.gimbal_pitch); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.gimbal_yaw); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.magneticencoder_roll); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.magneticencoder_pitch); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.magneticencoder_yaw); + chunk_cb(buffer, 16, ctx); + } + + static void _decode_com_xacti_GimbalAttitudeStatus(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_xacti_GimbalAttitudeStatus msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.gimbal_roll); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.gimbal_pitch); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.gimbal_yaw); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.magneticencoder_roll); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.magneticencoder_pitch); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, true, ref msg.magneticencoder_yaw); + bit_ofs += 16; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.xacti.GimbalControlData.cs b/ExtLibs/DroneCAN/out/src/com.xacti.GimbalControlData.cs new file mode 100644 index 0000000000..a5236e15c0 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.xacti.GimbalControlData.cs @@ -0,0 +1,64 @@ + +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_com_xacti_GimbalControlData(com_xacti_GimbalControlData msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_xacti_GimbalControlData(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_xacti_GimbalControlData(CanardRxTransfer transfer, com_xacti_GimbalControlData msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_xacti_GimbalControlData(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_xacti_GimbalControlData(uint8_t[] buffer, com_xacti_GimbalControlData msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.pitch_cmd_type); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.yaw_cmd_type); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.pitch_cmd_value); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.yaw_cmd_value); + chunk_cb(buffer, 16, ctx); + } + + static void _decode_com_xacti_GimbalControlData(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_xacti_GimbalControlData msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.pitch_cmd_type); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.yaw_cmd_type); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.pitch_cmd_value); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.yaw_cmd_value); + bit_ofs += 16; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.xacti.GnssStatus.cs b/ExtLibs/DroneCAN/out/src/com.xacti.GnssStatus.cs new file mode 100644 index 0000000000..d317a8dcc9 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.xacti.GnssStatus.cs @@ -0,0 +1,112 @@ + +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_com_xacti_GnssStatus(com_xacti_GnssStatus msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_xacti_GnssStatus(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_xacti_GnssStatus(CanardRxTransfer transfer, com_xacti_GnssStatus msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_xacti_GnssStatus(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_xacti_GnssStatus(uint8_t[] buffer, com_xacti_GnssStatus msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.gps_status); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.order); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.remain_buffer); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.utc_year); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.utc_month); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.utc_day); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.utc_hour); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.utc_minute); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.utc_seconds); + chunk_cb(buffer, 32, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 64, msg.latitude); + chunk_cb(buffer, 64, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 64, msg.longitude); + chunk_cb(buffer, 64, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.altitude); + chunk_cb(buffer, 32, ctx); + } + + static void _decode_com_xacti_GnssStatus(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_xacti_GnssStatus msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.gps_status); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.order); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.remain_buffer); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.utc_year); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.utc_month); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.utc_day); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.utc_hour); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.utc_minute); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 32, true, ref msg.utc_seconds); + bit_ofs += 32; + + canardDecodeScalar(transfer, bit_ofs, 64, true, ref msg.latitude); + bit_ofs += 64; + + canardDecodeScalar(transfer, bit_ofs, 64, true, ref msg.longitude); + bit_ofs += 64; + + canardDecodeScalar(transfer, bit_ofs, 32, true, ref msg.altitude); + bit_ofs += 32; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/com.xacti.GnssStatusReq.cs b/ExtLibs/DroneCAN/out/src/com.xacti.GnssStatusReq.cs new file mode 100644 index 0000000000..3d66137657 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/com.xacti.GnssStatusReq.cs @@ -0,0 +1,46 @@ + +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_com_xacti_GnssStatusReq(com_xacti_GnssStatusReq msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_com_xacti_GnssStatusReq(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_com_xacti_GnssStatusReq(CanardRxTransfer transfer, com_xacti_GnssStatusReq msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_com_xacti_GnssStatusReq(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_com_xacti_GnssStatusReq(uint8_t[] buffer, com_xacti_GnssStatusReq msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.requirement); + chunk_cb(buffer, 8, ctx); + } + + static void _decode_com_xacti_GnssStatusReq(CanardRxTransfer transfer,ref uint32_t bit_ofs, com_xacti_GnssStatusReq msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.requirement); + bit_ofs += 8; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/dronecan.protocol.CanStats.cs b/ExtLibs/DroneCAN/out/src/dronecan.protocol.CanStats.cs new file mode 100644 index 0000000000..972ab2e557 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/dronecan.protocol.CanStats.cs @@ -0,0 +1,106 @@ + +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_protocol_CanStats(dronecan_protocol_CanStats msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_dronecan_protocol_CanStats(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_dronecan_protocol_CanStats(CanardRxTransfer transfer, dronecan_protocol_CanStats msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_dronecan_protocol_CanStats(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_dronecan_protocol_CanStats(uint8_t[] buffer, dronecan_protocol_CanStats msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.@interface); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.tx_requests); + chunk_cb(buffer, 32, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.tx_rejected); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.tx_overflow); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.tx_success); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.tx_timedout); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.tx_abort); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.rx_received); + chunk_cb(buffer, 32, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rx_overflow); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rx_errors); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.busoff_errors); + chunk_cb(buffer, 16, ctx); + } + + static void _decode_dronecan_protocol_CanStats(CanardRxTransfer transfer,ref uint32_t bit_ofs, dronecan_protocol_CanStats msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.@interface); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.tx_requests); + bit_ofs += 32; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.tx_rejected); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.tx_overflow); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.tx_success); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.tx_timedout); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.tx_abort); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.rx_received); + bit_ofs += 32; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rx_overflow); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rx_errors); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.busoff_errors); + bit_ofs += 16; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/dronecan.protocol.Stats.cs b/ExtLibs/DroneCAN/out/src/dronecan.protocol.Stats.cs new file mode 100644 index 0000000000..5dd0adb81e --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/dronecan.protocol.Stats.cs @@ -0,0 +1,112 @@ + +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_protocol_Stats(dronecan_protocol_Stats msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_dronecan_protocol_Stats(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_dronecan_protocol_Stats(CanardRxTransfer transfer, dronecan_protocol_Stats msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_dronecan_protocol_Stats(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_dronecan_protocol_Stats(uint8_t[] buffer, dronecan_protocol_Stats msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.tx_frames); + chunk_cb(buffer, 32, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.tx_errors); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 32, msg.rx_frames); + chunk_cb(buffer, 32, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rx_error_oom); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rx_error_internal); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rx_error_missed_start); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rx_error_wrong_toggle); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rx_error_short_frame); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rx_error_bad_crc); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rx_ignored_wrong_address); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rx_ignored_not_wanted); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.rx_ignored_unexpected_tid); + chunk_cb(buffer, 16, ctx); + } + + static void _decode_dronecan_protocol_Stats(CanardRxTransfer transfer,ref uint32_t bit_ofs, dronecan_protocol_Stats msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.tx_frames); + bit_ofs += 32; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.tx_errors); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 32, false, ref msg.rx_frames); + bit_ofs += 32; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rx_error_oom); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rx_error_internal); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rx_error_missed_start); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rx_error_wrong_toggle); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rx_error_short_frame); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rx_error_bad_crc); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rx_ignored_wrong_address); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rx_ignored_not_wanted); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.rx_ignored_unexpected_tid); + bit_ofs += 16; + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/dronecan.sensors.rc.RCInput.cs b/ExtLibs/DroneCAN/out/src/dronecan.sensors.rc.RCInput.cs new file mode 100644 index 0000000000..bed1d9c192 --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/dronecan.sensors.rc.RCInput.cs @@ -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_sensors_rc_RCInput(dronecan_sensors_rc_RCInput msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_dronecan_sensors_rc_RCInput(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_dronecan_sensors_rc_RCInput(CanardRxTransfer transfer, dronecan_sensors_rc_RCInput msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_dronecan_sensors_rc_RCInput(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_dronecan_sensors_rc_RCInput(uint8_t[] buffer, dronecan_sensors_rc_RCInput msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 16, msg.status); + chunk_cb(buffer, 16, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.quality); + chunk_cb(buffer, 8, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 4, msg.id); + chunk_cb(buffer, 4, ctx); + if (!tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 6, msg.rcin_len); + chunk_cb(buffer, 6, ctx); + } + for (int i=0; i < msg.rcin_len; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 12, msg.rcin[i]); + chunk_cb(buffer, 12, ctx); + } + } + + static void _decode_dronecan_sensors_rc_RCInput(CanardRxTransfer transfer,ref uint32_t bit_ofs, dronecan_sensors_rc_RCInput msg, bool tao) { + + canardDecodeScalar(transfer, bit_ofs, 16, false, ref msg.status); + bit_ofs += 16; + + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.quality); + bit_ofs += 8; + + canardDecodeScalar(transfer, bit_ofs, 4, false, ref msg.id); + bit_ofs += 4; + + if (!tao) { + canardDecodeScalar(transfer, bit_ofs, 6, false, ref msg.rcin_len); + bit_ofs += 6; + } else { + msg.rcin_len = (uint8_t)(((transfer.payload_len*8)-bit_ofs)/12); + } + + msg.rcin = new uint16_t[msg.rcin_len]; + for (int i=0; i < msg.rcin_len; i++) { + canardDecodeScalar(transfer, bit_ofs, 12, false, ref msg.rcin[i]); + bit_ofs += 12; + } + + } + } +} \ No newline at end of file diff --git a/ExtLibs/DroneCAN/out/src/uavcan.tunnel.Targetted.cs b/ExtLibs/DroneCAN/out/src/uavcan.tunnel.Targetted.cs new file mode 100644 index 0000000000..6ad3b0aead --- /dev/null +++ b/ExtLibs/DroneCAN/out/src/uavcan.tunnel.Targetted.cs @@ -0,0 +1,90 @@ + +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_uavcan_tunnel_Targetted(uavcan_tunnel_Targetted msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool fdcan) { + uint8_t[] buffer = new uint8_t[8]; + _encode_uavcan_tunnel_Targetted(buffer, msg, chunk_cb, ctx, !fdcan); + } + + static uint32_t decode_uavcan_tunnel_Targetted(CanardRxTransfer transfer, uavcan_tunnel_Targetted msg, bool fdcan) { + uint32_t bit_ofs = 0; + _decode_uavcan_tunnel_Targetted(transfer, ref bit_ofs, msg, !fdcan); + return (bit_ofs+7)/8; + } + + static void _encode_uavcan_tunnel_Targetted(uint8_t[] buffer, uavcan_tunnel_Targetted msg, dronecan_serializer_chunk_cb_ptr_t chunk_cb, object ctx, bool tao) { + _encode_uavcan_tunnel_Protocol(buffer, msg.protocol, chunk_cb, ctx, false); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 7, msg.target_node); + chunk_cb(buffer, 7, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 5, msg.serial_id); + chunk_cb(buffer, 5, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 4, msg.options); + chunk_cb(buffer, 4, ctx); + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 24, msg.baudrate); + chunk_cb(buffer, 24, ctx); + if (!tao) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 7, msg.buffer_len); + chunk_cb(buffer, 7, ctx); + } + for (int i=0; i < msg.buffer_len; i++) { + memset(buffer,0,8); + canardEncodeScalar(buffer, 0, 8, msg.buffer[i]); + chunk_cb(buffer, 8, ctx); + } + } + + static void _decode_uavcan_tunnel_Targetted(CanardRxTransfer transfer,ref uint32_t bit_ofs, uavcan_tunnel_Targetted msg, bool tao) { + + _decode_uavcan_tunnel_Protocol(transfer, ref bit_ofs, msg.protocol, false); + + canardDecodeScalar(transfer, bit_ofs, 7, false, ref msg.target_node); + bit_ofs += 7; + + canardDecodeScalar(transfer, bit_ofs, 5, true, ref msg.serial_id); + bit_ofs += 5; + + canardDecodeScalar(transfer, bit_ofs, 4, false, ref msg.options); + bit_ofs += 4; + + canardDecodeScalar(transfer, bit_ofs, 24, false, ref msg.baudrate); + bit_ofs += 24; + + if (!tao) { + canardDecodeScalar(transfer, bit_ofs, 7, false, ref msg.buffer_len); + bit_ofs += 7; + } else { + msg.buffer_len = (uint8_t)(((transfer.payload_len*8)-bit_ofs)/8); + } + + msg.buffer = new uint8_t[msg.buffer_len]; + for (int i=0; i < msg.buffer_len; i++) { + canardDecodeScalar(transfer, bit_ofs, 8, false, ref msg.buffer[i]); + bit_ofs += 8; + } + + } + } +} \ No newline at end of file