From 8f2cd98bd49189661d936cdf58c90beb8fe99b2a Mon Sep 17 00:00:00 2001 From: xu Date: Mon, 27 Dec 2021 12:41:32 +0800 Subject: [PATCH] =?UTF-8?q?1.=E5=8A=A0=E5=85=A5=E5=9B=9E=E4=BC=A0=E5=8A=9F?= =?UTF-8?q?=E7=8E=87=E8=AE=BE=E7=BD=AE=202.=E6=9C=8D=E5=8A=A1=E5=99=A8IP?= =?UTF-8?q?=E5=8F=AF=E4=BB=8E=E8=AE=BE=E7=BD=AE=E6=96=87=E4=BB=B6=E8=AF=BB?= =?UTF-8?q?=E5=8F=96=203.=E5=A2=9E=E5=8A=A0=E6=8A=9B=E7=89=A9=E5=8A=9F?= =?UTF-8?q?=E8=83=BD?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../CommunicationManagement/CommModule.cs | 39 ++++++++++++- .../CommModuleGenerateMavLink.cs | 57 ++++++++++++++++++- .../CommModulePacketAnalysis.cs | 4 ++ PlaneGcsSdk_Shared/Protocols/MavCommTypes.cs | 8 +++ 4 files changed, 102 insertions(+), 6 deletions(-) diff --git a/PlaneGcsSdk_Shared/CommunicationManagement/CommModule.cs b/PlaneGcsSdk_Shared/CommunicationManagement/CommModule.cs index e6efbb7..9549ece 100644 --- a/PlaneGcsSdk_Shared/CommunicationManagement/CommModule.cs +++ b/PlaneGcsSdk_Shared/CommunicationManagement/CommModule.cs @@ -12,17 +12,23 @@ using System.Text; using System.Threading.Tasks; using System.Windows.Media; +using System.Runtime.InteropServices; + namespace Plane.CommunicationManagement { //通信模块 public partial class CommModuleManager: ExceptionThrownEventSource, IDisposable { + [DllImport("kernel32")] //返回取得字符串缓冲区的长度 + private static extern int GetPrivateProfileString(string section, string key, string def, StringBuilder retVal, int size, string filePath); + private static CommModuleManager _Instance = new CommModuleManager(); public static CommModuleManager Instance { get { return _Instance; } } public TcpConnection Connection = null; public bool CommOK = false; - private const string MODULE_IP = "192.168.199.51"; // "192.168.199.51"; //在用版本 ----//"192.168.1.65"; //新版本 + private const string MODULE_IP = "192.168.199.51"; //"192.168.199.51"; // "192.168.199.51"; //在用版本 ----//"192.168.1.65"; //新版本 + private string ServerIP = MODULE_IP; // private const string LOCAL_IP = "192.168.199.50"; //"192.168.199.50"; private const int PORT = 9551; private bool _disposed; @@ -36,17 +42,32 @@ namespace Plane.CommunicationManagement /// private Stopwatch _writeMissionStopwatch; + private void LoadIPSet() + { + StringBuilder temp = new StringBuilder(255); + + string path = Environment.CurrentDirectory + @"\Config.ini"; + + int i = GetPrivateProfileString("Default", "ServerIP", "", temp, 255, path); + ServerIP= temp.ToString(); + + if (ServerIP == "") ServerIP = MODULE_IP; + } + + public async Task ConnectAsync() { - Connection = new TcpConnection(MODULE_IP, PORT); + LoadIPSet(); + Connection = new TcpConnection(ServerIP, PORT); await ConnectOpenAsync(); } public void Connect() { + LoadIPSet(); Task.Run(async () => { - Connection = new TcpConnection(MODULE_IP, PORT); + Connection = new TcpConnection(ServerIP, PORT); await ConnectOpenAsync(); } ); @@ -371,6 +392,18 @@ namespace Plane.CommunicationManagement + public async Task SetModulePower(short ModuleNo, short ModulePower) + { + byte[] packet = { 0x01, 0x00, 0x03, 0x00, 0x01, 0x0A }; + packet[2] = (byte)(ModuleNo & 0xFF); + packet[3] = (byte)((ModuleNo & 0xFF00) >> 8); + packet[5] = (byte)(ModulePower); + await WriteCommPacketAsync(0, MavComm.COMM_TO_MODULE, packet); + } + + + + bool temp = false; //测试用 灯光间隔1S闪烁 diff --git a/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs b/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs index 7121630..5b458ca 100644 --- a/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs +++ b/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs @@ -201,6 +201,18 @@ namespace Plane.CommunicationManagement return GeneratePacket(MAVLink.MAVLINK_MSG_ID_LED_CONTROL, led); } + private byte[] DoThrowoutCommandAsync() + { + MAVLink.mavlink_msg_id_led_control led = new MAVLink.mavlink_msg_id_led_control(); + led.target_system = 1; + led.target_component = 1;//(byte)MAVLink.MAV_COMPONENT.MAV_COMP_ID_SYSTEM_CONTROL;; + led.instance = 0; + led.pattern = 0; + led.custom_len = 1; //长度是1个字节 + led.custom_bytes = new byte[24]; + led.custom_bytes[0] = (byte)10; //10代表抛物 + return GeneratePacket(MAVLink.MAVLINK_MSG_ID_LED_CONTROL, led); + } private byte[] DoTaskLEDCommandAsync(int ledmode, float ledInterval, int ledtimes, byte cR,byte cG,Byte cB) @@ -442,7 +454,7 @@ namespace Plane.CommunicationManagement public async Task DoMissionStartAsync(IEnumerable copters,int hour_utc, int minute_utc, int second_utc, double Missionlng, double Missionlat) { if (UseTransModule) - await DoMissionStartAsync_CMod(hour_utc, minute_utc, second_utc, Missionlng, Missionlat); + await DoMissionStartAsync_CMod(copters,hour_utc, minute_utc, second_utc, Missionlng, Missionlat); else await DoMissionStartAsync_Single(copters, hour_utc, minute_utc, second_utc, Missionlng, Missionlat); } @@ -462,10 +474,16 @@ namespace Plane.CommunicationManagement } - public async Task DoMissionStartAsync_CMod(int hour_utc, int minute_utc, int second_utc, double Missionlng, double Missionlat) + public async Task DoMissionStartAsync_CMod(IEnumerable copters,int hour_utc, int minute_utc, int second_utc, double Missionlng, double Missionlat) { + byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.MISSION_START, hour_utc, minute_utc, second_utc, (float)Missionlng, (float)Missionlat, 0, -1); - await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false); + short copterId = 0; + byte[] batchPacket = null; + //部分开始任务 + if (copters!=null) + GetCopterIds(copters, out copterId, out batchPacket); + await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false); } @@ -529,6 +547,39 @@ namespace Plane.CommunicationManagement } } + + /// + /// 抛物 + /// + /// 要解锁的飞机 + /// + public void ThrowoutAsync(IEnumerable copters = null) + { + if (UseTransModule) + { + Task.Run(async () => + { + short copterId = 0; + byte[] batchPacket = null; + GetCopterIds(copters, out copterId, out batchPacket); + + byte[] packet = DoThrowoutCommandAsync(); + await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false); + }); + } + else + { + /* + Task.Run(async () => + { + foreach (var vcopter in copters) + await vcopter.LEDAsync(); + }); + */ + + } + } + /// /// LED闪烁白灯 /// diff --git a/PlaneGcsSdk_Shared/CommunicationManagement/CommModulePacketAnalysis.cs b/PlaneGcsSdk_Shared/CommunicationManagement/CommModulePacketAnalysis.cs index ff332c1..d1a1c09 100644 --- a/PlaneGcsSdk_Shared/CommunicationManagement/CommModulePacketAnalysis.cs +++ b/PlaneGcsSdk_Shared/CommunicationManagement/CommModulePacketAnalysis.cs @@ -104,6 +104,10 @@ namespace Plane.CommunicationManagement SaveMissionWriteStat(copterId, buffer[1]); break; + case 0x04: + Message.Show($"飞机{copterId}:功率设置成功,新回传功率:{buffer[1]}"); + break; + case 0x0e: if (copterId == 0) Message.Show("----------全部更新完成----------"); diff --git a/PlaneGcsSdk_Shared/Protocols/MavCommTypes.cs b/PlaneGcsSdk_Shared/Protocols/MavCommTypes.cs index 242b8d9..91da9cb 100644 --- a/PlaneGcsSdk_Shared/Protocols/MavCommTypes.cs +++ b/PlaneGcsSdk_Shared/Protocols/MavCommTypes.cs @@ -74,6 +74,14 @@ namespace Plane.Protocols /// public const short COMM_FLIGHT_LOAD_MODE = 0x55; + + /// + /// 发送非针对飞控的内部控制指令 + /// + public const short COMM_TO_MODULE = 0x5F; + + + /// /// 通信模块 ///