多条RTK同时发送
灯光长度测试
This commit is contained in:
parent
04b40f760e
commit
eeed927529
@ -27,6 +27,7 @@ namespace Plane.CommunicationManagement
|
|||||||
public int CommModuleCurMode = 0;
|
public int CommModuleCurMode = 0;
|
||||||
private long packetCountNum = 0;
|
private long packetCountNum = 0;
|
||||||
|
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// 用于判断写入任务操作超时的秒表。
|
/// 用于判断写入任务操作超时的秒表。
|
||||||
/// </summary>
|
/// </summary>
|
||||||
@ -322,7 +323,7 @@ namespace Plane.CommunicationManagement
|
|||||||
//await WriteCommPacketAsync(id, MavComm.COMM_DOWNLOAD_COMM, packet);
|
//await WriteCommPacketAsync(id, MavComm.COMM_DOWNLOAD_COMM, packet);
|
||||||
byte[] senddata = packet;
|
byte[] senddata = packet;
|
||||||
|
|
||||||
for (int times = 0; times < 4; times++)
|
for (int times = 0; times < 13; times++)
|
||||||
{
|
{
|
||||||
senddata = senddata.Concat(packet).ToArray();
|
senddata = senddata.Concat(packet).ToArray();
|
||||||
}
|
}
|
||||||
@ -333,15 +334,9 @@ namespace Plane.CommunicationManagement
|
|||||||
temp = !temp;
|
temp = !temp;
|
||||||
while (temp)
|
while (temp)
|
||||||
{
|
{
|
||||||
|
Message.Show("长度 = " + senddata.Length);
|
||||||
await WriteCommPacketAsync(id, MavComm.COMM_DOWNLOAD_COMM, senddata);
|
await WriteCommPacketAsync(id, MavComm.COMM_DOWNLOAD_COMM, senddata);
|
||||||
await Task.Delay(50).ConfigureAwait(false);
|
await Task.Delay(1000).ConfigureAwait(false);
|
||||||
await WriteCommPacketAsync(id, MavComm.COMM_DOWNLOAD_COMM, senddata);
|
|
||||||
await Task.Delay(50).ConfigureAwait(false);
|
|
||||||
await WriteCommPacketAsync(id, MavComm.COMM_DOWNLOAD_COMM, senddata);
|
|
||||||
await Task.Delay(50).ConfigureAwait(false);
|
|
||||||
await WriteCommPacketAsync(id, MavComm.COMM_DOWNLOAD_COMM, senddata);
|
|
||||||
await Task.Delay(50).ConfigureAwait(false);
|
|
||||||
await Task.Delay(800).ConfigureAwait(false);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -11,8 +11,7 @@ namespace Plane.CommunicationManagement
|
|||||||
{
|
{
|
||||||
public partial class CommModuleManager
|
public partial class CommModuleManager
|
||||||
{
|
{
|
||||||
public int packetcount = 0;
|
public int packetcount = 0;
|
||||||
|
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// 设置通道
|
/// 设置通道
|
||||||
@ -586,6 +585,8 @@ namespace Plane.CommunicationManagement
|
|||||||
}
|
}
|
||||||
|
|
||||||
int inject_seq_no = 0;
|
int inject_seq_no = 0;
|
||||||
|
|
||||||
|
|
||||||
public async Task InjectGpsRTCMDataAsync(byte[] data, int length)
|
public async Task InjectGpsRTCMDataAsync(byte[] data, int length)
|
||||||
{
|
{
|
||||||
MAVLink.mavlink_gps_rtcm_data_t gps = new MAVLink.mavlink_gps_rtcm_data_t();
|
MAVLink.mavlink_gps_rtcm_data_t gps = new MAVLink.mavlink_gps_rtcm_data_t();
|
||||||
@ -629,12 +630,82 @@ namespace Plane.CommunicationManagement
|
|||||||
gps.len = (byte)copy;
|
gps.len = (byte)copy;
|
||||||
|
|
||||||
byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_GPS_RTCM_DATA, gps);
|
byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_GPS_RTCM_DATA, gps);
|
||||||
Console.WriteLine($"{DateTime.Now.ToLongTimeString()}---发送给张伟的数据长度 = {packet.Length}");
|
Windows.Messages.Message.Show($"{DateTime.Now.ToString("HH:mm:ss:fff")} 通信数据长度 = {packet.Length}");
|
||||||
await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
|
await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
|
||||||
} }
|
|
||||||
|
// lock (lock_rtcm)
|
||||||
|
// {
|
||||||
|
// rtcm_packets.Add(packet);
|
||||||
|
// if (rtcm_packets.Count == 1)
|
||||||
|
// {
|
||||||
|
// waitRtcmTime = DateTime.Now;
|
||||||
|
// starttime = true;
|
||||||
|
// }
|
||||||
|
// }
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
private static object lock_rtcm = new object();//互锁量
|
||||||
|
private List<byte[]> rtcm_packets = new List<byte[]>();
|
||||||
|
private DateTime waitRtcmTime = DateTime.Now;
|
||||||
|
private bool starttime = false;
|
||||||
|
private bool rtcm_run = false;
|
||||||
|
/// <summary>
|
||||||
|
/// 开始循环检测Rtcm数量
|
||||||
|
/// </summary>
|
||||||
|
/// <returns></returns>
|
||||||
|
public async Task StartRtcmLoop()
|
||||||
|
{
|
||||||
|
rtcm_run = true;
|
||||||
|
waitRtcmTime = DateTime.Now;
|
||||||
|
await Task.Factory.StartNew(RtcmLoop);
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// 结束循环检测Rtcm数量
|
||||||
|
/// </summary>
|
||||||
|
/// <returns></returns>
|
||||||
|
public async Task CloseRtcmLoop()
|
||||||
|
{
|
||||||
|
rtcm_run = false;
|
||||||
|
await Task.Delay(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
private async Task RtcmLoop()
|
||||||
|
{
|
||||||
|
while(rtcm_run)
|
||||||
|
{
|
||||||
|
byte[] sendDate = new byte[0];
|
||||||
|
lock (lock_rtcm)
|
||||||
|
{
|
||||||
|
if (rtcm_packets.Count >= 3 ||
|
||||||
|
(starttime && waitRtcmTime.AddMilliseconds(200) <= DateTime.Now))
|
||||||
|
{
|
||||||
|
if (rtcm_packets.Count > 0)
|
||||||
|
{
|
||||||
|
Windows.Messages.Message.Show($"rtcm_packets.Count = {rtcm_packets.Count}");
|
||||||
|
for (int i = 0; i < rtcm_packets.Count; i++)
|
||||||
|
{
|
||||||
|
sendDate = sendDate.Concat(rtcm_packets[i]).ToArray();
|
||||||
|
}
|
||||||
|
rtcm_packets.Clear();
|
||||||
|
starttime = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sendDate!=null && sendDate.Length>0)
|
||||||
|
{
|
||||||
|
Windows.Messages.Message.Show($"{DateTime.Now.ToString("HH:mm:ss:fff")} 通信数据长度 = {sendDate.Length}");
|
||||||
|
await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, sendDate).ConfigureAwait(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
await Task.Delay(10);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
public byte[] GenerateRTKPacketAsync<TMavlinkPacket>(byte messageType, TMavlinkPacket indata, int rtklength)
|
public byte[] GenerateRTKPacketAsync<TMavlinkPacket>(byte messageType, TMavlinkPacket indata, int rtklength)
|
||||||
{
|
{
|
||||||
@ -779,4 +850,5 @@ namespace Plane.CommunicationManagement
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user