diff --git a/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs b/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs
index 26ea810..dd15f5c 100644
--- a/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs
+++ b/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs
@@ -11,26 +11,12 @@ namespace Plane.CommunicationManagement
{
public partial class CommModuleManager
{
- public int packetcount = 0;
-
- ///
- /// 设置通道
- ///
- ///
- ///
- ///
- ///
- ///
- ///
- public async Task SetChannelsAsync(IEnumerable copters = null, ushort? ch1 = null, ushort? ch2 = null, ushort? ch3 = null, ushort? ch4 = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- byte[] packet = SetChannels(ch1, ch2, ch3, ch4);
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
- }
+ public int packetcount = 0;
+ private static object lock_rtcm = new object();//互锁量
+ private List rtcm_packets = new List();
+ private DateTime waitRtcmTime = DateTime.Now;
+ private bool starttime = false;
+ private bool rtcm_run = false;
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)
{
@@ -40,7 +26,7 @@ namespace Plane.CommunicationManagement
rc.chan1_raw = ch1 ?? 1500;
rc.chan2_raw = ch2 ?? 1500;
rc.chan3_raw = ch3 ?? 1500;
- rc.chan4_raw = ch4 ?? 1500;
+ rc.chan4_raw = ch4 ?? 1500;
rc.chan5_raw = 1500;
rc.chan6_raw = 1500;
rc.chan7_raw = 1500;
@@ -48,400 +34,6 @@ namespace Plane.CommunicationManagement
return GeneratePacket(MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, rc);
}
- public async Task WriteMissionListAsync(short id, List missions)
- {
- missions.Insert(0, PLCopter.PRE_TAKE_OFF_MISSION);
- List mission_list = new List();
- foreach (IMission mission in missions)
- {
- var frame = mission.Command == FlightCommand.Waypoint && mission.Sequence == 0 ? MAVLink.MAV_FRAME.GLOBAL : MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT;
-
- var req = new MAVLink.mavlink_mission_item_t();
-
- req.target_system = 1;
- req.target_component = 1;
-
- req.command = (byte)mission.Command;
-
- req.current = 0;
- req.autocontinue = 1;
-
- req.frame = (byte)frame;
- if (mission.Command == FlightCommand.LEDControl)
- {
- req.x = mission.R;
- req.y = mission.G;
- req.z = mission.B;
- }
- else
- {
- req.x = (float)mission.Latitude;
- req.y = (float)mission.Longitude;
- req.z = mission.Altitude;
- }
-
- req.param1 = mission.Param1;
- req.param2 = mission.Param2;
- req.param3 = mission.Param3;
- req.param4 = mission.Param4;
-
- req.seq = mission.Sequence;
- mission_list.Add(req);
- }
-
- bool result = await MissionPacket(id, (byte)MavComm.COMM_DOWNLOAD_MODE, mission_list.ToArray());
-
- lock(MissinLocker)
- {
- if (missionWriteState.ContainsKey(id))
- {
- missionWriteState[id].StateReturn = MissionErrorId;
- missionWriteState[id].ErrorCode = ErrorCode;
- missionWriteState[id].SendAchieved = result;
- missionWriteState[id].WriteSucceed = false;
- }
- else
- {
- CommWriteMissinState state = new CommWriteMissinState(result);
- state.StateReturn = MissionErrorId;
- state.ErrorCode = ErrorCode;
- missionWriteState.Add(id, state);
- }
- return result;
- }
- }
-
- ///
- /// 开始任务
- ///
- public async Task DoMissionStartAsync(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);
- await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
- }
-
- ///
- /// 暂停任务
- ///
- public async Task DoMissionPauseAsync()
- {
- 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);
- }
-
- ///
- /// 恢复任务
- ///
- public async Task DoMissionResumeAsync(int hour_utc, int minute_utc, int second_utc)
- {
- 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);
- }
-
- ///
- /// 解锁
- ///
- ///
- ///
- public async Task UnlockAsync(IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters,out copterId, out batchPacket);
-
- byte[] packet1 = SetChannels(1500, 1500, 1100, 1500);
-
- byte[] packet2 = SetModeAsync(FlightMode.ALT_HOLD);
-
- byte[] packet3 = DoARMAsync(true);
-
- byte[] data = packet1.Concat(packet2).Concat(packet3).ToArray();
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
- }
-
- ///
- /// LED闪烁白灯
- ///
- ///
- ///
- public void LED_FlickerAsync(IEnumerable copters = null)
- {
- Task.Run(async () =>
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- byte[] packet = DoLEDCommandAsync();
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
- });
- }
-
-
- ///
- /// 设置参数
- ///
- ///
- ///
- ///
- ///
- public async Task SetParamAsync(string paramname, float value, IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- byte[] packet = SetParam2Async(paramname, value);
- int packetNum = packet[2];
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
- return packetNum;
- }
-
- public async Task SetMultipleParamAsync(params string[] param)
- {
- if (param.Length % 2 == 1)
- return 0;
-
- 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]);
- byte[] data = SetParam2Async(paramname, value);
- packetNum = data[2];
- packet = packet == null ? data : packet.Concat(data).ToArray();
- }
- await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
- return packetNum;
- }
-
-
- ///
- /// 读取参数
- ///
- ///
- ///
- ///
- public async Task ReadParamAsnyc(string paramname, IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- byte[] packet = GetParam2Async(paramname);
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
- }
-
- ///
- /// 起飞测试
- ///
- ///
- ///
- ///
- public async Task TakeOffAsync(float alt, IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- byte[] packet1 = SetModeAsync(FlightMode.GUIDED);
-
- byte[] packet2 = SetChannels(1500, 1500, 1500, 1500);
-
- byte[] packet3 = DoCommandAsync(MAVLink.MAV_CMD.TAKEOFF, 0, 0, 0, 0, 0, 0, alt);
-
- byte[] data = packet1.Concat(packet2).Concat(packet3).ToArray();
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
- }
-
- ///
- /// 返航
- ///
- ///
- ///
- public async Task ReturnToLaunchAsync(IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- byte[] packet = SetModeAsync(FlightMode.RTL);
- await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
- }
-
-
-
-
- ///
- /// 获取版本
- ///
- ///
- ///
- public async Task GetVersionsAsync(IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- MAVLink.mavlink_sversion_request req = new MAVLink.mavlink_sversion_request();
- req.version = 0;
- byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, req);
- await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
- }
- ///
- /// 降落
- ///
- ///
- public async Task LandAsync(IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- byte[] packet = SetModeAsync(FlightMode.LAND);
- await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
- }
-
- ///
- /// 加锁
- ///
- ///
- ///
- public async Task LockAsync(IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- byte[] packet1 = SetChannels(1500, 1500, 1100, 1500);
-
- byte[] packet2 = DoARMAsync(false);
-
- byte[] data = packet1.Concat(packet2).ToArray();
- await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
- }
-
- ///
- /// 测试电机
- ///
- ///
- ///
- public async Task MotorTestAsync(IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- //1-4代表1-4电机
- byte[] data1 = DoMotorTestAsync(1, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
- byte[] data2 = DoMotorTestAsync(2, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
- byte[] data3 = DoMotorTestAsync(3, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
- byte[] data4 = DoMotorTestAsync(4, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
-
- byte[] data = data1.Concat(data2).Concat(data3).Concat(data4).ToArray();
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket);
- }
-
- ///
- /// 悬停
- ///
- ///
- public async Task HoverAsync(IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- byte[] packet1 = SetChannels(1500, 1500, 1500, 1500);
-
- byte[] packet2 = SetModeAsync(FlightMode.LOITER);
-
- byte[] data = packet1.Concat(packet2).ToArray();
- await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
- }
-
- ///
- /// 手动
- ///
- ///
- ///
- public async Task FloatAsync(IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- byte[] packet = SetModeAsync(FlightMode.ALT_HOLD);
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
- }
-
- ///
- /// 校准加速计
- ///
- ///
- ///
- public async Task DoStartPreflightCompassAsync(IEnumerable copters = null)
- {
- 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);
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
- }
-
- ///
- /// 校准加速计下一步
- ///
- ///
- ///
- public async Task DoNextPreflightCompassAsync(IEnumerable copters = null)
- {
- short copterId = 0;
- byte[] batchPacket = null;
- GetCopterIds(copters, out copterId, out batchPacket);
-
- MAVLink.mavlink_command_ack_t req = new MAVLink.mavlink_command_ack_t();
- req.command = 1;
- req.result = 1;
-
- byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_COMMAND_ACK, req);
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
- }
-
- ///
- /// 校准指南针
- ///
- ///
- ///
- public async Task DoCalibrationCompassAsync(IEnumerable copters = null)
- {
- 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);
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
- }
-
- ///
- /// 放弃校准指南针
- ///
- ///
- ///
- public async Task DoCancelCalibrationCompassAsync(short copterId)
- {
- byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.DO_CANCEL_MAG_CAL, 0, 0, 1, 0, 0, 0, 0);
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
- }
-
- public async Task DoAcceptCalibrationCompassAsync(short copterId)
- {
- byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.DO_ACCEPT_MAG_CAL, 0, 0, 1, 0, 0, 0, 0);
- await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
- }
-
private byte[] SetModeAsync(FlightMode mode)
{
return SetModeAsync(mode.ToAC2Mode());
@@ -475,7 +67,7 @@ namespace Plane.CommunicationManagement
req.param5 = p5;
req.param6 = p6;
req.param7 = p7;
-
+
return GeneratePacket(MAVLink.MAVLINK_MSG_ID_COMMAND_LONG, req); ;
}
@@ -558,6 +150,577 @@ namespace Plane.CommunicationManagement
return true;
}
+ private byte[] SetParam2Async(string paramname, float value)
+ {
+ // param type is set here, however it is always sent over the air as a float 100int = 100f.
+ var req = new MAVLink.mavlink_param_set_t { target_system = 1, target_component = 1, param_type = 4 };
+
+ byte[] temp = Encoding.GetEncoding("ASCII").GetBytes(paramname);
+
+ Array.Resize(ref temp, 16);
+ req.param_id = temp;
+ req.param_value = (value);
+
+ return GeneratePacket((byte)MAVLink.MAVLINK_MSG_ID_PARAM_SET, req);
+ }
+
+ private byte[] GetParam2Async(string paramname)
+ {
+ var paramId = Encoding.ASCII.GetBytes(paramname);
+ Array.Resize(ref paramId, 16);
+
+ var req = new MAVLink.mavlink_param_request_read_t
+ {
+ param_index = -1,
+ target_system = 1,
+ target_component = 1,
+ param_id = paramId
+ };
+
+ return GeneratePacket(MAVLink.MAVLINK_MSG_ID_PARAM_REQUEST_READ, req);
+ }
+
+ private byte[] DoLEDCommandAsync()
+ {
+ 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 = 4;
+ led.custom_bytes = new byte[24];
+ led.custom_bytes[0] = 255;
+ led.custom_bytes[1] = 255;
+ led.custom_bytes[2] = 255;
+ led.custom_bytes[3] = 3;
+
+ return GeneratePacket(MAVLink.MAVLINK_MSG_ID_LED_CONTROL, led);
+ }
+
+ private byte[] BatchCopterIdData(IEnumerable copters)
+ {
+ byte[] BatchByte = null;
+ List copterList = copters.OrderBy(c => int.Parse(c.Id)).ToList();
+ for (int i = 0; i < copterList.Count; i++)
+ {
+ byte[] tempByte;
+ int id = int.Parse(copterList[i].Id);
+ int count = 1;
+ while (i + 1 < copterList.Count && int.Parse(copterList[i + 1].Id) == id + count)
+ {
+ count++;
+ i++;
+ }
+
+ if (count == 1)
+ {
+ short curId = (short)(0 << 12 ^ id);
+ tempByte = BitConverter.GetBytes(curId);
+ }
+ else
+ {
+ short beginId = (short)(2 << 12 ^ id);
+ tempByte = BitConverter.GetBytes(beginId);
+
+ short numCount = (short)(4 << 12 ^ count);
+ tempByte = tempByte.Concat(BitConverter.GetBytes(numCount)).ToArray();
+ }
+
+ if (BatchByte == null)
+ BatchByte = tempByte;
+ else
+ BatchByte = BatchByte.Concat(tempByte).ToArray();
+ }
+ return BatchByte;
+ }
+
+ private void GetCopterIds(IEnumerable copters, out short copterId, out byte[] batchPacket)
+ {
+ copterId = 0;
+ batchPacket = null;
+
+ if (copters != null)
+ {
+ if (copters.Count() == 1)
+ copterId = short.Parse(copters.FirstOrDefault().Id);
+ else
+ {
+ batchPacket = BatchCopterIdData(copters);
+ }
+ }
+ }
+
+ 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 async Task SetChannelsAsync(IEnumerable copters = null, ushort? ch1 = null, ushort? ch2 = null, ushort? ch3 = null, ushort? ch4 = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ byte[] packet = SetChannels(ch1, ch2, ch3, ch4);
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
+ }
+
+ ///
+ /// 开始写任务
+ ///
+ /// 飞机ID
+ /// 任务列表
+ ///
+ public async Task WriteMissionListAsync(short id, List missions)
+ {
+ missions.Insert(0, PLCopter.PRE_TAKE_OFF_MISSION);
+ List mission_list = new List();
+ foreach (IMission mission in missions)
+ {
+ var frame = mission.Command == FlightCommand.Waypoint && mission.Sequence == 0 ? MAVLink.MAV_FRAME.GLOBAL : MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT;
+
+ var req = new MAVLink.mavlink_mission_item_t();
+
+ req.target_system = 1;
+ req.target_component = 1;
+
+ req.command = (byte)mission.Command;
+
+ req.current = 0;
+ req.autocontinue = 1;
+
+ req.frame = (byte)frame;
+ if (mission.Command == FlightCommand.LEDControl)
+ {
+ req.x = mission.R;
+ req.y = mission.G;
+ req.z = mission.B;
+ }
+ else
+ {
+ req.x = (float)mission.Latitude;
+ req.y = (float)mission.Longitude;
+ req.z = mission.Altitude;
+ }
+
+ req.param1 = mission.Param1;
+ req.param2 = mission.Param2;
+ req.param3 = mission.Param3;
+ req.param4 = mission.Param4;
+
+ req.seq = mission.Sequence;
+ mission_list.Add(req);
+ }
+
+ bool result = await MissionPacket(id, (byte)MavComm.COMM_DOWNLOAD_MODE, mission_list.ToArray());
+
+ lock(MissinLocker)
+ {
+ if (missionWriteState.ContainsKey(id))
+ {
+ missionWriteState[id].StateReturn = MissionErrorId;
+ missionWriteState[id].ErrorCode = ErrorCode;
+ missionWriteState[id].SendAchieved = result;
+ missionWriteState[id].WriteSucceed = false;
+ }
+ else
+ {
+ CommWriteMissinState state = new CommWriteMissinState(result);
+ state.StateReturn = MissionErrorId;
+ state.ErrorCode = ErrorCode;
+ missionWriteState.Add(id, state);
+ }
+ return result;
+ }
+ }
+
+ ///
+ /// 开始执行任务
+ ///
+ /// 开始执行的小时
+ /// 开始执行的分钟
+ /// 开始执行的秒
+ /// 任务原点经度
+ /// 任务原点纬度
+ ///
+
+ public async Task DoMissionStartAsync(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);
+ await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
+ }
+
+ ///
+ /// 暂停任务
+ ///
+ public async Task DoMissionPauseAsync()
+ {
+ 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);
+ }
+
+ ///
+ /// 恢复任务
+ ///
+ public async Task DoMissionResumeAsync(int hour_utc, int minute_utc, int second_utc)
+ {
+ 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);
+ }
+
+ ///
+ /// 解锁
+ ///
+ /// 要解锁的飞机
+ ///
+ public async Task UnlockAsync(IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters,out copterId, out batchPacket);
+
+ byte[] packet1 = SetChannels(1500, 1500, 1100, 1500);
+
+ byte[] packet2 = SetModeAsync(FlightMode.ALT_HOLD);
+
+ byte[] packet3 = DoARMAsync(true);
+
+ byte[] data = packet1.Concat(packet2).Concat(packet3).ToArray();
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
+ }
+
+ ///
+ /// LED闪烁白灯
+ ///
+ /// 要闪烁的飞机
+ ///
+ public void LED_FlickerAsync(IEnumerable copters = null)
+ {
+ Task.Run(async () =>
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ byte[] packet = DoLEDCommandAsync();
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
+ });
+ }
+
+
+ ///
+ /// 设置参数
+ ///
+ ///
+ ///
+ ///
+ ///
+ public async Task SetParamAsync(string paramname, float value, IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ byte[] packet = SetParam2Async(paramname, value);
+ int packetNum = packet[2];
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
+ return packetNum;
+ }
+
+ ///
+ /// 广播设置多个参数
+ ///
+ ///
+ ///
+ public async Task SetMultipleParamAsync(params string[] param)
+ {
+ if (param.Length % 2 == 1)
+ return 0;
+
+ 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]);
+ byte[] data = SetParam2Async(paramname, value);
+ packetNum = data[2];
+ packet = packet == null ? data : packet.Concat(data).ToArray();
+ }
+ await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
+ return packetNum;
+ }
+
+
+ ///
+ /// 读取参数
+ ///
+ ///
+ ///
+ ///
+ public async Task ReadParamAsnyc(string paramname, IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ byte[] packet = GetParam2Async(paramname);
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
+ }
+
+ ///
+ /// 起飞测试
+ ///
+ /// 起飞高度
+ ///
+ ///
+ public async Task TakeOffAsync(float alt, IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ byte[] packet1 = SetModeAsync(FlightMode.GUIDED);
+
+ byte[] packet2 = SetChannels(1500, 1500, 1500, 1500);
+
+ byte[] packet3 = DoCommandAsync(MAVLink.MAV_CMD.TAKEOFF, 0, 0, 0, 0, 0, 0, alt);
+
+ byte[] data = packet1.Concat(packet2).Concat(packet3).ToArray();
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
+ }
+
+ ///
+ /// 返航
+ ///
+ ///
+ ///
+ public async Task ReturnToLaunchAsync(IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ byte[] packet = SetModeAsync(FlightMode.RTL);
+ await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
+ }
+
+
+
+
+ ///
+ /// 获取飞机版本
+ ///
+ ///
+ ///
+ public async Task GetVersionsAsync(IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ MAVLink.mavlink_sversion_request req = new MAVLink.mavlink_sversion_request();
+ req.version = 0;
+ byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, req);
+ await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
+ }
+ ///
+ /// 降落
+ ///
+ ///
+ public async Task LandAsync(IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ byte[] packet = SetModeAsync(FlightMode.LAND);
+ await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
+ }
+
+ ///
+ /// 加锁
+ ///
+ ///
+ ///
+ public async Task LockAsync(IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ byte[] packet1 = SetChannels(1500, 1500, 1100, 1500);
+
+ byte[] packet2 = DoARMAsync(false);
+
+ byte[] data = packet1.Concat(packet2).ToArray();
+ await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
+ }
+
+ ///
+ /// 测试电机
+ ///
+ ///
+ ///
+ public async Task MotorTestAsync(IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ //1-4代表1-4电机
+ byte[] data1 = DoMotorTestAsync(1, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
+ byte[] data2 = DoMotorTestAsync(2, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
+ byte[] data3 = DoMotorTestAsync(3, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
+ byte[] data4 = DoMotorTestAsync(4, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
+
+ byte[] data = data1.Concat(data2).Concat(data3).Concat(data4).ToArray();
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket);
+ }
+
+ ///
+ /// 切换悬停模式
+ ///
+ ///
+ public async Task HoverAsync(IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ byte[] packet1 = SetChannels(1500, 1500, 1500, 1500);
+
+ byte[] packet2 = SetModeAsync(FlightMode.LOITER);
+
+ byte[] data = packet1.Concat(packet2).ToArray();
+ await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
+ }
+
+ ///
+ /// 切换手动模式
+ ///
+ ///
+ ///
+ public async Task FloatAsync(IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ byte[] packet = SetModeAsync(FlightMode.ALT_HOLD);
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
+ }
+
+ ///
+ /// 校准加速计
+ ///
+ ///
+ ///
+ public async Task DoStartPreflightCompassAsync(IEnumerable copters = null)
+ {
+ 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);
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
+ }
+
+ ///
+ /// 校准加速计下一步
+ ///
+ ///
+ ///
+ public async Task DoNextPreflightCompassAsync(IEnumerable copters = null)
+ {
+ short copterId = 0;
+ byte[] batchPacket = null;
+ GetCopterIds(copters, out copterId, out batchPacket);
+
+ MAVLink.mavlink_command_ack_t req = new MAVLink.mavlink_command_ack_t();
+ req.command = 1;
+ req.result = 1;
+
+ byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_COMMAND_ACK, req);
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
+ }
+
+ ///
+ /// 校准指南针
+ ///
+ ///
+ ///
+ public async Task DoCalibrationCompassAsync(IEnumerable copters = null)
+ {
+ 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);
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
+ }
+
+ ///
+ /// 放弃校准指南针
+ ///
+ ///
+ ///
+ public async Task DoCancelCalibrationCompassAsync(short copterId)
+ {
+ byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.DO_CANCEL_MAG_CAL, 0, 0, 1, 0, 0, 0, 0);
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
+ }
+ ///
+ /// 确认校准磁罗盘
+ ///
+ ///
+ ///
+ public async Task DoAcceptCalibrationCompassAsync(short copterId)
+ {
+ byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.DO_ACCEPT_MAG_CAL, 0, 0, 1, 0, 0, 0, 0);
+ await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
+ }
+
+
+
///
///广播Rtk
@@ -586,7 +749,12 @@ namespace Plane.CommunicationManagement
int inject_seq_no = 0;
-
+ ///
+ /// 插入RTK数据
+ ///
+ ///
+ ///
+ ///
public async Task InjectGpsRTCMDataAsync(byte[] data, int length)
{
MAVLink.mavlink_gps_rtcm_data_t gps = new MAVLink.mavlink_gps_rtcm_data_t();
@@ -647,11 +815,7 @@ namespace Plane.CommunicationManagement
}
- private static object lock_rtcm = new object();//互锁量
- private List rtcm_packets = new List();
- private DateTime waitRtcmTime = DateTime.Now;
- private bool starttime = false;
- private bool rtcm_run = false;
+
///
/// 开始循环检测Rtcm数量
///
@@ -673,40 +837,16 @@ namespace Plane.CommunicationManagement
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);
- }
- }
+
-
+ ///
+ /// 产生RTK包
+ ///
+ ///
+ ///
+ ///
+ ///
+ ///
public byte[] GenerateRTKPacketAsync(byte messageType, TMavlinkPacket indata, int rtklength)
{
byte[] data;
@@ -749,106 +889,7 @@ namespace Plane.CommunicationManagement
return packet;
}
-
- private byte[] SetParam2Async(string paramname, float value)
- {
- // param type is set here, however it is always sent over the air as a float 100int = 100f.
- var req = new MAVLink.mavlink_param_set_t { target_system = 1, target_component = 1, param_type = 4 };
-
- byte[] temp = Encoding.GetEncoding("ASCII").GetBytes(paramname);
-
- Array.Resize(ref temp, 16);
- req.param_id = temp;
- req.param_value = (value);
-
- return GeneratePacket((byte)MAVLink.MAVLINK_MSG_ID_PARAM_SET, req);
- }
-
- private byte[] GetParam2Async(string paramname)
- {
- var paramId = Encoding.ASCII.GetBytes(paramname);
- Array.Resize(ref paramId, 16);
-
- var req = new MAVLink.mavlink_param_request_read_t
- {
- param_index = -1,
- target_system = 1,
- target_component = 1,
- param_id = paramId
- };
-
- return GeneratePacket(MAVLink.MAVLINK_MSG_ID_PARAM_REQUEST_READ, req);
- }
-
- private byte[] DoLEDCommandAsync()
- {
- 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 = 4;
- led.custom_bytes = new byte[24];
- led.custom_bytes[0] = 255;
- led.custom_bytes[1] = 255;
- led.custom_bytes[2] = 255;
- led.custom_bytes[3] = 3;
-
- return GeneratePacket(MAVLink.MAVLINK_MSG_ID_LED_CONTROL, led);
- }
-
- private byte[] BatchCopterIdData(IEnumerable copters)
- {
- byte[] BatchByte = null;
- List copterList = copters.OrderBy(c=>int.Parse(c.Id)).ToList();
- for (int i = 0; i < copterList.Count; i++)
- {
- byte[] tempByte;
- int id = int.Parse(copterList[i].Id);
- int count = 1;
- while(i+1 < copterList.Count && int.Parse(copterList[i + 1].Id) == id + count)
- {
- count++;
- i++;
- }
-
- if (count == 1)
- {
- short curId = (short)(0 << 12 ^ id);
- tempByte = BitConverter.GetBytes(curId);
- }
- else
- {
- short beginId = (short)(2 << 12 ^ id);
- tempByte = BitConverter.GetBytes(beginId);
-
- short numCount = (short)(4 << 12 ^ count);
- tempByte = tempByte.Concat(BitConverter.GetBytes(numCount)).ToArray();
- }
-
- if (BatchByte == null)
- BatchByte = tempByte;
- else
- BatchByte = BatchByte.Concat(tempByte).ToArray();
- }
- return BatchByte;
- }
-
- private void GetCopterIds(IEnumerable copters, out short copterId, out byte[] batchPacket)
- {
- copterId = 0;
- batchPacket = null;
-
- if (copters != null)
- {
- if (copters.Count() == 1)
- copterId = short.Parse(copters.FirstOrDefault().Id);
- else
- {
- batchPacket = BatchCopterIdData(copters);
- }
- }
- }
+
}
}