初步支持wifi通讯
This commit is contained in:
parent
21d9c121f5
commit
0d1f38f27a
@ -130,5 +130,9 @@ namespace Plane.Copters
|
|||||||
/// </summary>
|
/// </summary>
|
||||||
/// <returns>表示此命令异步发送操作的 <see cref="Task"/> 实例。</returns>
|
/// <returns>表示此命令异步发送操作的 <see cref="Task"/> 实例。</returns>
|
||||||
Task StopPairingAsync();
|
Task StopPairingAsync();
|
||||||
|
|
||||||
|
|
||||||
|
Task DoCommandAsync(int actionid, float p1, float p2, float p3, float p4, float p5, float p6, float p7);
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -19,7 +19,7 @@ namespace Plane.CommunicationManagement
|
|||||||
private bool starttime = false;
|
private bool starttime = false;
|
||||||
private bool rtcm_run = false;
|
private bool rtcm_run = false;
|
||||||
//是否使用专用传输模块
|
//是否使用专用传输模块
|
||||||
private bool UseTransModule = true;
|
public 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)
|
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)
|
||||||
{
|
{
|
||||||
@ -493,7 +493,10 @@ namespace Plane.CommunicationManagement
|
|||||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
Windows.Messages.Message.Show($"未开发完成!!");
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.UnlockAsync();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -516,7 +519,15 @@ namespace Plane.CommunicationManagement
|
|||||||
});
|
});
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
Windows.Messages.Message.Show($"未开发完成!!");
|
{
|
||||||
|
Task.Run(async () =>
|
||||||
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.LEDAsync();
|
||||||
|
});
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -542,7 +553,8 @@ namespace Plane.CommunicationManagement
|
|||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
Windows.Messages.Message.Show($"未开发完成!!");
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.SetParamAsync(paramname, value);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -554,11 +566,11 @@ namespace Plane.CommunicationManagement
|
|||||||
/// <returns></returns>
|
/// <returns></returns>
|
||||||
public async Task<int> SetMultipleParamAsync(params string[] param)
|
public async Task<int> SetMultipleParamAsync(params string[] param)
|
||||||
{
|
{
|
||||||
|
if (param.Length % 2 == 1)
|
||||||
|
return 0;
|
||||||
if (UseTransModule)
|
if (UseTransModule)
|
||||||
{
|
{
|
||||||
if (param.Length % 2 == 1)
|
|
||||||
return 0;
|
|
||||||
|
|
||||||
byte[] packet = null;
|
byte[] packet = null;
|
||||||
int packetNum = 0;
|
int packetNum = 0;
|
||||||
for (int i = 0; i < param.Length; i += 2)
|
for (int i = 0; i < param.Length; i += 2)
|
||||||
@ -574,7 +586,20 @@ namespace Plane.CommunicationManagement
|
|||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
Windows.Messages.Message.Show($"未开发完成!!");
|
byte[] packet = null;
|
||||||
|
int packetNum = 0;
|
||||||
|
for (int i = 0; i < param.Length; i += 2)
|
||||||
|
{
|
||||||
|
string paramname = param[i];
|
||||||
|
float value = float.Parse(param[i + 1]);
|
||||||
|
// foreach (var vcopter in Copters )
|
||||||
|
// await vcopter.SetParamAsync(paramname, value);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -628,7 +653,11 @@ namespace Plane.CommunicationManagement
|
|||||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
Windows.Messages.Message.Show($"未开发完成!!");
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.TakeOffAsync();
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -648,11 +677,16 @@ namespace Plane.CommunicationManagement
|
|||||||
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
Windows.Messages.Message.Show($"未开发完成!!");
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.ReturnToLaunchAsync ();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// 获取飞机版本
|
/// 获取飞机版本
|
||||||
@ -673,7 +707,11 @@ namespace Plane.CommunicationManagement
|
|||||||
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
{
|
||||||
|
|
||||||
Windows.Messages.Message.Show($"未开发完成!!");
|
Windows.Messages.Message.Show($"未开发完成!!");
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// 降落
|
/// 降落
|
||||||
@ -691,7 +729,12 @@ namespace Plane.CommunicationManagement
|
|||||||
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
Windows.Messages.Message.Show($"未开发完成!!");
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.LandAsync();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -715,7 +758,12 @@ namespace Plane.CommunicationManagement
|
|||||||
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
|
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
Windows.Messages.Message.Show($"未开发完成!!");
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.LockAsync();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -741,7 +789,17 @@ namespace Plane.CommunicationManagement
|
|||||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket);
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
Windows.Messages.Message.Show($"未开发完成!!");
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
{
|
||||||
|
await vcopter.MotorTestAsync(1);
|
||||||
|
await vcopter.MotorTestAsync(2);
|
||||||
|
await vcopter.MotorTestAsync(3);
|
||||||
|
await vcopter.MotorTestAsync(4);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -764,7 +822,12 @@ namespace Plane.CommunicationManagement
|
|||||||
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
|
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
Windows.Messages.Message.Show($"未开发完成!!");
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.HoverAsync();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -774,12 +837,21 @@ namespace Plane.CommunicationManagement
|
|||||||
/// <returns></returns>
|
/// <returns></returns>
|
||||||
public async Task FloatAsync(IEnumerable<ICopter> copters = null)
|
public async Task FloatAsync(IEnumerable<ICopter> copters = null)
|
||||||
{
|
{
|
||||||
short copterId = 0;
|
if (UseTransModule)
|
||||||
byte[] batchPacket = null;
|
{
|
||||||
GetCopterIds(copters, out copterId, out batchPacket);
|
short copterId = 0;
|
||||||
|
byte[] batchPacket = null;
|
||||||
|
GetCopterIds(copters, out copterId, out batchPacket);
|
||||||
|
|
||||||
byte[] packet = SetModeAsync(FlightMode.ALT_HOLD);
|
byte[] packet = SetModeAsync(FlightMode.ALT_HOLD);
|
||||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.FloatAsync();
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -789,12 +861,21 @@ namespace Plane.CommunicationManagement
|
|||||||
/// <returns></returns>
|
/// <returns></returns>
|
||||||
public async Task DoStartPreflightCompassAsync(IEnumerable<ICopter> copters = null)
|
public async Task DoStartPreflightCompassAsync(IEnumerable<ICopter> copters = null)
|
||||||
{
|
{
|
||||||
short copterId = 0;
|
if (UseTransModule)
|
||||||
byte[] batchPacket = null;
|
{
|
||||||
GetCopterIds(copters, out copterId, out batchPacket);
|
short copterId = 0;
|
||||||
|
byte[] batchPacket = null;
|
||||||
|
GetCopterIds(copters, out copterId, out batchPacket);
|
||||||
|
|
||||||
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION, 0, 0, 0, 0, 1, 0, 0);
|
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION, 0, 0, 0, 0, 1, 0, 0);
|
||||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.DoCommandAsync((int)MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION, 0, 0, 0, 0, 1, 0, 0);
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -804,16 +885,24 @@ namespace Plane.CommunicationManagement
|
|||||||
/// <returns></returns>
|
/// <returns></returns>
|
||||||
public async Task DoNextPreflightCompassAsync(IEnumerable<ICopter> copters = null)
|
public async Task DoNextPreflightCompassAsync(IEnumerable<ICopter> copters = null)
|
||||||
{
|
{
|
||||||
short copterId = 0;
|
if (UseTransModule)
|
||||||
byte[] batchPacket = null;
|
{
|
||||||
GetCopterIds(copters, out copterId, out batchPacket);
|
short copterId = 0;
|
||||||
|
byte[] batchPacket = null;
|
||||||
|
GetCopterIds(copters, out copterId, out batchPacket);
|
||||||
|
|
||||||
MAVLink.mavlink_command_ack_t req = new MAVLink.mavlink_command_ack_t();
|
MAVLink.mavlink_command_ack_t req = new MAVLink.mavlink_command_ack_t();
|
||||||
req.command = 1;
|
req.command = 1;
|
||||||
req.result = 1;
|
req.result = 1;
|
||||||
|
|
||||||
byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_COMMAND_ACK, req);
|
byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_COMMAND_ACK, req);
|
||||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
Windows.Messages.Message.Show($"未开发完成!!");
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -823,12 +912,21 @@ namespace Plane.CommunicationManagement
|
|||||||
/// <returns></returns>
|
/// <returns></returns>
|
||||||
public async Task DoCalibrationCompassAsync(IEnumerable<ICopter> copters = null)
|
public async Task DoCalibrationCompassAsync(IEnumerable<ICopter> copters = null)
|
||||||
{
|
{
|
||||||
short copterId = 0;
|
if (UseTransModule)
|
||||||
byte[] batchPacket = null;
|
{
|
||||||
GetCopterIds(copters, out copterId, out batchPacket);
|
short copterId = 0;
|
||||||
|
byte[] batchPacket = null;
|
||||||
|
GetCopterIds(copters, out copterId, out batchPacket);
|
||||||
|
|
||||||
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.DO_START_MAG_CAL, 0, 1, 1, 0, 0, 0, 0);
|
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.DO_START_MAG_CAL, 0, 1, 1, 0, 0, 0, 0);
|
||||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.DoCommandAsync((int)MAVLink.MAV_CMD.DO_START_MAG_CAL, 0, 1, 1, 0, 0, 0, 0);
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
|
@ -24,5 +24,14 @@ namespace Plane.Copters
|
|||||||
{
|
{
|
||||||
return Task.FromResult(true);
|
return Task.FromResult(true);
|
||||||
}
|
}
|
||||||
|
public async Task DoCommandAsync(int actionid, float p1, float p2, float p3, float p4, float p5, float p6, float p7)
|
||||||
|
{
|
||||||
|
|
||||||
|
await Task.Delay(50).ConfigureAwait(false);
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -295,6 +295,13 @@ namespace Plane.Copters
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public async Task DoCommandAsync(int actionid, float p1, float p2, float p3, float p4, float p5, float p6, float p7)
|
||||||
|
{
|
||||||
|
|
||||||
|
await Task.Delay(50).ConfigureAwait(false);
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
public Task SetParamAsync(string paramName, float value, int millisecondsTimeout = Timeout.Infinite)
|
public Task SetParamAsync(string paramName, float value, int millisecondsTimeout = Timeout.Infinite)
|
||||||
{
|
{
|
||||||
// TODO: 林俊清, 20150807, 实现仿真的 SetParamAsync。
|
// TODO: 林俊清, 20150807, 实现仿真的 SetParamAsync。
|
||||||
|
@ -356,6 +356,12 @@ namespace Plane.Copters
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
public async Task DoCommandAsync(int actionid, float p1, float p2, float p3, float p4, float p5, float p6, float p7)
|
||||||
|
{
|
||||||
|
await _internalCopter.DoCommandAsync((MAVLink.MAV_CMD)actionid, p1, p2, p3, p4, p5, p6, p7).ConfigureAwait(false);
|
||||||
|
}
|
||||||
|
|
||||||
public async Task LEDAsync()
|
public async Task LEDAsync()
|
||||||
{
|
{
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user