From f31f08e5309cf8ec37087003a7d315bb0fee1d48 Mon Sep 17 00:00:00 2001 From: panxu Date: Mon, 30 Apr 2018 19:41:13 +0800 Subject: [PATCH] =?UTF-8?q?=E5=B0=86Src0918=E7=9A=84=E9=83=A8=E5=88=86?= =?UTF-8?q?=E5=8A=9F=E8=83=BD=E7=A7=BB=E6=A4=8D=E8=BF=9B=E6=9D=A5=EF=BC=8C?= =?UTF-8?q?=E8=BF=98=E6=9C=89=E5=80=92=E8=AE=A1=E6=97=B6=EF=BC=8C=E4=BB=BB?= =?UTF-8?q?=E5=8A=A1=E5=90=AF=E5=8A=A8=E6=A3=80=E6=9F=A5=E7=81=AF=E6=B2=A1?= =?UTF-8?q?=E6=9C=89=E7=A7=BB=E6=A4=8D=201.shift=E5=A4=9A=E9=80=89?= =?UTF-8?q?=E8=88=AA=E7=82=B9=202.=E4=BB=BB=E5=8A=A1=E6=95=B4=E4=BD=93?= =?UTF-8?q?=E7=A7=BB=E5=8A=A8?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Plane.FormationCreator/App.xaml.cs | 28 +- Plane.FormationCreator/AppConfig.cs | 9 +- .../Formation/CopterManager.cs | 2 +- .../Formation/Extensions.cs | 2 - .../Formation/FlightTaskManager.cs | 23 +- Plane.FormationCreator/MainWindow.xaml.cs | 3 + .../ViewModels/CopterListViewModel.cs | 2 +- .../ViewModels/ModifyTaskViewModel.cs | 264 ++++++++++++++---- .../Views/CopterListView.xaml.cs | 11 +- .../Views/MapView_CopterDrawing.cs | 1 + .../Views/ModifyTaskView.xaml | 46 +-- 11 files changed, 299 insertions(+), 92 deletions(-) diff --git a/Plane.FormationCreator/App.xaml.cs b/Plane.FormationCreator/App.xaml.cs index 0e5bc3a..cc675a4 100644 --- a/Plane.FormationCreator/App.xaml.cs +++ b/Plane.FormationCreator/App.xaml.cs @@ -113,19 +113,27 @@ namespace Plane.FormationCreator */ MainWindow = new MainWindow(); MainWindow.Show(); - - TcpServerConnectionManager.Instance.ConnectionEstablished += ConnectionManager_ConnectionEstablished; - if (!TcpServerConnectionManager.Instance.StartListening()) + try { - Alert.Show("网络连接不正常,无法启动监听。"); + + TcpServerConnectionManager.Instance.ConnectionEstablished += ConnectionManager_ConnectionEstablished; + if (!TcpServerConnectionManager.Instance.StartListening()) + { + Alert.Show("网络连接不正常,无法连接飞机。"); + return; + } + UdpServerConnectionManager.Instance.ExceptionThrown += (sender, e1) => + { + _logger.Log(e1.Exception); + }; + UdpServerConnectionManager.Instance.ConnectionEstablished += ConnectionManager_ConnectionEstablished; + UdpServerConnectionManager.Instance.StartReceiving(); + } + catch (Exception ex) + { + Alert.Show("网络连接不正常,无法连接飞机。"); return; } - UdpServerConnectionManager.Instance.ExceptionThrown += (sender, e1) => - { - _logger.Log(e1.Exception); - }; - UdpServerConnectionManager.Instance.ConnectionEstablished += ConnectionManager_ConnectionEstablished; - UdpServerConnectionManager.Instance.StartReceiving(); } private void Copter_TextReceived(object sender, MessageCreatedEventArgs e) { diff --git a/Plane.FormationCreator/AppConfig.cs b/Plane.FormationCreator/AppConfig.cs index 8311b30..bea7877 100644 --- a/Plane.FormationCreator/AppConfig.cs +++ b/Plane.FormationCreator/AppConfig.cs @@ -69,7 +69,8 @@ namespace Plane.FormationCreator } set { - _config.Center = $"{value.Lat},{value.Lng}"; + if (_config != null) + _config.Center = $"{value.Lat},{value.Lng}"; } } @@ -89,7 +90,8 @@ namespace Plane.FormationCreator } set { - _config.ZoomLevel = value; + if (_config != null) + _config.ZoomLevel = value; } } @@ -99,7 +101,8 @@ namespace Plane.FormationCreator { Directory.CreateDirectory(_dirPath); } - File.WriteAllText(_filePath, JsonConvert.SerializeObject(_config)); + if (_config != null) + File.WriteAllText(_filePath, JsonConvert.SerializeObject(_config)); } } } diff --git a/Plane.FormationCreator/Formation/CopterManager.cs b/Plane.FormationCreator/Formation/CopterManager.cs index 5067749..599f797 100644 --- a/Plane.FormationCreator/Formation/CopterManager.cs +++ b/Plane.FormationCreator/Formation/CopterManager.cs @@ -86,7 +86,7 @@ namespace Plane.FormationCreator.Formation // } //} - + public bool shiftkeydown; public IEnumerable SelectedCopters { get { return _selectedCoptersGetter().Cast(); } } /// diff --git a/Plane.FormationCreator/Formation/Extensions.cs b/Plane.FormationCreator/Formation/Extensions.cs index ca820b6..8f2fb6e 100644 --- a/Plane.FormationCreator/Formation/Extensions.cs +++ b/Plane.FormationCreator/Formation/Extensions.cs @@ -62,8 +62,6 @@ namespace Plane.FormationCreator.Formation public static bool ArrivedTarget(this ICopter copter, double targetLat, double targetLng, float targetAlt) { - // return copter.DistanceTo(targetLat, targetLng, targetAlt) < 0.6; //到达航点精度 - if (copter.GpsFixType == GpsFixType.RTKFIXED) return copter.DistanceTo(targetLat, targetLng, targetAlt) < RTKArrivedDis; //RTK到达航点精度0.6米 else diff --git a/Plane.FormationCreator/Formation/FlightTaskManager.cs b/Plane.FormationCreator/Formation/FlightTaskManager.cs index 3a468af..12355f7 100644 --- a/Plane.FormationCreator/Formation/FlightTaskManager.cs +++ b/Plane.FormationCreator/Formation/FlightTaskManager.cs @@ -224,7 +224,7 @@ namespace Plane.FormationCreator.Formation var newTask = new FlightTask(FlightTaskType.FlyTo); int coptindex = 0; - int colnum = 4; //自动生成列数=4 + int colnum = 5; //自动生成列数=4 float coldis = 5;//列相距5米 float rowdis = 5;//行相距5米 float matrixdis = 20; //生成方阵距离30米 @@ -363,6 +363,7 @@ namespace Plane.FormationCreator.Formation public void RestoreFlyToTask(bool staggerRoutes, dynamic singleCopterInfos) { var copters = _copterManager.Copters; + float tagalt = 15; if (!copters.Any()) return; AppEx.Current.AppMode = AppMode.ModifyingTask; var lastTask = Tasks.LastOrDefault(); @@ -371,11 +372,23 @@ namespace Plane.FormationCreator.Formation var center = nullableCenter.Value; var newTask = new FlightTask(FlightTaskType.FlyTo) { StaggerRoutes = staggerRoutes }; // TODO: 林俊清, 20150801, 处理实际飞行器数目与记录中数目不一致的情况。 - for (int i = 0; i < copters.Count && i < singleCopterInfos.Count; i++) + for (int i = 0; i < copters.Count; i++) { var copter = copters[i]; - var singleCopterInfoObj = singleCopterInfos[i]; - var newSingleCopterInfo = FlightTaskSingleCopterInfo.CreateForFlyToTask(copter, new LatLng((double)singleCopterInfoObj.latOffset, (double)singleCopterInfoObj.lngOffset), (float)singleCopterInfoObj.targetAlt,(bool)singleCopterInfoObj.showLED); + FlightTaskSingleCopterInfo newSingleCopterInfo; + if (i < singleCopterInfos.Count) + { + var singleCopterInfoObj = singleCopterInfos[i]; + tagalt = (float)singleCopterInfoObj.targetAlt; + newSingleCopterInfo = FlightTaskSingleCopterInfo.CreateForFlyToTask(copter, new LatLng((double)singleCopterInfoObj.latOffset, (double)singleCopterInfoObj.lngOffset), (float)singleCopterInfoObj.targetAlt, (bool)singleCopterInfoObj.showLED); + + } + else + { + newSingleCopterInfo = FlightTaskSingleCopterInfo.CreateForFlyToTask + (copter, (double)copter.Latitude, (double)copter.Longitude, tagalt, (bool)false); + + } newTask.SingleCopterInfos.Add(newSingleCopterInfo); } Tasks.Add(newTask); @@ -493,7 +506,7 @@ namespace Plane.FormationCreator.Formation loiterTimeTask.HeadYaw = HeadYaw; // foreach (var copter in copters) - for (int i=0; i < copters.Count && i < singleCopterInfos.Count; i++) + for (int i = 0; i < copters.Count; i++) { var copter = copters[i]; var singleCopterInfoObj = singleCopterInfos[i]; diff --git a/Plane.FormationCreator/MainWindow.xaml.cs b/Plane.FormationCreator/MainWindow.xaml.cs index 80deaed..858e1bb 100644 --- a/Plane.FormationCreator/MainWindow.xaml.cs +++ b/Plane.FormationCreator/MainWindow.xaml.cs @@ -107,7 +107,9 @@ namespace Plane.FormationCreator case Key.LeftShift: { + var copters = _copterManager.AcceptingControlCopters; Shiftkeydown = true; + _copterManager.shiftkeydown = true; break; } //开关SHOWLED @@ -359,6 +361,7 @@ namespace Plane.FormationCreator case Key.LeftShift: { Shiftkeydown = false; + _copterManager.shiftkeydown = false; break; } case Key.W: diff --git a/Plane.FormationCreator/ViewModels/CopterListViewModel.cs b/Plane.FormationCreator/ViewModels/CopterListViewModel.cs index 0bcd5bf..6d89ce6 100644 --- a/Plane.FormationCreator/ViewModels/CopterListViewModel.cs +++ b/Plane.FormationCreator/ViewModels/CopterListViewModel.cs @@ -54,7 +54,7 @@ namespace Plane.FormationCreator.ViewModels var center = _mapManager.Center; string id; - int colnum = 4; //自动生成列数=4 + int colnum = 5; //自动生成列数=4 float coldis = 3;//列相距5米 float rowdis = 3;//行相距5米 int currcol = 0; //当前列号 diff --git a/Plane.FormationCreator/ViewModels/ModifyTaskViewModel.cs b/Plane.FormationCreator/ViewModels/ModifyTaskViewModel.cs index 1e79bbb..26cf859 100644 --- a/Plane.FormationCreator/ViewModels/ModifyTaskViewModel.cs +++ b/Plane.FormationCreator/ViewModels/ModifyTaskViewModel.cs @@ -175,6 +175,12 @@ namespace Plane.FormationCreator.ViewModels set { Set(nameof(txtendindex), ref _txtendindex, value); } } + private float _directionvalue = 0; + public float directionvalue + { + get { return _directionvalue; } + set { Set(nameof(directionvalue), ref _directionvalue, value); } + } @@ -263,7 +269,57 @@ namespace Plane.FormationCreator.ViewModels } } + //调整所有任务经度 + private ICommand _ModiAllPosCommand; + public ICommand ModiAllPosCommand + { + get + { + return _ModiAllPosCommand ?? (_ModiAllPosCommand = new RelayCommand(async => + { + if (_flightTaskManager.Tasks.Count < 2) return; + float lowalt = 200; + + + int _startindex = 0; + int _endindex = _flightTaskManager.Tasks.Count - 1; + int lowtask = 0; + int lowCopter = 0; + + if ((txtStarindex != 0) && (txtendindex != 0)) + { + _startindex = txtStarindex; + _endindex = txtendindex; + } + + for (int i = _startindex; i <= _endindex; i++) + { + + if ((_flightTaskManager.Tasks[i].TaskType == FlightTaskType.TakeOff) || + (_flightTaskManager.Tasks[i].TaskType == FlightTaskType.ReturnToLand)) + continue; + + + for (int j = 0; j < _flightTaskManager.Tasks[i].SingleCopterInfos.Count; j++) + { + Tuple targetLatLng = new Tuple(0, 0); + + targetLatLng = GeographyUtils.CalcLatLngSomeMetersAway2D( + _flightTaskManager.Tasks[i].SingleCopterInfos[j].TargetLat, + _flightTaskManager.Tasks[i].SingleCopterInfos[j].TargetLng, + directionvalue, + Modialtvalue + ); + _flightTaskManager.Tasks[i].SingleCopterInfos[j].TargetLat = targetLatLng.Item1; + _flightTaskManager.Tasks[i].SingleCopterInfos[j].TargetLng = targetLatLng.Item2; + } + } + Alert.Show("指定步骤任务位置已向" + directionvalue + "度改变" + Modialtvalue + "米,注意是否有障碍物!"); + + })); + } + } private ICommand _LevelAverageCommand; @@ -366,56 +422,59 @@ namespace Plane.FormationCreator.ViewModels ////////////////////// var selectedCopter = _copterManager.SelectedCopters.FirstOrDefault(); - bool copterisselect; - int selectednumber = _copterManager.SelectedCopters.Count() - 1; - for (int i = 0; i < _flightTaskManager.SelectedTask.SingleCopterInfos.Count; i++) + if (_flightTaskManager.SelectedTask != null) { - copterisselect = false; - selectedCopter = _flightTaskManager.SelectedTask.SingleCopterInfos[i].Copter; - foreach (var capter in _copterManager.SelectedCopters) + bool copterisselect; + int selectednumber = _copterManager.SelectedCopters.Count() - 1; + for (int i = 0; i < _flightTaskManager.SelectedTask.SingleCopterInfos.Count; i++) { - if (capter == selectedCopter) - copterisselect = true; + copterisselect = false; + selectedCopter = _flightTaskManager.SelectedTask.SingleCopterInfos[i].Copter; + foreach (var capter in _copterManager.SelectedCopters) + { + if (capter == selectedCopter) + copterisselect = true; + } + if (copterisselect) + { + + tlat = _flightTaskManager.SelectedTask.SingleCopterInfos[i].TargetLat; + if (minlat == 0) + minlat = tlat; + if (tlat > maxlat) + maxlat = tlat; + else if (tlat < minlat) + minlat = tlat; + + } } - if (copterisselect) + avgl = (maxlat - minlat) / selectednumber; + int coptnum = 0; + + for (int i = 0; i < _flightTaskManager.SelectedTask.SingleCopterInfos.Count; i++) { + copterisselect = false; + selectedCopter = _flightTaskManager.SelectedTask.SingleCopterInfos[i].Copter; + foreach (var capter in _copterManager.SelectedCopters) + { + if (capter == selectedCopter) + copterisselect = true; - tlat = _flightTaskManager.SelectedTask.SingleCopterInfos[i].TargetLat; - if (minlat == 0) - minlat = tlat; - if (tlat > maxlat) - maxlat = tlat; - else if (tlat < minlat) - minlat = tlat; + } + if (copterisselect) + { + _flightTaskManager.SelectedTask.SingleCopterInfos[i].TargetLat = maxlat - avgl * coptnum; + coptnum++; + + } } + + /////////////////////// + + // await Task.Delay(100); // 如果不等待一段时间,很可能会再触发 DataStreamReceived 事件导致飞行器重新出现在地图上。 } - avgl = (maxlat - minlat) / selectednumber; - int coptnum = 0; - - for (int i = 0; i < _flightTaskManager.SelectedTask.SingleCopterInfos.Count; i++) - { - copterisselect = false; - selectedCopter = _flightTaskManager.SelectedTask.SingleCopterInfos[i].Copter; - foreach (var capter in _copterManager.SelectedCopters) - { - if (capter == selectedCopter) - copterisselect = true; - - } - if (copterisselect) - { - - _flightTaskManager.SelectedTask.SingleCopterInfos[i].TargetLat = maxlat - avgl * coptnum; - coptnum++; - - } - } - - /////////////////////// - - // await Task.Delay(100); // 如果不等待一段时间,很可能会再触发 DataStreamReceived 事件导致飞行器重新出现在地图上。 } })); } @@ -437,7 +496,9 @@ namespace Plane.FormationCreator.ViewModels var selectedCopter = _copterManager.SelectedCopters.FirstOrDefault(); - bool copterisselect; + if (_flightTaskManager.SelectedTask != null) + { + bool copterisselect; for (int i = 0; i < _flightTaskManager.SelectedTask.SingleCopterInfos.Count; i++) { copterisselect = false; @@ -477,10 +538,33 @@ namespace Plane.FormationCreator.ViewModels } } - + } + else + //调整飞机 + { + //模拟飞机才能调整 + if (selectedCopter is FakeCopter) + { + foreach (var capter in _copterManager.SelectedCopters) + { + tlat = capter.Latitude; + if (tlat > maxlat) + maxlat = tlat; + } + + foreach (var capter in _copterManager.SelectedCopters) + { + var copterfk = (FakeCopter)capter; + copterfk.SetProperties( + latitude: maxlat, + longitude: copterfk.Longitude); + } + } + } + + - //await Task.Delay(100); // 如果不等待一段时间,很可能会再触发 DataStreamReceived 事件导致飞行器重新出现在地图上。 })); @@ -505,7 +589,9 @@ public ICommand VerticlAlignmentCommand double tlng = 0; var selectedCopter = _copterManager.SelectedCopters.FirstOrDefault(); bool copterisselect; - for (int i = 0; i < _flightTaskManager.SelectedTask.SingleCopterInfos.Count; i++) + if (_flightTaskManager.SelectedTask != null) + { + for (int i = 0; i < _flightTaskManager.SelectedTask.SingleCopterInfos.Count; i++) { copterisselect = false; selectedCopter = _flightTaskManager.SelectedTask.SingleCopterInfos[i].Copter; @@ -544,11 +630,37 @@ public ICommand VerticlAlignmentCommand } } - - //await Task.Delay(100); // 如果不等待一段时间,很可能会再触发 DataStreamReceived 事件导致飞行器重新出现在地图上。 - })); + //await Task.Delay(100); // 如果不等待一段时间,很可能会再触发 DataStreamReceived 事件导致飞行器重新出现在地图上。 + + //await Task.Delay(100); // 如果不等待一段时间,很可能会再触发 DataStreamReceived 事件导致飞行器重新出现在地图上。 } + else + //调整飞机 + { + //模拟飞机才能调整 + if (selectedCopter is FakeCopter) + { + foreach (var capter in _copterManager.SelectedCopters) + { + tlng = capter.Longitude; + if (tlng > maxlng) + maxlng = tlng; + } + + foreach (var capter in _copterManager.SelectedCopters) + { + var copterfk = (FakeCopter)capter; + copterfk.SetProperties( + latitude: copterfk.Latitude, + longitude: maxlng); + } + } + } + + })); + } + } @@ -623,6 +735,8 @@ public ICommand VerticlAlignmentCommand double centlng = 0; double centlat = 0; var selectedCopter = _copterManager.SelectedCopters.FirstOrDefault(); + if (_flightTaskManager.SelectedTask != null) + { bool copterisselect; for (int i = 0; i < _flightTaskManager.SelectedTask.SingleCopterInfos.Count; i++) { @@ -685,6 +799,56 @@ public ICommand VerticlAlignmentCommand //// await Task.Delay(100); // 如果不等待一段时间,很可能会再触发 DataStreamReceived 事件导致飞行器重新出现在地图上。 + + } + else + //调整飞机 + { + //模拟飞机才能调整 + if (selectedCopter is FakeCopter) + { + foreach (var capter in _copterManager.SelectedCopters) + { + lngsum += capter.Longitude; + latsum += capter.Latitude; + selectcount++; + } + + //计算旋转中心 + if (selectcount > 0) + { + centlng = lngsum / selectcount; + centlat = latsum / selectcount; + } + else return; + + foreach (var capter in _copterManager.SelectedCopters) + { + + + double lpDistance = CalculationLogLatDistance.GetDistanceOne(centlng, centlat, + capter.Longitude, + capter.Latitude); + + CalculationLogLatDistance.MyLatLng mypos1, mypos2; + mypos1 = new CalculationLogLatDistance.MyLatLng(centlng, centlat); + mypos2 = new CalculationLogLatDistance.MyLatLng( + capter.Longitude + , capter.Latitude); + double lpAzimuth = CalculationLogLatDistance.getAngle(mypos1, mypos2); + double lng2 = 0; + double lat2 = 0; + CalculationLogLatDistance.ConvertDistanceToLogLat(centlng, centlat, lpDistance, + lpAzimuth + (double)RotateLine, out lng2, out lat2); + + var copterfk = (FakeCopter)capter; + copterfk.SetProperties( + latitude: lat2, + longitude: lng2); + } + } + } + })); } } @@ -791,6 +955,8 @@ public ICommand VerticlAlignmentCommand double centlat = 0; double centalt = 0; var selectedCopter = _copterManager.SelectedCopters.FirstOrDefault(); + if (_flightTaskManager.SelectedTask != null) + { bool copterisselect; for (int i = 0; i < _flightTaskManager.SelectedTask.SingleCopterInfos.Count; i++) { @@ -888,7 +1054,7 @@ public ICommand VerticlAlignmentCommand await Task.Delay(100); // 如果不等待一段时间,很可能会再触发 DataStreamReceived 事件导致飞行器重新出现在地图上。 - + } })); } } diff --git a/Plane.FormationCreator/Views/CopterListView.xaml.cs b/Plane.FormationCreator/Views/CopterListView.xaml.cs index a401157..3dc6ce7 100644 --- a/Plane.FormationCreator/Views/CopterListView.xaml.cs +++ b/Plane.FormationCreator/Views/CopterListView.xaml.cs @@ -32,7 +32,7 @@ namespace Plane.FormationCreator.Views _copterManager.SetSelectionDelegates( () => lvwDrones.SelectedItems, - copter => lvwDrones.SelectedItem = copter + SelectitemMessage ); lvwDrones.SelectionChanged += (sender, e) => { @@ -41,5 +41,14 @@ namespace Plane.FormationCreator.Views } private CopterManager _copterManager = ServiceLocator.Current.GetInstance(); + private void SelectitemMessage(ICopter copter) + { + + + if (!_copterManager.shiftkeydown) + lvwDrones.SelectedItem = copter; + else + lvwDrones.SelectedItems.Add(copter); + } } } diff --git a/Plane.FormationCreator/Views/MapView_CopterDrawing.cs b/Plane.FormationCreator/Views/MapView_CopterDrawing.cs index a3875d6..4fa3016 100644 --- a/Plane.FormationCreator/Views/MapView_CopterDrawing.cs +++ b/Plane.FormationCreator/Views/MapView_CopterDrawing.cs @@ -336,6 +336,7 @@ namespace Plane.FormationCreator.Views private void RegisterEventHandlersForTaskInfo(Ellipse wp, int taskIndex) { var info = _flightTaskManager.Tasks[taskIndex].SingleCopterInfos.FirstOrDefault(i => i.Copter == this.Copter); + if (info == null) return; info.PropertyChanged += (sender, e) => { switch (e.PropertyName) diff --git a/Plane.FormationCreator/Views/ModifyTaskView.xaml b/Plane.FormationCreator/Views/ModifyTaskView.xaml index afa8fac..db246f2 100644 --- a/Plane.FormationCreator/Views/ModifyTaskView.xaml +++ b/Plane.FormationCreator/Views/ModifyTaskView.xaml @@ -71,18 +71,18 @@ Margin="0,5,5,0" Command="{Binding VerticlRotateCommand}" CommandParameter="{Binding ElementName=txtAlignmentLine, Path=Text}"/> - - -