修改通讯中,加入通讯模式参数

UseTransModule
This commit is contained in:
xu 2020-03-02 17:15:53 +08:00
parent 3518f4d570
commit 772bafa771

View File

@ -1,5 +1,6 @@
using Plane.Copters;
using Plane.Protocols;
using Plane.Windows.Messages;
using System;
using System.Collections.Generic;
using System.Linq;
@ -17,8 +18,8 @@ namespace Plane.CommunicationManagement
private DateTime waitRtcmTime = DateTime.Now;
private bool starttime = false;
private bool rtcm_run = false;
//是否单独处理传输
private bool IsSingleTrans=false;
//是否使用专用传输模块
private bool UseTransModule = true;
private byte[] SetChannels(ushort? ch1 = null, ushort? ch2 = null, ushort? ch3 = null, ushort? ch4 = null, ushort? ch5 = null, ushort? ch6 = null, ushort? ch7 = null, ushort? ch8 = null)
{
@ -300,9 +301,9 @@ namespace Plane.CommunicationManagement
public async Task SetChannelsAsync(IEnumerable<ICopter> copters = null, ushort? ch1 = null, ushort? ch2 = null, ushort? ch3 = null, ushort? ch4 = null)
{
if (IsSingleTrans)
await SetChannelsAsync_Single(copters, ch1, ch2, ch3, ch4);
else await SetChannelsAsync_CMod(copters, ch1, ch2, ch3, ch4);
if (UseTransModule)
await SetChannelsAsync_CMod(copters, ch1, ch2, ch3, ch4);
else await SetChannelsAsync_Single(copters, ch1, ch2, ch3, ch4);
}
public async Task SetChannelsAsync_Single(IEnumerable<ICopter> copters = null, ushort? ch1 = null, ushort? ch2 = null, ushort? ch3 = null, ushort? ch4 = null)
{
@ -330,9 +331,9 @@ namespace Plane.CommunicationManagement
public async Task<bool> WriteMissionListAsync(ICopter copter, List<IMission> missions)
{
if (IsSingleTrans)
return await WriteMissionListAsync_Single(copter, missions);
else return await WriteMissionListAsync_CMod(short.Parse(copter.Id), missions);
if (UseTransModule)
return await WriteMissionListAsync_CMod(short.Parse(copter.Id), missions);
else return await WriteMissionListAsync_Single(copter, missions);
}
@ -415,9 +416,9 @@ namespace Plane.CommunicationManagement
/// <returns></returns>
public async Task DoMissionStartAsync(IEnumerable<ICopter> copters,int hour_utc, int minute_utc, int second_utc, double Missionlng, double Missionlat)
{
if (IsSingleTrans)
await DoMissionStartAsync_Single(copters,hour_utc, minute_utc, second_utc, Missionlng, Missionlat);
else await DoMissionStartAsync_CMod(hour_utc, minute_utc, second_utc, Missionlng, Missionlat);
if (UseTransModule)
await DoMissionStartAsync_CMod(hour_utc, minute_utc, second_utc, Missionlng, Missionlat);
else await DoMissionStartAsync_Single(copters, hour_utc, minute_utc, second_utc, Missionlng, Missionlat);
}
public async Task DoMissionStartAsync_Single(IEnumerable<ICopter> copters,int hour_utc, int minute_utc, int second_utc, double Missionlng, double Missionlat)
@ -442,22 +443,31 @@ namespace Plane.CommunicationManagement
await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
}
/// <summary>
/// 暂停任务
/// </summary>
public async Task DoMissionPauseAsync()
{
if (UseTransModule)
{
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
Windows.Messages.Message.Show($"未开发完成!!");
}
/// <summary>
/// 恢复任务
/// </summary>
public async Task DoMissionResumeAsync(int hour_utc, int minute_utc, int second_utc)
{
if (UseTransModule)
{
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
Windows.Messages.Message.Show($"未开发完成!!");
}
/// <summary>
@ -466,6 +476,8 @@ namespace Plane.CommunicationManagement
/// <param name="copters">要解锁的飞机</param>
/// <returns></returns>
public async Task UnlockAsync(IEnumerable<ICopter> copters = null)
{
if (UseTransModule)
{
short copterId = 0;
byte[] batchPacket = null;
@ -480,6 +492,9 @@ namespace Plane.CommunicationManagement
byte[] data = packet1.Concat(packet2).Concat(packet3).ToArray();
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
}
else
Windows.Messages.Message.Show($"未开发完成!!");
}
/// <summary>
/// LED闪烁白灯
@ -487,6 +502,8 @@ namespace Plane.CommunicationManagement
/// <param name="copters">要闪烁的飞机</param>
/// <returns></returns>
public void LED_FlickerAsync(IEnumerable<ICopter> copters = null)
{
if (UseTransModule)
{
Task.Run(async () =>
{
@ -498,6 +515,9 @@ namespace Plane.CommunicationManagement
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
});
}
else
Windows.Messages.Message.Show($"未开发完成!!");
}
/// <summary>
@ -508,6 +528,8 @@ namespace Plane.CommunicationManagement
/// <param name="copters"></param>
/// <returns></returns>
public async Task<int> SetParamAsync(string paramname, float value, IEnumerable<ICopter> copters = null)
{
if (UseTransModule)
{
short copterId = 0;
byte[] batchPacket = null;
@ -518,6 +540,12 @@ namespace Plane.CommunicationManagement
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
return packetNum;
}
else
{
Windows.Messages.Message.Show($"未开发完成!!");
return 0;
}
}
/// <summary>
/// 广播设置多个参数
@ -525,6 +553,8 @@ namespace Plane.CommunicationManagement
/// <param name="param"></param>
/// <returns></returns>
public async Task<int> SetMultipleParamAsync(params string[] param)
{
if (UseTransModule)
{
if (param.Length % 2 == 1)
return 0;
@ -542,6 +572,12 @@ namespace Plane.CommunicationManagement
await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
return packetNum;
}
else
{
Windows.Messages.Message.Show($"未开发完成!!");
return 0;
}
}
/// <summary>
@ -551,6 +587,8 @@ namespace Plane.CommunicationManagement
/// <param name="copters"></param>
/// <returns></returns>
public async Task ReadParamAsnyc(string paramname, IEnumerable<ICopter> copters = null)
{
if (UseTransModule)
{
short copterId = 0;
byte[] batchPacket = null;
@ -559,6 +597,12 @@ namespace Plane.CommunicationManagement
byte[] packet = GetParam2Async(paramname);
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
}
else
{
Windows.Messages.Message.Show($"未开发完成!!");
}
}
/// <summary>
/// 起飞测试
@ -567,6 +611,8 @@ namespace Plane.CommunicationManagement
/// <param name="copters"></param>
/// <returns></returns>
public async Task TakeOffAsync(float alt, IEnumerable<ICopter> copters = null)
{
if (UseTransModule)
{
short copterId = 0;
byte[] batchPacket = null;
@ -581,6 +627,9 @@ namespace Plane.CommunicationManagement
byte[] data = packet1.Concat(packet2).Concat(packet3).ToArray();
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
}
else
Windows.Messages.Message.Show($"未开发完成!!");
}
/// <summary>
/// 返航
@ -588,6 +637,8 @@ namespace Plane.CommunicationManagement
/// <param name="copters"></param>
/// <returns></returns>
public async Task ReturnToLaunchAsync(IEnumerable<ICopter> copters = null)
{
if (UseTransModule)
{
short copterId = 0;
byte[] batchPacket = null;
@ -596,6 +647,9 @@ namespace Plane.CommunicationManagement
byte[] packet = SetModeAsync(FlightMode.RTL);
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
}
else
Windows.Messages.Message.Show($"未开发完成!!");
}
@ -606,6 +660,8 @@ namespace Plane.CommunicationManagement
/// <param name="copters"></param>
/// <returns></returns>
public async Task GetVersionsAsync(IEnumerable<ICopter> copters = null)
{
if (UseTransModule)
{
short copterId = 0;
byte[] batchPacket = null;
@ -616,11 +672,16 @@ namespace Plane.CommunicationManagement
byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, req);
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
}
else
Windows.Messages.Message.Show($"未开发完成!!");
}
/// <summary>
/// 降落
/// </summary>
/// <returns></returns>
public async Task LandAsync(IEnumerable<ICopter> copters = null)
{
if (UseTransModule)
{
short copterId = 0;
byte[] batchPacket = null;
@ -629,6 +690,9 @@ namespace Plane.CommunicationManagement
byte[] packet = SetModeAsync(FlightMode.LAND);
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
}
else
Windows.Messages.Message.Show($"未开发完成!!");
}
/// <summary>
/// 加锁
@ -636,6 +700,8 @@ namespace Plane.CommunicationManagement
/// <param name="armit"></param>
/// <returns></returns>
public async Task LockAsync(IEnumerable<ICopter> copters = null)
{
if (UseTransModule)
{
short copterId = 0;
byte[] batchPacket = null;
@ -648,6 +714,9 @@ namespace Plane.CommunicationManagement
byte[] data = packet1.Concat(packet2).ToArray();
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
}
else
Windows.Messages.Message.Show($"未开发完成!!");
}
/// <summary>
/// 测试电机
@ -655,6 +724,8 @@ namespace Plane.CommunicationManagement
/// <param name="motor"></param>
/// <returns></returns>
public async Task MotorTestAsync(IEnumerable<ICopter> copters = null)
{
if (UseTransModule)
{
short copterId = 0;
byte[] batchPacket = null;
@ -669,12 +740,17 @@ namespace Plane.CommunicationManagement
byte[] data = data1.Concat(data2).Concat(data3).Concat(data4).ToArray();
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket);
}
else
Windows.Messages.Message.Show($"未开发完成!!");
}
/// <summary>
/// 切换悬停模式
/// </summary>
/// <returns></returns>
public async Task HoverAsync(IEnumerable<ICopter> copters = null)
{
if (UseTransModule)
{
short copterId = 0;
byte[] batchPacket = null;
@ -687,6 +763,9 @@ namespace Plane.CommunicationManagement
byte[] data = packet1.Concat(packet2).ToArray();
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
}
else
Windows.Messages.Message.Show($"未开发完成!!");
}
/// <summary>
/// 切换手动模式