From 40bf208054455dce8ed99ec3c688bc8a584393e3 Mon Sep 17 00:00:00 2001 From: xu Date: Fri, 28 Jun 2024 23:15:26 +0800 Subject: [PATCH] =?UTF-8?q?[fix]=20=E5=B9=BF=E6=92=AD=E7=AB=AF=E5=8F=A3?= =?UTF-8?q?=E6=94=B9=E4=B8=BA=E5=BC=82=E6=AD=A5=E5=8F=91=E9=80=81=20?= =?UTF-8?q?=E6=B5=8B=E8=AF=95=E5=8F=91=E7=8E=B0RTK=E6=9C=89=E9=98=BB?= =?UTF-8?q?=E5=A1=9E=EF=BC=8C=E5=AF=BC=E8=87=B4=E6=AD=BB=E6=9C=BA?= 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 | 21 ++++++++++++------- 1 file changed, 13 insertions(+), 8 deletions(-) diff --git a/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs b/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs index 6fc8f92..063030c 100644 --- a/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs +++ b/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs @@ -1214,25 +1214,27 @@ namespace Plane.CommunicationManagement byte rtcm_Broadser = 0;//用于广播的 - public void BroadcastbackupGpsDataAsync(byte[] packet) + public async Task BroadcastbackupGpsDataAsync(byte[] packet) { bool sendok=false; try { - RecomPort.Write(packet, 0, packet.Length); + //防止阻塞,异步发送 + await RecomPort.BaseStream.WriteAsync(packet, 0, packet.Length); + //RecomPort.Write(packet, 0, packet.Length); sendok = true; } catch (Exception ex) { - Windows.Messages.Message.Show("转发端口发送失败("+ ex.Message + "),尝试新打开..."); + Windows.Messages.Message.Show("广播端口发送失败..."); } if (!sendok) { try { ReOpenRtcmserial(); - if (Recomisopen) Windows.Messages.Message.Show("转发端口打开成功!"); + if (Recomisopen) Windows.Messages.Message.Show("广播端口打开成功!"); } catch (Exception ex) { @@ -1289,15 +1291,15 @@ namespace Plane.CommunicationManagement await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false); //发送到广播端口作为备用数据源 if (enrecom) - BroadcastbackupGpsDataAsync(packet); + await BroadcastbackupGpsDataAsync(packet); await Task.Delay(80).ConfigureAwait(false); //没有延时得话如果超过110长度,连续发可能收不到 // 重发一次,有序列号(target_component)飞机可以检测出来重复接收的 //需要新固件支持 await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false); //发送到广播端口作为备用数据源 - if (enrecom) - BroadcastbackupGpsDataAsync(packet); + if (enrecom) + await BroadcastbackupGpsDataAsync(packet); await Task.Delay(80).ConfigureAwait(false); //没有延时得话如果超过110长度,连续发可能收不到 } @@ -1451,7 +1453,10 @@ namespace Plane.CommunicationManagement RecomPort.StopBits = StopBits.One; RecomPort.DataBits = 8; RecomPort.Handshake = Handshake.None; - + //改为异步更好一些 + // RecomPort.WriteTimeout = 500; // 设置写入超时为500毫秒 + + try { RecomPort.Open();