1.加入回传功率设置
2.服务器IP可从设置文件读取 3.增加抛物功能
This commit is contained in:
parent
d91b759d5f
commit
8f2cd98bd4
@ -12,17 +12,23 @@ using System.Text;
|
|||||||
using System.Threading.Tasks;
|
using System.Threading.Tasks;
|
||||||
using System.Windows.Media;
|
using System.Windows.Media;
|
||||||
|
|
||||||
|
using System.Runtime.InteropServices;
|
||||||
|
|
||||||
namespace Plane.CommunicationManagement
|
namespace Plane.CommunicationManagement
|
||||||
{
|
{
|
||||||
//通信模块
|
//通信模块
|
||||||
public partial class CommModuleManager: ExceptionThrownEventSource, IDisposable
|
public partial class CommModuleManager: ExceptionThrownEventSource, IDisposable
|
||||||
{
|
{
|
||||||
|
[DllImport("kernel32")] //返回取得字符串缓冲区的长度
|
||||||
|
private static extern int GetPrivateProfileString(string section, string key, string def, StringBuilder retVal, int size, string filePath);
|
||||||
|
|
||||||
private static CommModuleManager _Instance = new CommModuleManager();
|
private static CommModuleManager _Instance = new CommModuleManager();
|
||||||
public static CommModuleManager Instance { get { return _Instance; } }
|
public static CommModuleManager Instance { get { return _Instance; } }
|
||||||
|
|
||||||
public TcpConnection Connection = null;
|
public TcpConnection Connection = null;
|
||||||
public bool CommOK = false;
|
public bool CommOK = false;
|
||||||
private const string MODULE_IP = "192.168.199.51"; // "192.168.199.51"; //在用版本 ----//"192.168.1.65"; //新版本
|
private const string MODULE_IP = "192.168.199.51"; //"192.168.199.51"; // "192.168.199.51"; //在用版本 ----//"192.168.1.65"; //新版本
|
||||||
|
private string ServerIP = MODULE_IP;
|
||||||
// private const string LOCAL_IP = "192.168.199.50"; //"192.168.199.50";
|
// private const string LOCAL_IP = "192.168.199.50"; //"192.168.199.50";
|
||||||
private const int PORT = 9551;
|
private const int PORT = 9551;
|
||||||
private bool _disposed;
|
private bool _disposed;
|
||||||
@ -36,17 +42,32 @@ namespace Plane.CommunicationManagement
|
|||||||
/// </summary>
|
/// </summary>
|
||||||
private Stopwatch _writeMissionStopwatch;
|
private Stopwatch _writeMissionStopwatch;
|
||||||
|
|
||||||
|
private void LoadIPSet()
|
||||||
|
{
|
||||||
|
StringBuilder temp = new StringBuilder(255);
|
||||||
|
|
||||||
|
string path = Environment.CurrentDirectory + @"\Config.ini";
|
||||||
|
|
||||||
|
int i = GetPrivateProfileString("Default", "ServerIP", "", temp, 255, path);
|
||||||
|
ServerIP= temp.ToString();
|
||||||
|
|
||||||
|
if (ServerIP == "") ServerIP = MODULE_IP;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
public async Task ConnectAsync()
|
public async Task ConnectAsync()
|
||||||
{
|
{
|
||||||
Connection = new TcpConnection(MODULE_IP, PORT);
|
LoadIPSet();
|
||||||
|
Connection = new TcpConnection(ServerIP, PORT);
|
||||||
await ConnectOpenAsync();
|
await ConnectOpenAsync();
|
||||||
}
|
}
|
||||||
|
|
||||||
public void Connect()
|
public void Connect()
|
||||||
{
|
{
|
||||||
|
LoadIPSet();
|
||||||
Task.Run(async () =>
|
Task.Run(async () =>
|
||||||
{
|
{
|
||||||
Connection = new TcpConnection(MODULE_IP, PORT);
|
Connection = new TcpConnection(ServerIP, PORT);
|
||||||
await ConnectOpenAsync();
|
await ConnectOpenAsync();
|
||||||
}
|
}
|
||||||
);
|
);
|
||||||
@ -371,6 +392,18 @@ namespace Plane.CommunicationManagement
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
public async Task SetModulePower(short ModuleNo, short ModulePower)
|
||||||
|
{
|
||||||
|
byte[] packet = { 0x01, 0x00, 0x03, 0x00, 0x01, 0x0A };
|
||||||
|
packet[2] = (byte)(ModuleNo & 0xFF);
|
||||||
|
packet[3] = (byte)((ModuleNo & 0xFF00) >> 8);
|
||||||
|
packet[5] = (byte)(ModulePower);
|
||||||
|
await WriteCommPacketAsync(0, MavComm.COMM_TO_MODULE, packet);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
bool temp = false;
|
bool temp = false;
|
||||||
//测试用 灯光间隔1S闪烁
|
//测试用 灯光间隔1S闪烁
|
||||||
|
@ -201,6 +201,18 @@ namespace Plane.CommunicationManagement
|
|||||||
|
|
||||||
return GeneratePacket(MAVLink.MAVLINK_MSG_ID_LED_CONTROL, led);
|
return GeneratePacket(MAVLink.MAVLINK_MSG_ID_LED_CONTROL, led);
|
||||||
}
|
}
|
||||||
|
private byte[] DoThrowoutCommandAsync()
|
||||||
|
{
|
||||||
|
MAVLink.mavlink_msg_id_led_control led = new MAVLink.mavlink_msg_id_led_control();
|
||||||
|
led.target_system = 1;
|
||||||
|
led.target_component = 1;//(byte)MAVLink.MAV_COMPONENT.MAV_COMP_ID_SYSTEM_CONTROL;;
|
||||||
|
led.instance = 0;
|
||||||
|
led.pattern = 0;
|
||||||
|
led.custom_len = 1; //长度是1个字节
|
||||||
|
led.custom_bytes = new byte[24];
|
||||||
|
led.custom_bytes[0] = (byte)10; //10代表抛物
|
||||||
|
return GeneratePacket(MAVLink.MAVLINK_MSG_ID_LED_CONTROL, led);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
private byte[] DoTaskLEDCommandAsync(int ledmode, float ledInterval, int ledtimes, byte cR,byte cG,Byte cB)
|
private byte[] DoTaskLEDCommandAsync(int ledmode, float ledInterval, int ledtimes, byte cR,byte cG,Byte cB)
|
||||||
@ -442,7 +454,7 @@ namespace Plane.CommunicationManagement
|
|||||||
public async Task DoMissionStartAsync(IEnumerable<ICopter> copters,int hour_utc, int minute_utc, int second_utc, double Missionlng, double Missionlat)
|
public async Task DoMissionStartAsync(IEnumerable<ICopter> copters,int hour_utc, int minute_utc, int second_utc, double Missionlng, double Missionlat)
|
||||||
{
|
{
|
||||||
if (UseTransModule)
|
if (UseTransModule)
|
||||||
await DoMissionStartAsync_CMod(hour_utc, minute_utc, second_utc, Missionlng, Missionlat);
|
await DoMissionStartAsync_CMod(copters,hour_utc, minute_utc, second_utc, Missionlng, Missionlat);
|
||||||
else await DoMissionStartAsync_Single(copters, hour_utc, minute_utc, second_utc, Missionlng, Missionlat);
|
else await DoMissionStartAsync_Single(copters, hour_utc, minute_utc, second_utc, Missionlng, Missionlat);
|
||||||
|
|
||||||
}
|
}
|
||||||
@ -462,10 +474,16 @@ namespace Plane.CommunicationManagement
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
public async Task DoMissionStartAsync_CMod(int hour_utc, int minute_utc, int second_utc, double Missionlng, double Missionlat)
|
public async Task DoMissionStartAsync_CMod(IEnumerable<ICopter> copters,int hour_utc, int minute_utc, int second_utc, double Missionlng, double Missionlat)
|
||||||
{
|
{
|
||||||
|
|
||||||
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.MISSION_START, hour_utc, minute_utc, second_utc, (float)Missionlng, (float)Missionlat, 0, -1);
|
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.MISSION_START, hour_utc, minute_utc, second_utc, (float)Missionlng, (float)Missionlat, 0, -1);
|
||||||
await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
|
short copterId = 0;
|
||||||
|
byte[] batchPacket = null;
|
||||||
|
//部分开始任务
|
||||||
|
if (copters!=null)
|
||||||
|
GetCopterIds(copters, out copterId, out batchPacket);
|
||||||
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -529,6 +547,39 @@ namespace Plane.CommunicationManagement
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// 抛物
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="copters">要解锁的飞机</param>
|
||||||
|
/// <returns></returns>
|
||||||
|
public void ThrowoutAsync(IEnumerable<ICopter> copters = null)
|
||||||
|
{
|
||||||
|
if (UseTransModule)
|
||||||
|
{
|
||||||
|
Task.Run(async () =>
|
||||||
|
{
|
||||||
|
short copterId = 0;
|
||||||
|
byte[] batchPacket = null;
|
||||||
|
GetCopterIds(copters, out copterId, out batchPacket);
|
||||||
|
|
||||||
|
byte[] packet = DoThrowoutCommandAsync();
|
||||||
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
/*
|
||||||
|
Task.Run(async () =>
|
||||||
|
{
|
||||||
|
foreach (var vcopter in copters)
|
||||||
|
await vcopter.LEDAsync();
|
||||||
|
});
|
||||||
|
*/
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// LED闪烁白灯
|
/// LED闪烁白灯
|
||||||
/// </summary>
|
/// </summary>
|
||||||
|
@ -104,6 +104,10 @@ namespace Plane.CommunicationManagement
|
|||||||
SaveMissionWriteStat(copterId, buffer[1]);
|
SaveMissionWriteStat(copterId, buffer[1]);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case 0x04:
|
||||||
|
Message.Show($"飞机{copterId}:功率设置成功,新回传功率:{buffer[1]}");
|
||||||
|
break;
|
||||||
|
|
||||||
case 0x0e:
|
case 0x0e:
|
||||||
if (copterId == 0)
|
if (copterId == 0)
|
||||||
Message.Show("----------全部更新完成----------");
|
Message.Show("----------全部更新完成----------");
|
||||||
|
@ -74,6 +74,14 @@ namespace Plane.Protocols
|
|||||||
/// </summary>
|
/// </summary>
|
||||||
public const short COMM_FLIGHT_LOAD_MODE = 0x55;
|
public const short COMM_FLIGHT_LOAD_MODE = 0x55;
|
||||||
|
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// 发送非针对飞控的内部控制指令
|
||||||
|
/// </summary>
|
||||||
|
public const short COMM_TO_MODULE = 0x5F;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// 通信模块
|
/// 通信模块
|
||||||
/// </summary>
|
/// </summary>
|
||||||
|
Loading…
Reference in New Issue
Block a user