From c6de7dc49ec1639d76f0987f99967062e40a7915 Mon Sep 17 00:00:00 2001 From: zxd Date: Sat, 11 Aug 2018 12:13:21 +0800 Subject: [PATCH] =?UTF-8?q?=E4=BD=BF=E7=94=A8=E9=80=9A=E4=BF=A1=E6=A8=A1?= =?UTF-8?q?=E5=9D=97=E5=89=8D=E7=9A=84=E6=8F=90=E4=BA=A4=20=E6=B7=BB?= =?UTF-8?q?=E5=8A=A0=E9=80=9F=E5=BA=A6=E6=94=B9=E5=8F=98?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../Formation/FlightTaskManager.cs | 6 +- .../Formation/FlightTaskSingleCopterInfo.cs | 22 ++++++ .../FlightTaskSingleCopterInfo_FlyTo.cs | 47 ++++++++++++- Plane.FormationCreator/MainWindow.xaml | 2 +- .../ViewModels/ConnectViewModel.cs | 37 +++++----- .../ViewModels/ControlPanelViewModel.cs | 11 ++- .../Views/ModifyTaskView.xaml | 70 ++++++++++++++----- 7 files changed, 154 insertions(+), 41 deletions(-) diff --git a/Plane.FormationCreator/Formation/FlightTaskManager.cs b/Plane.FormationCreator/Formation/FlightTaskManager.cs index 420ab09..51d1b85 100644 --- a/Plane.FormationCreator/Formation/FlightTaskManager.cs +++ b/Plane.FormationCreator/Formation/FlightTaskManager.cs @@ -220,9 +220,9 @@ namespace Plane.FormationCreator.Formation var newTask = new FlightTask(FlightTaskType.FlyTo); int coptindex = 0; - int colnum = 5; //自动生成列数=4 - float coldis = 5;//列相距5米 - float rowdis = 5;//行相距5米 + int colnum = 10; //自动生成列数=4 + float coldis = 5f;//列相距5米 + float rowdis = 2.5f;//行相距5米 float matrixdis = 20; //生成方阵距离30米 diff --git a/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo.cs b/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo.cs index 98b49af..77be82e 100644 --- a/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo.cs +++ b/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo.cs @@ -84,6 +84,28 @@ namespace Plane.FormationCreator.Formation } } + //应用当前是否是降落点到所选 + private ICommand _SetIsChangeCommand; + public ICommand SetIsChangeCommand + { + get + { + return _SetIsChangeCommand ?? (_SetIsChangeCommand = new RelayCommand(async => + { + foreach (FlightTaskSingleCopterInfo info in _flightTaskManager.SelectedTask.SingleCopterInfos) + { + if (_copterManager.AcceptingControlCopters.Contains(info.Copter)) + { + info.IsChangeSpeed = IsChangeSpeed; + info.LevelSpeed = LevelSpeed; + info.UpSpeed = UpSpeed; + info.DownSpeed = DownSpeed; + } + } + })); + } + } + private ICommand _SetSelLandWaitTimeCommand; public ICommand SetSelLandWaitTimeCommand diff --git a/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo_FlyTo.cs b/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo_FlyTo.cs index b7db3b4..2f292aa 100644 --- a/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo_FlyTo.cs +++ b/Plane.FormationCreator/Formation/FlightTaskSingleCopterInfo_FlyTo.cs @@ -42,13 +42,58 @@ namespace Plane.FormationCreator.Formation } private bool _IsLandWaypoint = false; - //降落前的航点 只有高度有效,自动飞往起飞点,写入航点的经纬为1000 飞控自动认为1000是飞往起点 by张旭东 + + /// + /// 降落前的航点 只有高度有效,自动飞往起飞点,写入航点的经纬为90 180 飞控自动认为90 180是飞往起点 + /// public bool IsLandWaypoint { get { return _IsLandWaypoint; } set { Set(nameof(IsLandWaypoint), ref _IsLandWaypoint, value); } } + private bool _IsChangeSpeed = false; + + /// + /// 是否在当前航点前修改飞行速度 + /// + public bool IsChangeSpeed + { + get {return _IsChangeSpeed; } + set { Set(nameof(IsChangeSpeed), ref _IsChangeSpeed, value); } + } + + + private float _LevelSpeed = 5.0f; + /// + /// 水平速度 IsChangeSpeed为True有效 + /// + public float LevelSpeed + { + get { return _LevelSpeed; } + set { Set(nameof(LevelSpeed), ref _LevelSpeed, value); } + } + + + private float _UpSpeed = 2.5f; + /// + /// 上升速度 IsChangeSpeed为True有效 + /// + public float UpSpeed + { + get { return _UpSpeed; } + set { Set(nameof(UpSpeed), ref _UpSpeed, value); } + } + + private float _DownSpeed = 1.5f; + /// + /// 下降速度 IsChangeSpeed为True有效 + /// + public float DownSpeed + { + get { return _DownSpeed; } + set { Set(nameof(DownSpeed), ref _DownSpeed, value); } + } /* * //同一个任务每一架飞机的FlytoTime和LoiterTime保持统一,已将FlytoTime和LoiterTime改到FlightTask.cs中 diff --git a/Plane.FormationCreator/MainWindow.xaml b/Plane.FormationCreator/MainWindow.xaml index aed6a8e..2a4e0c0 100644 --- a/Plane.FormationCreator/MainWindow.xaml +++ b/Plane.FormationCreator/MainWindow.xaml @@ -61,7 +61,7 @@ Click="btnConnect_Click" /> - + diff --git a/Plane.FormationCreator/ViewModels/ConnectViewModel.cs b/Plane.FormationCreator/ViewModels/ConnectViewModel.cs index 5fa9bee..959eb48 100644 --- a/Plane.FormationCreator/ViewModels/ConnectViewModel.cs +++ b/Plane.FormationCreator/ViewModels/ConnectViewModel.cs @@ -86,7 +86,7 @@ namespace Plane.FormationCreator.ViewModels { return _SendCommand ?? (_SendCommand = new RelayCommand(async () => { - await SendCommandAsync(); + await SendCommandAsync(CopterNum); } )); } @@ -132,7 +132,7 @@ namespace Plane.FormationCreator.ViewModels { return _WriteIdCommand ?? (_WriteIdCommand = new RelayCommand(async () => { - await WriteIdCommandAsync(CopterNum, MavComm.COMMANDTYPE4); + await WriteIdCommandAsync(CopterNum, MavComm.COMM_SEARCH_MODE); } )); } @@ -146,7 +146,7 @@ namespace Plane.FormationCreator.ViewModels { return _ChangeWriteMissionCommand ?? (_ChangeWriteMissionCommand = new RelayCommand(async () => { - await WriteIdCommandAsync(0, MavComm.COMM_WRITE_MISSION); + await WriteIdCommandAsync(0, MavComm.COMM_DOWNLOAD_MODE); } )); } @@ -279,21 +279,24 @@ namespace Plane.FormationCreator.ViewModels } } - await WriteCommandAsync(copter, missions); + } - + bool result = await WriteCommandAsync(copter, missions); //_copterManager.Copters[i].WriteMissionListAsync(missions); - /* + if (!result) { - - Alert.Show($"飞机:{_copterManager.Copters[i].Name} 任务写入失败!"); - return; + Message.Show($"飞机:{copter.Name} 任务写入失败!"); } - */ + else + { + Message.Show($"飞机:{copter.Name} 任务写入成功!"); + } + + } - Alert.Show($"所有任务写入成功!"); + Alert.Show($"写入完成!"); })); } } @@ -326,11 +329,11 @@ namespace Plane.FormationCreator.ViewModels await commModule.GeneratePacketAsync((short)num, messageType); } - private async Task SendCommandAsync() + private async Task SendCommandAsync(int Count) { - Protocols.MavComm.comm_set_mav_count mavCount = new Protocols.MavComm.comm_set_mav_count(); - mavCount.mav_count = 200; - await commModule.GenerateDataAsync(0, (byte)Protocols.MavComm.COMM_SET_MAV_COUNT, mavCount); + MavComm.comm_set_mav_count mavCount = new MavComm.comm_set_mav_count(); + mavCount.mav_count = (short)Count; + await commModule.GenerateDataAsync(0, MavComm.COMM_SET_MAV_COUNT, mavCount); } public async Task DoCommandAsync(MAVLink.MAV_CMD actionid, float p1, float p2, float p3, float p4, float p5, float p6, float p7) @@ -357,7 +360,7 @@ namespace Plane.FormationCreator.ViewModels await Task.Delay(10); return true; } - private async Task WriteCommandAsync(ICopter copter, List missions) + private async Task WriteCommandAsync(ICopter copter, List missions) { List mission_list = new List(); foreach (IMission mission in missions) @@ -400,7 +403,7 @@ namespace Plane.FormationCreator.ViewModels mission_list.Add(req); } - await commModule.GeneratePacketAsyncNew(short.Parse(copter.Name), (byte)Protocols.MavComm.COMM_WRITE_MISSION, mission_list.ToArray()); + return await commModule.GeneratePacketAsyncNew(short.Parse(copter.Name), (byte)Protocols.MavComm.COMM_DOWNLOAD_MODE, mission_list.ToArray()); } diff --git a/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs b/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs index d83e36f..aa59c3b 100644 --- a/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs +++ b/Plane.FormationCreator/ViewModels/ControlPanelViewModel.cs @@ -426,7 +426,7 @@ namespace Plane.FormationCreator.ViewModels } - private string _RTKcomvalue = "COM3"; + private string _RTKcomvalue = "COM6"; public string RTKcomvalue { get { return _RTKcomvalue; } @@ -828,7 +828,14 @@ namespace Plane.FormationCreator.ViewModels case FlightTaskType.FlyTo: missions.AddRange(CreateLEDMissions(_flightTaskManager.Tasks[j].SingleCopterInfos[i].LEDInfos)); - + if (_flightTaskManager.Tasks[j].SingleCopterInfos[i].IsChangeSpeed) + { + missions.Add(Mission.CreateChangeSpeedMission( + _flightTaskManager.Tasks[j].SingleCopterInfos[i].LevelSpeed, + _flightTaskManager.Tasks[j].SingleCopterInfos[i].UpSpeed, + _flightTaskManager.Tasks[j].SingleCopterInfos[i].DownSpeed) + ); + } double Lat = _flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLat - _flightTaskManager.OriginLat; double Lng = _flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLng - _flightTaskManager.OriginLng; if (_flightTaskManager.Tasks[j].SingleCopterInfos[i].IsLandWaypoint) diff --git a/Plane.FormationCreator/Views/ModifyTaskView.xaml b/Plane.FormationCreator/Views/ModifyTaskView.xaml index 13047c8..82c21c3 100644 --- a/Plane.FormationCreator/Views/ModifyTaskView.xaml +++ b/Plane.FormationCreator/Views/ModifyTaskView.xaml @@ -59,7 +59,7 @@ - +