From ffb95b2e7dea9b4c9fb2e73354c41d772bb94be9 Mon Sep 17 00:00:00 2001 From: xu Date: Sun, 30 Jun 2024 11:15:19 +0800 Subject: [PATCH] =?UTF-8?q?[feat]=20=E5=A2=9E=E5=8A=A0=E5=B9=BF=E6=92=AD?= =?UTF-8?q?=E9=80=9A=E9=81=93=E5=8F=91=E9=80=81=E5=85=B3=E9=94=AE=E6=8C=87?= =?UTF-8?q?=E4=BB=A4=20=E8=AF=A6=E7=BB=86=E6=8F=8F=E8=BF=B0?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # 类型 包含: # feat:新功能(feature) # fix:修补bug # docs:文档(documentation) # style: 格式(不影响代码运行的变动) # refactor:重构(即不是新增功能,也不是修改bug的代码变动) # test:增加测试 # chore:构建过程或辅助工具的变动 --- .../CommModuleGenerateMavLink.cs | 53 +++++++++++++++---- 1 file changed, 43 insertions(+), 10 deletions(-) diff --git a/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs b/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs index 22a845e..c68e7e0 100644 --- a/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs +++ b/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs @@ -487,8 +487,14 @@ namespace Plane.CommunicationManagement short copterId = 0; byte[] batchPacket = null; //部分开始任务 - if (copters!=null) - GetCopterIds(copters, out copterId, out batchPacket); + if (copters != null) + GetCopterIds(copters, out copterId, out batchPacket); + else + { + //只有全部飞机才广播 + if (Recomisopen) + await BroadcastSendAsync(packet); + } await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false); } @@ -502,7 +508,10 @@ namespace Plane.CommunicationManagement { byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.MISSION_START, 0, 0, 0, 0, 0, 1, 0); await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false); - }else + if (Recomisopen) + await BroadcastSendAsync(packet); + } + else Windows.Messages.Message.Show($"未开发完成!!"); } @@ -515,7 +524,10 @@ namespace Plane.CommunicationManagement { byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.MISSION_START, hour_utc, minute_utc, second_utc, 0, 0, 2, 0); await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false); - }else + if (Recomisopen) + await BroadcastSendAsync(packet); + } + else Windows.Messages.Message.Show($"未开发完成!!"); } @@ -613,6 +625,8 @@ namespace Plane.CommunicationManagement byte[] packet = DoLEDCommandAsync(); await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false); + if (Recomisopen&&(copters == null)) + await BroadcastSendAsync(packet); }); } else @@ -671,6 +685,8 @@ namespace Plane.CommunicationManagement byte[] packet = SetParam2Async(paramname, value); int packetNum = packet[2]; await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false); + if (Recomisopen && (copters == null)) + await BroadcastSendAsync(packet); return packetNum; } else @@ -868,6 +884,8 @@ namespace Plane.CommunicationManagement short copterId = 0; byte[] batchPacket = null; await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false); + if (Recomisopen) + await BroadcastSendAsync(packet); } else { @@ -916,6 +934,8 @@ namespace Plane.CommunicationManagement byte[] packet = SetModeAsync(FlightMode.LAND); await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false); + if (Recomisopen&&(copters == null)) + await BroadcastSendAsync(packet); } else { @@ -950,6 +970,8 @@ namespace Plane.CommunicationManagement byte[] data = packet1.Concat(packet2).ToArray(); await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false); + if (Recomisopen&&(copters == null)) + await BroadcastSendAsync(data); } else { @@ -1224,8 +1246,13 @@ namespace Plane.CommunicationManagement /// public async Task BroadcastSendAsync(byte[] packet,bool reopensend = false) { - + bool sendok = false; + //并且没有最后打开的端口说明已经人为关闭了 + if (last_reserialport == "") + { + return; + } try { //防止阻塞,异步发送 @@ -1240,6 +1267,7 @@ namespace Plane.CommunicationManagement if (!sendok&& reopensend) { + //再次打开串口 try { ReOpenRtcmserial(); @@ -1248,8 +1276,9 @@ namespace Plane.CommunicationManagement catch (Exception ex) { Windows.Messages.Message.Show("再次打开串口失败" + ex.Message); - ReOpenRtcmserial(); + return; } + //再次发送 if (Recomisopen) { try @@ -1440,7 +1469,7 @@ namespace Plane.CommunicationManagement await Task.Delay(1); } - string last_reserialport; + string last_reserialport=""; public void ReOpenRtcmserial() { CloseResendRtcmserial(); @@ -1448,7 +1477,7 @@ namespace Plane.CommunicationManagement } - public void CloseResendRtcmserial() + public void CloseResendRtcmserial(bool cleanport=false) { if (Recomisopen) { @@ -1456,15 +1485,19 @@ namespace Plane.CommunicationManagement RecomPort.Dispose(); } Recomisopen = false; + //清除端口 + if (cleanport) + last_reserialport=""; + } public string BoardPortStatusStr { get { if (Recomisopen) - return "已打开"+ last_reserialport; + return "广播端口已打开"; else - return "端口未打开"; + return "广播端口未打开"; } }