From c1b3a32407f7dc1e4e0296bce3cc9250077881ec Mon Sep 17 00:00:00 2001 From: xu Date: Fri, 21 Feb 2020 23:59:24 +0800 Subject: [PATCH] =?UTF-8?q?=E5=BC=80=E5=A7=8B=E4=BF=AE=E6=94=B9=E9=80=9A?= =?UTF-8?q?=E8=AE=AF?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../CommModuleGenerateMavLink.cs | 58 ++++++++++++++++++- 1 file changed, 56 insertions(+), 2 deletions(-) diff --git a/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs b/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs index dd15f5c..27aab08 100644 --- a/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs +++ b/PlaneGcsSdk_Shared/CommunicationManagement/CommModuleGenerateMavLink.cs @@ -17,6 +17,8 @@ namespace Plane.CommunicationManagement private DateTime waitRtcmTime = DateTime.Now; private bool starttime = false; private bool rtcm_run = false; + //是否单独处理传输 + private bool IsSingleTrans=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) { @@ -293,7 +295,22 @@ namespace Plane.CommunicationManagement /// /// /// + + + public async Task SetChannelsAsync(IEnumerable 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); + } + public async Task SetChannelsAsync_Single(IEnumerable copters = null, ushort? ch1 = null, ushort? ch2 = null, ushort? ch3 = null, ushort? ch4 = null) + { + await Task.WhenAll(copters.Select(async copter => + await copter.SetChannelsAsync(ch2:ch2))).ConfigureAwait(false); + + } + public async Task SetChannelsAsync_CMod(IEnumerable copters = null, ushort? ch1 = null, ushort? ch2 = null, ushort? ch3 = null, ushort? ch4 = null) { short copterId = 0; byte[] batchPacket = null; @@ -309,7 +326,22 @@ namespace Plane.CommunicationManagement /// 飞机ID /// 任务列表 /// - public async Task WriteMissionListAsync(short id, List missions) + /// + + public async Task WriteMissionListAsync(ICopter copter, List missions) + { + if (IsSingleTrans) + return await WriteMissionListAsync_Single(copter, missions); + else return await WriteMissionListAsync_CMod(short.Parse(copter.Id), missions); + + } + + public async Task WriteMissionListAsync_Single(ICopter copter, List missions) + { + return await copter.WriteMissionListAsync(missions); + } + + public async Task WriteMissionListAsync_CMod(short id, List missions) { missions.Insert(0, PLCopter.PRE_TAKE_OFF_MISSION); List mission_list = new List(); @@ -381,8 +413,30 @@ namespace Plane.CommunicationManagement /// 任务原点经度 /// 任务原点纬度 /// + public async Task DoMissionStartAsync(IEnumerable 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); - public async Task DoMissionStartAsync(int hour_utc, int minute_utc, int second_utc, double Missionlng, double Missionlat) + } + public async Task DoMissionStartAsync_Single(IEnumerable copters,int hour_utc, int minute_utc, int second_utc, double Missionlng, double Missionlat) + { + + foreach (var vcopter in copters) + { + await vcopter.MissionStartAsync(hour_utc, + minute_utc, + second_utc, + Missionlng, + Missionlat + ); + } + + } + + + public async Task DoMissionStartAsync_CMod(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);