diff --git a/Plane.FormationCreator/Formation/FlightTaskManager.cs b/Plane.FormationCreator/Formation/FlightTaskManager.cs index fdc7882..f1ec1ae 100644 --- a/Plane.FormationCreator/Formation/FlightTaskManager.cs +++ b/Plane.FormationCreator/Formation/FlightTaskManager.cs @@ -442,8 +442,70 @@ namespace Plane.FormationCreator.Formation public void ImportC4DFlytoTask(string txt) { string[] lines = txt.Replace("\r\n", "\n").Split('\n'); - if (lines.Length != _copterManager.Copters.Count) + + if (lines.Length % (_copterManager.Copters.Count + 1) != 0) + { + Alert.Show("文件内容错误!"); return; + } + + int taskCount = lines.Length / (_copterManager.Copters.Count + 1); + int startIndex; + string line; + Dictionary PointDic; + for (int i = 0; i < taskCount; i++) + { + startIndex = i * (_copterManager.Copters.Count + 1); + string taskName = lines[startIndex]; + PointDic = new Dictionary(); + for (int j = 0; j < _copterManager.Copters.Count; j++) + { + line = lines[startIndex + j + 1]; + string[] parameters = line.Split(' '); + int id = Convert.ToInt32(parameters[0]); + string frame = parameters[1]; + string[] point = new string[3]; + point[0] = parameters[1]; //左右 经度 + point[1] = parameters[2]; //上下 高度 + point[2] = parameters[3]; //前后 纬度 + PointDic.Add(id, point); + } + + var lastTask = Tasks.LastOrDefault(); + var newTask = new FlightTask(FlightTaskType.FlyTo) { StaggerRoutes = true, FlytoTime = 10, LoiterTime = 10 }; + newTask.TaskCnName = taskName; + for (int k = 0; k < PointDic.Count; k++) + { + string[] point = PointDic[k + 1]; + + //string frame = parameters[1]; + string x = point[0]; //左右 经度 + string y = point[1]; //上下 高度 + string z = point[2]; //前后 纬度 + Tuple observationLatLng = null; + observationLatLng = GeographyUtils.CalcLatLngSomeMetersAway2D( + OriginLat, + OriginLng, + 90, + Convert.ToSingle(x) / 100); + + observationLatLng = GeographyUtils.CalcLatLngSomeMetersAway2D( + observationLatLng.Item1, + observationLatLng.Item2, + 0, + Convert.ToSingle(z) / 100); + + var thisSingleCopterInfo = FlightTaskSingleCopterInfo.CreateForFlyToTask( + _copterManager.Copters[k], new LatLng(observationLatLng.Item1 - OriginLat, observationLatLng.Item2 - OriginLng), + Convert.ToSingle(y) / 100, false); + newTask.SingleCopterInfos.Add(thisSingleCopterInfo); + + } + Tasks.Add(newTask); + TaskAdded?.Invoke(this, new FlightTaskAddedEventArgs { LastTask = lastTask, AddedTask = newTask }); + } + + /* Dictionary PointDic = new Dictionary(); foreach (string line in lines) { @@ -451,9 +513,9 @@ namespace Plane.FormationCreator.Formation int id = Convert.ToInt32(parameters[0]); string frame = parameters[1]; string[] point = new string[3]; - point[0] = parameters[2]; //左右 经度 - point[1] = parameters[3]; //上下 高度 - point[2] = parameters[4]; //前后 纬度 + point[0] = parameters[1]; //左右 经度 + point[1] = parameters[2]; //上下 高度 + point[2] = parameters[3]; //前后 纬度 PointDic.Add(id, point); } @@ -489,6 +551,7 @@ namespace Plane.FormationCreator.Formation } Tasks.Add(newTask); TaskAdded?.Invoke(this, new FlightTaskAddedEventArgs { LastTask = lastTask, AddedTask = newTask }); + */ } @@ -538,7 +601,7 @@ namespace Plane.FormationCreator.Formation } } - public void RestoreFlyToTask(bool staggerRoutes, int flytoTime, int loiterTime, string taskName, dynamic singleCopterInfos) + public void RestoreFlyToTask(bool staggerRoutes, int flytoTime, int loiterTime, string taskName, dynamic singleCopterInfos, bool isMeter) { var copters = _copterManager.Copters; float tagalt = 15; @@ -559,10 +622,19 @@ namespace Plane.FormationCreator.Formation { var singleCopterInfoObj = singleCopterInfos[i]; tagalt = (float)singleCopterInfoObj.targetAlt; - newSingleCopterInfo = FlightTaskSingleCopterInfo.CreateForFlyToTask( - copter, new LatLng((double)singleCopterInfoObj.latOffset, - (double)singleCopterInfoObj.lngOffset), (float)singleCopterInfoObj.targetAlt - copter.GroundAlt, (bool)singleCopterInfoObj.isLandWaypoint); - + if (isMeter) + newSingleCopterInfo = FlightTaskSingleCopterInfo.CreateForFlyToTask( + copter, + (double)singleCopterInfoObj.x, + (double)singleCopterInfoObj.y, + (float)singleCopterInfoObj.targetAlt - copter.GroundAlt, + (bool)singleCopterInfoObj.isLandWaypoint); + else + newSingleCopterInfo = FlightTaskSingleCopterInfo.CreateForFlyToTask( + copter, + new LatLng((double)singleCopterInfoObj.latOffset, (double)singleCopterInfoObj.lngOffset), + (float)singleCopterInfoObj.targetAlt - copter.GroundAlt, (bool)singleCopterInfoObj.isLandWaypoint); + var jsonArray = singleCopterInfoObj.ledInfos as Newtonsoft.Json.Linq.JArray; ObservableCollection ledList = jsonArray.ToObject>(); foreach(LEDInfo info in ledList) @@ -767,6 +839,165 @@ namespace Plane.FormationCreator.Formation SelectedTaskIndex = Tasks.Count - 1; } + //导出任务 (单位:米) + public IEnumerable ExportTasksToMeter() + { + var tasks = Tasks.Select(task => + { + var type = task.TaskType; + switch (type) + { + case FlightTaskType.TakeOff: + return new { + type = type, + takeoffnumber = TakeOffNumAttr, + takeoffTime = task.TakeOffTime, + singleCopterInfos = task.SingleCopterInfos.Select(info => + { + return new + { + waitTime = info.TakeOffWaitTime, + ledInfos = info.LEDInfos + }; + }) + }; + case FlightTaskType.FlyTo: + return new + { + type = type, + staggerRoutes = task.StaggerRoutes, + flytoTime = task.FlytoTime, + loiterTime = task.LoiterTime, + taskname = task.TaskCnName, + singleCopterInfos = task.SingleCopterInfos.Select(info => + { + var offset = info.LatLngOffset; + return new + { + x = info.X, + y = info.Y, + targetAlt = info.TargetAlt + info.Copter.GroundAlt, //导出时加上地面摆放高度,导入后若没有摆放高度,模拟就会清楚的看到高度错误 + //showLED = info.FlytoShowLED, + ledInfos = info.LEDInfos, + isLandWaypoint = info.IsLandWaypoint, + isChangeSpeed = info.IsChangeSpeed, + levelSpeed = info.LevelSpeed, + upSpeed = info.UpSpeed, + downSpeed = info.DownSpeed + }; + }) + }; + case FlightTaskType.Turn: + return new + { + type = type, + singleCopterInfos = task.SingleCopterInfos.Select(info => + { + var offset = info.LatLngOffset; + return new + { + latOffset = offset.Lat, + lngOffset = offset.Lng, + targetAlt = info.TargetAlt, + targetHeading = info.TargetHeading + }; + }) + }; + case FlightTaskType.Loiter: // 导出悬停任务 + return new + { + type = type, + loiterTimeAttr = task.LoiterTimeAttr, + flashCheck = task.flashAttr, + flashCheckPeriod = task.flashPeriodAttr, + oneByOneCheck = task.oneByOneAttr, + oneByOneCheckPeriod = task.oneByOnePeriodAttr, + flashNameArray = task.flashCopterNameArray, + flashIndexArray = task.flashCopterIndexArray, + ChangeYaw = task.ChangeYaw, + HeadYaw = task.HeadYaw, + + + singleCopterInfos = task.SingleCopterInfos.Select(info => + { + var offset = info.LatLngOffset; + return new + { + latOffset = offset.Lat, + lngOffset = offset.Lng, + targetAlt = info.TargetAlt + }; + }) + }; + case FlightTaskType.Circle: + return new + { + type = type, + singleCopterInfos = task.SingleCopterInfos.Select(info => + { + var offset = info.LatLngOffset; + return new + { + latOffset = offset.Lat, + lngOffset = offset.Lng, + targetAlt = info.TargetAlt, + centerDirectionDeg = info.CenterDirectionDeg, + radius = info.Radius, + rate = info.Rate, + turns = info.Turns, + channel3 = info.Channel3 + }; + }) + }; + case FlightTaskType.SimpleCircle: + return new + { + type = type, + singleCopterInfos = task.SingleCopterInfos.Select(info => + { + var offset = info.LatLngOffset; + return new + { + latOffset = offset.Lat, + lngOffset = offset.Lng, + targetAlt = info.TargetAlt, + rate = info.Rate, + turns = info.Turns, + channel3 = info.Channel3 + }; + }) + }; + case FlightTaskType.ReturnToLand: // added by ZJF + return new + { + type = type, + rtlalt= task.RTLAlt, + retnumber = task.RetNumAttr + + }; + + case FlightTaskType.Land: + { + return new + { + type = type, + singleCopterInfos = task.SingleCopterInfos.Select(info => + { + return new + { + waitTime = info.LandWaitTime + }; + }) + + }; + } + default: + throw new NotImplementedException(type + " task export not implemented."); + } + }); + return tasks; + } + //导出任务 public IEnumerable ExportTasks() { @@ -1019,7 +1250,7 @@ namespace Plane.FormationCreator.Formation //导入任务,可设置导入哪些步骤 - public void ImportTasksindex(dynamic tasks, int startindex,int endindex) + public void ImportTasksindex(dynamic tasks, int startindex,int endindex, bool isMeter) { var copters = _copterManager.Copters; @@ -1041,7 +1272,7 @@ namespace Plane.FormationCreator.Formation RestoreTakeOffTask((byte)task.takeoffTime, task.singleCopterInfos); break; case FlightTaskType.FlyTo: - RestoreFlyToTask((bool)task.staggerRoutes, (int)task.flytoTime, (int)task.loiterTime, (string)task.taskname, task.singleCopterInfos); + RestoreFlyToTask((bool)task.staggerRoutes, (int)task.flytoTime, (int)task.loiterTime, (string)task.taskname, task.singleCopterInfos, isMeter); break; case FlightTaskType.Turn: RestoreTurnTask(task.singleCopterInfos); @@ -1376,8 +1607,10 @@ namespace Plane.FormationCreator.Formation } } + + // 导入任务 - public void ImportTasks(dynamic tasks) + public void ImportTasks(dynamic tasks, bool isMeter) { var copters = _copterManager.Copters; @@ -1394,7 +1627,7 @@ namespace Plane.FormationCreator.Formation RestoreTakeOffTask((byte)task.takeoffTime, task.singleCopterInfos); break; case FlightTaskType.FlyTo: - RestoreFlyToTask((bool)task.staggerRoutes, (int)task.flytoTime, (int)task.loiterTime, (string)task.taskname, task.singleCopterInfos); + RestoreFlyToTask((bool)task.staggerRoutes, (int)task.flytoTime, (int)task.loiterTime, (string)task.taskname, task.singleCopterInfos, isMeter); break; case FlightTaskType.Turn: RestoreTurnTask(task.singleCopterInfos); diff --git a/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo.cs b/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo.cs index 2849d48..6c396ed 100644 --- a/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo.cs +++ b/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo.cs @@ -8,6 +8,7 @@ using System.Text; using System.Threading.Tasks; using System.Windows.Input; using GalaSoft.MvvmLight.Command; +using Plane.Geography; namespace Plane.FormationCreator.Formation { @@ -182,6 +183,51 @@ namespace Plane.FormationCreator.Formation } } + public double X + { + get + { + double x = GeographyUtils.CalcDistance(_flightTaskManager.OriginLat, _flightTaskManager.OriginLng, 0, + _flightTaskManager.OriginLat, TargetLng, 0); + if (TargetLng < _flightTaskManager.OriginLng) x = -x; + + return x; + } + set + { + Tuple observationLatLng = null; + observationLatLng = GeographyUtils.CalcLatLngSomeMetersAway2D( + _flightTaskManager.OriginLat, + _flightTaskManager.OriginLng, + 90, + Convert.ToSingle(value)); + TargetLng = observationLatLng.Item2; + } + } + + public double Y + { + get + { + double y = GeographyUtils.CalcDistance(_flightTaskManager.OriginLat, _flightTaskManager.OriginLng, 0, + TargetLat, _flightTaskManager.OriginLng, 0); + if (TargetLat < _flightTaskManager.OriginLat) y = -y; + + return y; + } + set + { + Tuple observationLatLng = null; + observationLatLng = GeographyUtils.CalcLatLngSomeMetersAway2D( + _flightTaskManager.OriginLat, + _flightTaskManager.OriginLng, + 0, + Convert.ToSingle(value)); + TargetLat = observationLatLng.Item1; + } + } + + public LatLng LatLngOffset { @@ -200,6 +246,8 @@ namespace Plane.FormationCreator.Formation } } + + public LatLng GetOrigin() { return _copterManager.Copters.GetCenter() ?? LatLng.Empty; diff --git a/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo_FlyTo.cs b/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo_FlyTo.cs index 2f292aa..0ae29a9 100644 --- a/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo_FlyTo.cs +++ b/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo_FlyTo.cs @@ -33,8 +33,20 @@ namespace Plane.FormationCreator.Formation }; return info; } - - private bool _FlytoShowLED = true; + + public static FlightTaskSingleCopterInfo CreateForFlyToTask(ICopter copter, double x, double y, float targetAlt, bool isLandWaypoint) + { + var info = new FlightTaskSingleCopterInfo(copter) + { + X = x, + Y = y, + TargetAlt = targetAlt, + IsLandWaypoint = isLandWaypoint + }; + return info; + } + + private bool _FlytoShowLED = true; public bool FlytoShowLED { get { return _FlytoShowLED; } diff --git a/Plane.FormationCreator/Formation/RtcmManager.cs b/Plane.FormationCreator/Formation/RtcmManager.cs index 39c4f46..3102fbf 100644 --- a/Plane.FormationCreator/Formation/RtcmManager.cs +++ b/Plane.FormationCreator/Formation/RtcmManager.cs @@ -238,15 +238,16 @@ namespace Plane.FormationCreator.Formation public async Task Close() { + await _commModuleManager.CloseRtcmLoop(); Rtcmthreadrun = false; comPort.Close(); - await Task.Delay(1); } private async Task RtcmLoop() { int reconnecttimeout = 10; DateTime lastrecv = DateTime.MinValue; + await _commModuleManager.StartRtcmLoop(); while (Rtcmthreadrun) { try @@ -289,7 +290,7 @@ namespace Plane.FormationCreator.Formation if ((seenmsg = rtcm.Read(buffer[a])) > 0) { bpsusefull += rtcm.length; - Message.Show($"{DateTime.Now.ToString("HH-mm-ss:fff")} rtcm.length = {rtcm.length}"); + await _commModuleManager.InjectGpsRTCMDataAsync(rtcm.packet, rtcm.length); string msgname = "Rtcm" + seenmsg; diff --git a/Plane.FormationCreator/MainWindow.xaml b/Plane.FormationCreator/MainWindow.xaml index 5df3f2f..7c3c701 100644 --- a/Plane.FormationCreator/MainWindow.xaml +++ b/Plane.FormationCreator/MainWindow.xaml @@ -116,6 +116,7 @@ + @@ -164,6 +165,10 @@ x:Name="groupsView" Visibility="Collapsed"> + + diff --git a/Plane.FormationCreator/MainWindow.xaml.cs b/Plane.FormationCreator/MainWindow.xaml.cs index f1f6bc8..24c2c47 100644 --- a/Plane.FormationCreator/MainWindow.xaml.cs +++ b/Plane.FormationCreator/MainWindow.xaml.cs @@ -35,13 +35,7 @@ namespace Plane.FormationCreator this.DataContext = ServiceLocator.Current.GetInstance(); - DateTime dateTimeClose = DateTime.Parse("2019-12-7"); - if (DateTime.UtcNow > dateTimeClose) - { - MessageBox.Show("软件过旧,请更新!"); - Application.Current.Shutdown(); - throw new NotImplementedException(); - } + //ShowConnectDialog(); //if (_copterManager.CoptersForControlling.Count <= 0) //{ @@ -532,5 +526,14 @@ namespace Plane.FormationCreator else groupsView.Visibility = Visibility.Visible; } + + private void btnVirtualId_Click(object sender, RoutedEventArgs e) + { + CheckBox checkbox = sender as CheckBox; + if (checkbox.IsChecked == false) + configVirtualView.Visibility = Visibility.Collapsed; + else + configVirtualView.Visibility = Visibility.Visible; + } } } diff --git a/Plane.FormationCreator/Plane.FormationCreator.csproj b/Plane.FormationCreator/Plane.FormationCreator.csproj index 761caa5..cfe3fd9 100644 --- a/Plane.FormationCreator/Plane.FormationCreator.csproj +++ b/Plane.FormationCreator/Plane.FormationCreator.csproj @@ -119,6 +119,8 @@ ..\packages\System.Data.SQLite.Linq.1.0.109.0\lib\net46\System.Data.SQLite.Linq.dll True + + ..\packages\MahApps.Metro.1.5.0\lib\net45\System.Windows.Interactivity.dll True @@ -205,6 +207,7 @@ + @@ -219,6 +222,9 @@ CalibrationWindow.xaml + + ConfigVirtualIdView.xaml + ControlPanelView.xaml @@ -348,6 +354,10 @@ Designer MSBuild:Compile + + Designer + MSBuild:Compile + Designer MSBuild:Compile diff --git a/Plane.FormationCreator/ServiceLocatorConfigurer.cs b/Plane.FormationCreator/ServiceLocatorConfigurer.cs index 712241c..2735eb4 100644 --- a/Plane.FormationCreator/ServiceLocatorConfigurer.cs +++ b/Plane.FormationCreator/ServiceLocatorConfigurer.cs @@ -36,6 +36,7 @@ namespace Plane.FormationCreator _container.Register(); _container.Register(); _container.Register(); + _container.Register(); _container.Register(() => new LocalFileLogger(new DebugLogger())); diff --git a/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs b/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs index d3457e4..21f104e 100644 --- a/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs +++ b/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs @@ -1330,7 +1330,6 @@ namespace Plane.FormationCreator.ViewModels var _flightTaskManager = ServiceLocator.Current.GetInstance(); for (j = 0; j < _flightTaskManager.Tasks.Count; j++) { - switch (_flightTaskManager.Tasks[j].TaskType) { case FlightTaskType.TakeOff: @@ -1389,7 +1388,8 @@ namespace Plane.FormationCreator.ViewModels break; } } - bool result = await _commModuleManager.WriteMissionListAsync(short.Parse(_copterManager.Copters[i].Id), missions); + var targetCopter = _copterManager.Copters.FirstOrDefault(o => o.VirtualId == (i+1)); + bool result = await _commModuleManager.WriteMissionListAsync(short.Parse(targetCopter.Id), missions); //CommWriteMissinState state = new CommWriteMissinState(result); //_commModuleManager.missionWriteState.Add(int.Parse(_copterManager.Copters[i].Id), state); if (!result) diff --git a/Plane.FormationCreator/ViewModels/CopterListViewModel.cs b/Plane.FormationCreator/ViewModels/CopterListViewModel.cs index d6fcdbb..82db035 100644 --- a/Plane.FormationCreator/ViewModels/CopterListViewModel.cs +++ b/Plane.FormationCreator/ViewModels/CopterListViewModel.cs @@ -20,6 +20,7 @@ using Plane.FormationCreator.Util; using Newtonsoft.Json; using System.IO; using Newtonsoft.Json.Linq; +using Plane.Windows.Messages; namespace Plane.FormationCreator.ViewModels { @@ -99,6 +100,13 @@ namespace Plane.FormationCreator.ViewModels set { Set(nameof(ContinuousNum), ref _ContinuousNum, value); } } + private bool _ShowTemp = false; + public bool ShowTemp + { + get { return _ShowTemp; } + set { Set(nameof(ShowTemp), ref _ShowTemp, value); } + } + public ObservableCollection CopterGroups { get; } = new ObservableCollection(); @@ -165,6 +173,25 @@ namespace Plane.FormationCreator.ViewModels } } + bool showVirtualId = false; + + private ICommand _SwitchIdVirtualIdCommand; + public ICommand SwitchIdVirtualIdCommand + { + get + { + return _SwitchIdVirtualIdCommand ?? (_SwitchIdVirtualIdCommand = new RelayCommand(async () => + { + showVirtualId = !showVirtualId; + foreach (var copter in _copterManager.Copters) + { + copter.DisplayVirtualId = showVirtualId; + } + await Task.Delay(10); + })); + } + } + private ICommand _AddVirtualCopterCommand; public ICommand AddVirtualCopterCommand { @@ -292,6 +319,9 @@ namespace Plane.FormationCreator.ViewModels } } + + + private ICommand _SetCoptersPutCommand; public ICommand SetCoptersPutCommand { diff --git a/Plane.FormationCreator/ViewModels/MainViewModel.cs b/Plane.FormationCreator/ViewModels/MainViewModel.cs index 28ee8b8..c075848 100644 --- a/Plane.FormationCreator/ViewModels/MainViewModel.cs +++ b/Plane.FormationCreator/ViewModels/MainViewModel.cs @@ -13,6 +13,7 @@ using Microsoft.Win32; using Microsoft.Practices.ServiceLocation; using System.IO; using Newtonsoft.Json; +using Plane.Geography; namespace Plane.FormationCreator.ViewModels { @@ -195,36 +196,44 @@ namespace Plane.FormationCreator.ViewModels return; } - string exportedText; - - var taskObject = _flightTaskManager.ExportTasks(); - if (OnlyImpotWaypointS) - { - exportedText = JsonConvert.SerializeObject(taskObject); - } - else - { - var groupObject = _groupManager.ExportGroups(); - var locateObject = ExportLocate(); - - - object obj = new - { - groups = groupObject, - locate = locateObject, - tasks = taskObject - }; - exportedText = JsonConvert.SerializeObject(obj); - } - - var dialog = new SaveFileDialog { - DefaultExt = "fcg", - Filter = "编队飞行任务 (*.fcg)|*.fcg" + DefaultExt = "fcgm", + Filter = "编队任务 (*.fcgm)|*.fcgm|旧编队任务(*.fcg)|*.fcg" }; if (dialog.ShowDialog() == true) { + IEnumerable taskObject; + string extension = Path.GetExtension(dialog.FileName); + if (extension == ".fcgm") + taskObject = _flightTaskManager.ExportTasksToMeter(); + else + taskObject = _flightTaskManager.ExportTasks(); + + string exportedText; + + if (OnlyImpotWaypointS) + { + exportedText = JsonConvert.SerializeObject(taskObject); + } + else + { + var groupObject = _groupManager.ExportGroups(); + var locateObject = ExportLocate(); + + + object obj = new + { + groups = groupObject, + locate = locateObject, + tasks = taskObject + }; + exportedText = JsonConvert.SerializeObject(obj); + } + + + + File.WriteAllText(dialog.FileName, exportedText); } })); @@ -245,21 +254,6 @@ namespace Plane.FormationCreator.ViewModels return locateList; } - //导出航点 单位米 - private List ExportLocateToMeter() - { - List locateList = new List(); - foreach (var copter in _copterManager.Copters) - { - double[] locate = new double[3]; - locate[0] = copter.Latitude - _flightTaskManager.OriginLat; - locate[1] = copter.Longitude - _flightTaskManager.OriginLng; - locate[2] = copter.GroundAlt; - locateList.Add(locate); - } - return locateList; - } - private int _txtStarindex = 0; public int txtStarindex @@ -289,11 +283,14 @@ namespace Plane.FormationCreator.ViewModels } var dialog = new OpenFileDialog { - DefaultExt = "fcg", - Filter = "编队飞行任务 (*.fcg)|*.fcg" + DefaultExt = "fcgm", + Filter = "编队任务 (*.fcgm)|*.fcgm|旧编队任务(*.fcg)|*.fcg" }; if (dialog.ShowDialog() == true) { + + + int _startindex = txtStarindex; int _endindex = txtendindex; @@ -320,10 +317,13 @@ namespace Plane.FormationCreator.ViewModels //int task Newtonsoft.Json.Linq.JArray + string extension = Path.GetExtension(dialog.FileName); + bool isMeter = extension == ".fcgm"; + + if ((txtStarindex == 0) && (txtendindex == 0)) { - - _flightTaskManager.ImportTasks(taskinfo); + _flightTaskManager.ImportTasks(taskinfo, isMeter); } else { @@ -332,7 +332,7 @@ namespace Plane.FormationCreator.ViewModels _startindex = 1; if (_endindex == 0) _endindex = _startindex; - _flightTaskManager.ImportTasksindex(taskinfo, _startindex, _endindex); + _flightTaskManager.ImportTasksindex(taskinfo, _startindex, _endindex, isMeter); } diff --git a/Plane.FormationCreator/Views/CopterListView.xaml b/Plane.FormationCreator/Views/CopterListView.xaml index f85c398..0b5ec16 100644 --- a/Plane.FormationCreator/Views/CopterListView.xaml +++ b/Plane.FormationCreator/Views/CopterListView.xaml @@ -17,6 +17,9 @@ + @@ -59,6 +62,10 @@ + @@ -83,7 +90,7 @@ Margin="0,0,5,0" Text="10" VerticalContentAlignment="Center" /> -