Compare commits

..

No commits in common. "ffb95b2e7dea9b4c9fb2e73354c41d772bb94be9" and "40bf208054455dce8ed99ec3c688bc8a584393e3" have entirely different histories.

View File

@ -487,14 +487,8 @@ namespace Plane.CommunicationManagement
short copterId = 0;
byte[] batchPacket = null;
//部分开始任务
if (copters != null)
GetCopterIds(copters, out copterId, out batchPacket);
else
{
//只有全部飞机才广播
if (Recomisopen)
await BroadcastSendAsync(packet);
}
if (copters!=null)
GetCopterIds(copters, out copterId, out batchPacket);
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
}
@ -508,10 +502,7 @@ 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);
if (Recomisopen)
await BroadcastSendAsync(packet);
}
else
}else
Windows.Messages.Message.Show($"未开发完成!!");
}
@ -524,10 +515,7 @@ 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);
if (Recomisopen)
await BroadcastSendAsync(packet);
}
else
}else
Windows.Messages.Message.Show($"未开发完成!!");
}
@ -552,9 +540,6 @@ namespace Plane.CommunicationManagement
byte[] data = packet1.Concat(packet2).Concat(packet3).ToArray();
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
if (Recomisopen)
await BroadcastSendAsync(data);
}
else
{
@ -625,8 +610,6 @@ 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
@ -685,8 +668,6 @@ 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
@ -884,8 +865,6 @@ 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
{
@ -934,8 +913,6 @@ 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
{
@ -970,8 +947,6 @@ 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
{
@ -1238,21 +1213,11 @@ namespace Plane.CommunicationManagement
byte rtcm_tmpser = 0; //用于通讯模块的
byte rtcm_Broadser = 0;//用于广播的
/// <summary>
/// 发送到广播端口
/// </summary>
/// <param name="packet">发送数据</param>
/// <param name="reopensend">发送失败是否要重新打开再发一次</param>
/// <returns></returns>
public async Task BroadcastSendAsync(byte[] packet,bool reopensend = false)
public async Task BroadcastbackupGpsDataAsync(byte[] packet)
{
bool sendok = false;
//并且没有最后打开的端口说明已经人为关闭了
if (last_reserialport == "")
{
return;
}
bool sendok=false;
try
{
//防止阻塞,异步发送
@ -1264,10 +1229,8 @@ namespace Plane.CommunicationManagement
{
Windows.Messages.Message.Show("广播端口发送失败...");
}
if (!sendok&& reopensend)
if (!sendok)
{
//再次打开串口
try
{
ReOpenRtcmserial();
@ -1276,29 +1239,10 @@ namespace Plane.CommunicationManagement
catch (Exception ex)
{
Windows.Messages.Message.Show("再次打开串口失败" + ex.Message);
return;
}
//再次发送
if (Recomisopen)
{
try
{
await RecomPort.BaseStream.WriteAsync(packet, 0, packet.Length);
//RecomPort.Write(packet, 0, packet.Length);
}
catch (Exception ex)
{
Windows.Messages.Message.Show("再次发送失败...");
}
}
ReOpenRtcmserial();
}
}
}
public async Task BroadcastbackupGpsDataAsync(byte[] packet)
{
await BroadcastSendAsync(packet,true);
}
// get sum crc 计算数据校验和
public byte checkrtrcmsum(byte[] data, ushort length)
@ -1469,7 +1413,7 @@ namespace Plane.CommunicationManagement
await Task.Delay(1);
}
string last_reserialport="";
string last_reserialport;
public void ReOpenRtcmserial()
{
CloseResendRtcmserial();
@ -1477,7 +1421,7 @@ namespace Plane.CommunicationManagement
}
public void CloseResendRtcmserial(bool cleanport=false)
public void CloseResendRtcmserial()
{
if (Recomisopen)
{
@ -1485,19 +1429,15 @@ namespace Plane.CommunicationManagement
RecomPort.Dispose();
}
Recomisopen = false;
//清除端口
if (cleanport)
last_reserialport="";
}
public string BoardPortStatusStr
{
get {
if (Recomisopen)
return "广播端口已打开";
return "已打开"+ last_reserialport;
else
return "广播端口未打开";
return "端口未打开";
}
}
@ -1513,7 +1453,8 @@ namespace Plane.CommunicationManagement
RecomPort.StopBits = StopBits.One;
RecomPort.DataBits = 8;
RecomPort.Handshake = Handshake.None;
RecomPort.WriteTimeout = 500; // 设置写入超时为500毫秒,防止Close时候卡死
//改为异步更好一些
// RecomPort.WriteTimeout = 500; // 设置写入超时为500毫秒
try