添加了降落任务,一键起飞,测试电机,flyto的下降点,检测所有飞机5秒平均电压,通信模块的测试,起飞延时,降落延时,界面修改

This commit is contained in:
zxd 2018-08-03 11:43:23 +08:00
parent 27d8974ee9
commit cb188feb48
25 changed files with 1242 additions and 788 deletions

View File

@ -100,19 +100,21 @@ namespace Plane.FormationCreator
md.Add(new ResourceDictionary { Source = new Uri("pack://application:,,,/Styles/Colors.xaml") });
md.Add(new ResourceDictionary { Source = new Uri("pack://application:,,,/Styles.xaml") });
/*
new UpdateChecker("http://dl.Plane.com/tools/ver.php?app=FormationCreator", _logger)
.CheckAsync(ver =>
{
var currentVersion = this.GetType().Assembly.GetName().Version;
if (currentVersion < ver
&& Alert.Show("检测到新版本,请下载。", "更新提示", MessageBoxButton.YesNo) == MessageBoxResult.Yes)
{
Process.Start("http://dl.Plane.com/tools/FormationCreatorSetup.exe");
this.Shutdown();
}
});
*/
/*
new UpdateChecker("http://dl.Plane.com/tools/ver.php?app=FormationCreator", _logger)
.CheckAsync(ver =>
{
var currentVersion = this.GetType().Assembly.GetName().Version;
if (currentVersion < ver
&& Alert.Show("检测到新版本,请下载。", "更新提示", MessageBoxButton.YesNo) == MessageBoxResult.Yes)
{
Process.Start("http://dl.Plane.com/tools/FormationCreatorSetup.exe");
this.Shutdown();
}
});
*/
System.Windows.FrameworkCompatibilityPreferences.KeepTextBoxDisplaySynchronizedWithTextProperty = false;
MainWindow = new MainWindow();
MainWindow.Show();
try

View File

@ -35,26 +35,53 @@ namespace Plane.FormationCreator.Formation
get { return _TaskType; }
set
{
if (_TaskType != value)
Set(nameof(TaskType), ref _TaskType, value);
//if (_TaskType != value)
{
RaisePropertyChanged(nameof(TaskTypeIndex));
}
Set(nameof(TaskType), ref _TaskType, value);
}
}
/*
public int TaskTypeIndex
{
get { return (int)TaskType; }
set
{
TaskType = (FlightTaskType)value;
VerticalLift = false;
if ( (value == (int)FlightTaskType.Loiter) || (value == (int)FlightTaskType.Circle) )
{
VerticalLift = true;
}
}
}
*/
public int TaskTypeIndex
{
get {
int index = 1;
switch (TaskType)
{
case FlightTaskType.TakeOff:index = 0; break;
case FlightTaskType.FlyTo: index = 1; break;
case FlightTaskType.Land: index = 2; break;
}
return index;
}
set
{
switch (value)
{
case 0: TaskType = FlightTaskType.TakeOff; break;
case 1: TaskType = FlightTaskType.FlyTo; break;
case 2: TaskType = FlightTaskType.Land; break;
}
}
}
private bool _IsSelected;
public bool IsSelected
@ -72,19 +99,7 @@ namespace Plane.FormationCreator.Formation
}
//同一个任务每一架飞机的FlytoTime和LoiterTime保持统一
private int _FlytoTime = 10;
public int FlytoTime
{
get { return _FlytoTime; }
set { Set(nameof(FlytoTime), ref _FlytoTime, value); }
}
private int _LoiterTime = 10;
public int LoiterTime
{
get { return _LoiterTime; }
set { Set(nameof(LoiterTime), ref _LoiterTime, value); }
}
public List<FlightTaskSingleCopterInfo> SingleCopterInfos { get; set; } = new List<FlightTaskSingleCopterInfo>();
@ -122,6 +137,9 @@ namespace Plane.FormationCreator.Formation
//多架同时返航
await MutilRunReturnToLandTaskAsync().ConfigureAwait(false);
break;
case FlightTaskType.Land:
await MutilLandTaskAsync().ConfigureAwait(false);
break;
default:
throw new InvalidOperationException();
}
@ -137,6 +155,7 @@ namespace Plane.FormationCreator.Formation
// LEDAction = 4,
ReturnToLand = 4, // added by ZJF. 20160315
SimpleCircle = 5,
Land = 6,
TakeOff = 100
}
}

View File

@ -402,11 +402,14 @@ namespace Plane.FormationCreator.Formation
tagalt = (float)singleCopterInfoObj.targetAlt;
newSingleCopterInfo = FlightTaskSingleCopterInfo.CreateForFlyToTask(
copter, new LatLng((double)singleCopterInfoObj.latOffset,
(double)singleCopterInfoObj.lngOffset), (float)singleCopterInfoObj.targetAlt);
(double)singleCopterInfoObj.lngOffset), (float)singleCopterInfoObj.targetAlt, (bool)singleCopterInfoObj.isLandWaypoint);
var jsonArray = singleCopterInfoObj.ledInfos as Newtonsoft.Json.Linq.JArray;
newSingleCopterInfo.LEDInfos = jsonArray.ToObject<ObservableCollection<LEDInfo>>();
ObservableCollection<LEDInfo> ledList = jsonArray.ToObject<ObservableCollection<LEDInfo>>();
foreach(LEDInfo info in ledList)
{
newSingleCopterInfo.AddLEDInfo(info);
}
}
else
{
@ -507,6 +510,44 @@ namespace Plane.FormationCreator.Formation
SelectedTaskIndex = Tasks.Count - 1;
}
private void RestoreTakeOffTask(int takeOffTime, dynamic singleCopterInfos)
{
var copters = _copterManager.Copters;
if (copters == null || !copters.Any()) return;
AppEx.Current.AppMode = AppMode.ModifyingTask;
var lastTask = Tasks.LastOrDefault();
FlightTask takeOffTask = Tasks[0];
takeOffTask.TakeOffTime = takeOffTime;
for (int i = 0; i < copters.Count; i++)
{
var singleCopterInfoObj = singleCopterInfos[i];
takeOffTask.SingleCopterInfos[i].TakeOffWaitTime = (int)singleCopterInfoObj.waitTime;
}
}
private void RestoreLandTask(dynamic singleCopterInfos)
{
var copters = _copterManager.Copters;
if (copters == null || !copters.Any()) return;
AppEx.Current.AppMode = AppMode.ModifyingTask;
var lastTask = Tasks.LastOrDefault();
var LandTask = new FlightTask(FlightTaskType.Land);
for (int i = 0; i < copters.Count; i++)
{
var copter = copters[i];
FlightTaskSingleCopterInfo newSingleCopterInfo;
var singleCopterInfoObj = singleCopterInfos[i];
newSingleCopterInfo = FlightTaskSingleCopterInfo.CreateForLandTask(copter, (int)singleCopterInfoObj.waitTime);
LandTask.SingleCopterInfos.Add(newSingleCopterInfo);
}
Tasks.Add(LandTask);
TaskAdded?.Invoke(this, new FlightTaskAddedEventArgs { LastTask = lastTask, AddedTask = LandTask });
SelectedTask = LandTask;
SelectedTaskIndex = Tasks.Count - 1;
}
// added by ZJF
private void RestoreLoiterTimeTask(float LoiteTimeTmp, bool flashCheck, float flashCheckPeriod,
bool oneByOneCheck, float oneByOneCheckPeriod, string flashNameArray, string flashIndexArray,
@ -647,7 +688,15 @@ namespace Plane.FormationCreator.Formation
case FlightTaskType.TakeOff:
return new {
type = type,
takeoffnumber = TakeOffNumAttr
takeoffnumber = TakeOffNumAttr,
takeoffTime = task.TakeOffTime,
singleCopterInfos = task.SingleCopterInfos.Select(info =>
{
return new
{
waitTime = info.TakeOffWaitTime
};
})
};
case FlightTaskType.FlyTo:
return new
@ -665,7 +714,8 @@ namespace Plane.FormationCreator.Formation
lngOffset = offset.Lng,
targetAlt = info.TargetAlt,
//showLED = info.FlytoShowLED,
ledInfos = info.LEDInfos
ledInfos = info.LEDInfos,
isLandWaypoint = info.IsLandWaypoint
};
})
};
@ -757,6 +807,22 @@ namespace Plane.FormationCreator.Formation
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.");
}
@ -817,8 +883,10 @@ namespace Plane.FormationCreator.Formation
{
dynamic tasks = JsonConvert.DeserializeObject(tasksText);
var copters = _copterManager.Copters;
if (Tasks.Count == 0)
AddTakeOffTask(copters);
foreach (var task in tasks)
{
switch ((FlightTaskType)task.type)
@ -826,6 +894,7 @@ namespace Plane.FormationCreator.Formation
case FlightTaskType.TakeOff:
// AddTakeOffTask(copters); // added by ZJF
TakeOffNumAttr = task.takeoffnumber;
RestoreTakeOffTask((int)task.takeoffTime, task.singleCopterInfos);
break;
case FlightTaskType.FlyTo:
RestoreFlyToTask((bool)task.staggerRoutes, (int)task.flytoTime, (int)task.loiterTime, task.singleCopterInfos);
@ -848,6 +917,9 @@ namespace Plane.FormationCreator.Formation
case FlightTaskType.ReturnToLand:
RestoreReturnToLandTask(copters, (int)task.retnumber, (int)task.rtlalt);
break;
case FlightTaskType.Land:
RestoreLandTask(task.singleCopterInfos);
break;
}
}
}
@ -1046,7 +1118,7 @@ namespace Plane.FormationCreator.Formation
// 在目前的起飞、降落逻辑,如果起飞或最后一个任务是返航降落,不要检查两架飞机距离过近. added by ZJF
bool RTLFlag = ( CurrentRunningTaskIndex == Tasks.Count()-1 ) && ( CurrentRunningTask.TaskType == FlightTaskType.ReturnToLand );
// bool RTLFlag = false;
if ( (CurrentRunningTaskIndex != 0) && !RTLFlag)
//if ( (CurrentRunningTaskIndex != 0) && !RTLFlag)
{
foreach (var copter in _copterManager.Copters)

View File

@ -6,6 +6,8 @@ using System.Collections.Generic;
using System.Linq;
using System.Text;
using System.Threading.Tasks;
using System.Windows.Input;
using GalaSoft.MvvmLight.Command;
namespace Plane.FormationCreator.Formation
{
@ -44,6 +46,82 @@ namespace Plane.FormationCreator.Formation
private float? _TargetAlt;
public float TargetAlt { get { return _TargetAlt ?? Copter.Altitude; } set { Set(nameof(TargetAlt), ref _TargetAlt, value); } }
//应用当前航点高度到所选
private ICommand _SetAllCopterAltCommand;
public ICommand SetAllCopterAltCommand
{
get
{
return _SetAllCopterAltCommand ?? (_SetAllCopterAltCommand = new RelayCommand<double>(async =>
{
foreach (FlightTaskSingleCopterInfo info in _flightTaskManager.SelectedTask.SingleCopterInfos)
{
if (_copterManager.AcceptingControlCopters.Contains(info.Copter))
{
info.TargetAlt = TargetAlt;
}
}
}));
}
}
//应用当前是否是降落点到所选
private ICommand _SetIsLandCommand;
public ICommand SetIsLandCommand
{
get
{
return _SetIsLandCommand ?? (_SetIsLandCommand = new RelayCommand<double>(async =>
{
foreach (FlightTaskSingleCopterInfo info in _flightTaskManager.SelectedTask.SingleCopterInfos)
{
if (_copterManager.AcceptingControlCopters.Contains(info.Copter))
{
info.IsLandWaypoint = IsLandWaypoint;
}
}
}));
}
}
private ICommand _SetSelLandWaitTimeCommand;
public ICommand SetSelLandWaitTimeCommand
{
get
{
return _SetSelLandWaitTimeCommand ?? (_SetSelLandWaitTimeCommand = new RelayCommand<double>(async =>
{
foreach (FlightTaskSingleCopterInfo info in _flightTaskManager.SelectedTask.SingleCopterInfos)
{
if (_copterManager.AcceptingControlCopters.Contains(info.Copter))
{
info.LandWaitTime = LandWaitTime;
}
}
}));
}
}
private ICommand _SetSelTakeOffWaitTimeCommand;
public ICommand SetSelTakeOffWaitCommand
{
get
{
return _SetSelTakeOffWaitTimeCommand ?? (_SetSelTakeOffWaitTimeCommand = new RelayCommand<double>(async =>
{
foreach (FlightTaskSingleCopterInfo info in _flightTaskManager.SelectedTask.SingleCopterInfos)
{
if (_copterManager.AcceptingControlCopters.Contains(info.Copter))
{
info.TakeOffWaitTime = TakeOffWaitTime;
}
}
}));
}
}
public LatLng LatLngOffset
{
get

View File

@ -23,12 +23,13 @@ namespace Plane.FormationCreator.Formation
return info;
}
public static FlightTaskSingleCopterInfo CreateForFlyToTask(ICopter copter, LatLng latLngOffset, float targetAlt)
public static FlightTaskSingleCopterInfo CreateForFlyToTask(ICopter copter, LatLng latLngOffset, float targetAlt, bool isLandWaypoint)
{
var info = new FlightTaskSingleCopterInfo(copter)
{
LatLngOffset = latLngOffset,
TargetAlt = targetAlt
TargetAlt = targetAlt,
IsLandWaypoint = isLandWaypoint
};
return info;
}
@ -40,6 +41,14 @@ namespace Plane.FormationCreator.Formation
set { Set(nameof(FlytoShowLED), ref _FlytoShowLED, value); }
}
private bool _IsLandWaypoint = false;
//降落前的航点 只有高度有效,自动飞往起飞点写入航点的经纬为1000 飞控自动认为1000是飞往起点 by张旭东
public bool IsLandWaypoint
{
get { return _IsLandWaypoint; }
set { Set(nameof(IsLandWaypoint), ref _IsLandWaypoint, value); }
}
/*
* //同一个任务每一架飞机的FlytoTime和LoiterTime保持统一,已将FlytoTime和LoiterTime改到FlightTask.cs中
@ -58,7 +67,7 @@ namespace Plane.FormationCreator.Formation
}
*/
}
}

View File

@ -17,5 +17,23 @@ namespace Plane.FormationCreator.Formation
};
return info;
}
public static FlightTaskSingleCopterInfo CreateForTakeOffTask(ICopter copter, int waitTime)
{
var info = new FlightTaskSingleCopterInfo(copter)
{
TakeOffWaitTime = waitTime
};
return info;
}
//起飞等待时间
private int _TakeOffWaitTime = 1;
public int TakeOffWaitTime
{
get { return _TakeOffWaitTime; }
set { Set(nameof(TakeOffWaitTime), ref _TakeOffWaitTime, value); }
}
}
}

View File

@ -20,7 +20,21 @@ namespace Plane.FormationCreator.Formation
set { Set(nameof(StaggerRoutes), ref _StaggerRoutes, value); }
}
//同一个任务每一架飞机的FlytoTime和LoiterTime保持统一
private int _FlytoTime = 10;
public int FlytoTime
{
get { return _FlytoTime; }
set { Set(nameof(FlytoTime), ref _FlytoTime, value); }
}
private int _LoiterTime = 10;
public int LoiterTime
{
get { return _LoiterTime; }
set { Set(nameof(LoiterTime), ref _LoiterTime, value); }
}
private bool _VerticalLift = false;
@ -38,6 +52,7 @@ namespace Plane.FormationCreator.Formation
{
currentCopterInfos[i].TargetLat = previousCopterInfos[i].TargetLat;
currentCopterInfos[i].TargetLng = previousCopterInfos[i].TargetLng;
currentCopterInfos[i].TargetAlt = previousCopterInfos[i].TargetAlt;
}
}
@ -94,6 +109,13 @@ namespace Plane.FormationCreator.Formation
private async Task FlyToTaskFlySingleCopterAsync(FlightTaskSingleCopterInfo info)
{
DateTime dtNow = DateTime.Now;
DateTime dtLastTime = DateTime.Now;
TimeSpan ts = dtNow - dtLastTime;
FlightTask task = _flightTaskManager.CurrentRunningTask;
int flyToTime = task.FlytoTime;
int loiterTime = task.LoiterTime;
int taskIndex = _flightTaskManager.CurrentRunningTaskIndex;
int copterIndex = SingleCopterInfos.IndexOf(info);
@ -109,9 +131,7 @@ namespace Plane.FormationCreator.Formation
if (info.Copter.State != Plane.Copters.CopterState.CommandMode)
await info.Copter.GuidAsync();
DateTime dtNow = DateTime.Now;
DateTime dtLastTime = DateTime.Now;
TimeSpan ts = dtNow - dtLastTime;
/*
@ -125,28 +145,32 @@ namespace Plane.FormationCreator.Formation
await info.Copter.FlyToAsync(info.TargetLat, info.TargetLng, info.TargetAlt);
await Task.Delay(10).ConfigureAwait(false);
dtNow = DateTime.Now;
ts = dtNow - dtLastTime;
while (!info.Copter.ArrivedTarget(info.TargetLat, info.TargetLng, info.TargetAlt))
int sendFlyToTimes = 0;
//while (!info.Copter.ArrivedTarget(info.TargetLat, info.TargetLng, info.TargetAlt)) //按航点飞 所有Copter到达目标点开始飞下个航点
while (ts.TotalMilliseconds < (flyToTime + loiterTime) * 1000) //按时间轴飞:当前任务时间到达后自动飞往下个航点
{
if (_flightTaskManager.IsPaused == true)
{
await info.Copter.HoverAsync();
return;
}
await Task.Delay(250).ConfigureAwait(false); //判断是否到达位置10hz
await Task.Delay(100).ConfigureAwait(false); //判断是否到达位置10hz
dtNow = DateTime.Now;
ts = dtNow - dtLastTime;
if (ts.TotalMilliseconds > 500) // 每500ms发送一遍指点坐标
if (ts.TotalMilliseconds / 500 > sendFlyToTimes) // 每500ms发送一遍指点坐标
{
sendFlyToTimes++;
for (int i = 0; i < 2; i++)
{
await info.Copter.FlyToAsync(info.TargetLat, info.TargetLng, info.TargetAlt);
await Task.Delay(10).ConfigureAwait(false);
}
dtLastTime = dtNow;
//dtLastTime = dtNow;
}
// 当该飞机被标记时,悬停并跳过飞行任务
if ((bool)_copterManager.CopterStatus[copterIndex])
@ -154,6 +178,8 @@ namespace Plane.FormationCreator.Formation
await info.Copter.HoverAsync();
return;
}
dtNow = DateTime.Now;
ts = dtNow - dtLastTime;
}
// await info.Copter.HoverAsync();
if (taskIndex == _flightTaskManager.Tasks.Count() - 1)

View File

@ -23,6 +23,14 @@ namespace Plane.FormationCreator.Formation
}
}
//起飞到第一个航点高度的飞行时间
private int _TakeOffTime = 10;
public int TakeOffTime
{
get { return _TakeOffTime; }
set { Set(nameof(TakeOffTime), ref _TakeOffTime, value); }
}
//一架架起飞--未使用
public async Task RunTakeOffTaskAsync()
{
@ -62,11 +70,15 @@ namespace Plane.FormationCreator.Formation
}
// 几架飞机同时起飞参数为takeOffCount-----------------使用中
//起飞分三个阶段1阶段分批起飞到15米(目前15米高度是飞控起飞航点决定)上一批起飞超过5米下一批开始起飞
//等待全部起飞完成后执行第二阶段,
//2阶段等待高度超过9米(可能已到达15米)然后平飞到第一个航点位置,高度为15米的位置
//3阶段垂直上升到第一个航点指定高度
//起飞分三个阶段:
//1阶段分批起飞到15米(目前15米高度是飞控起飞航点决定)上一批起飞超过5米下一批开始起飞
// 等待全部起飞完成后执行第二阶段,
//2阶段等待高度超过9米(可能已到达15米)然后平飞到第一个航点位置,高度为15米的位置
//3阶段垂直上升到第一个航点指定高度
//
//修改方案:针对高度
//1.上升到起飞高度(目前没有地面站设置高度,高度在飞控中)
//2.直接飞往第一个航点的高度
public async Task MutilRunTakeOffTaskAsync()
{
int TaskCount = _flightTaskManager.Tasks.Count();
@ -227,10 +239,10 @@ namespace Plane.FormationCreator.Formation
//执行第二第三阶段起飞任务-------------使用中
private async Task TakeOffSecondTaskAsync(FlightTaskSingleCopterInfo info)
{
float takeOffAlt = 20;// 15; 起飞高度到20米
int copterIndex = SingleCopterInfos.IndexOf(info);
var copterNextTask = _flightTaskManager.Tasks[1].SingleCopterInfos[copterIndex];
float takeOffAlt = copterNextTask.TargetAlt;// 15; 起飞高度到下个任务的高度
// 当该飞机被标记时,悬停并跳过飞行任务
if ((bool)_copterManager.CopterStatus[copterIndex])
{
@ -266,6 +278,8 @@ namespace Plane.FormationCreator.Formation
DateTime dtLastTime = DateTime.Now;
TimeSpan ts = dtNow - dtLastTime;
#region
// 第二阶段超过9米开始水平飞行
if (info.takeOffStage == 1)
{
@ -276,11 +290,11 @@ namespace Plane.FormationCreator.Formation
//异步执行飞到第一个航点高度固定为15米的任务
for (int j = 0; j < 3; j++)
{
await info.Copter.FlyToAsync(copterNextTask.TargetLat, copterNextTask.TargetLng, takeOffAlt);
await info.Copter.FlyToAsync(info.TargetLat, info.TargetLng, takeOffAlt);
await Task.Delay(10).ConfigureAwait(false);
}
//直到到达第一个航点并高度15米
while (!info.Copter.ArrivedTarget(copterNextTask.TargetLat, copterNextTask.TargetLng, takeOffAlt))
while (!info.Copter.ArrivedTarget(info.TargetLat, info.TargetLng, takeOffAlt))
{
if (_flightTaskManager.IsPaused == true)
{
@ -296,7 +310,7 @@ namespace Plane.FormationCreator.Formation
{
for (int j = 0; j < 2; j++)
{
await info.Copter.FlyToAsync(copterNextTask.TargetLat, copterNextTask.TargetLng, takeOffAlt);
await info.Copter.FlyToAsync(info.TargetLat, info.TargetLng, takeOffAlt);
await Task.Delay(10).ConfigureAwait(false);
}
dtLastTime = dtNow;
@ -313,10 +327,15 @@ namespace Plane.FormationCreator.Formation
info.takeOffStage++; //当前变为2
}
}
dtNow = DateTime.Now;
dtLastTime = DateTime.Now;
ts = dtNow - dtLastTime;
#endregion
info.takeOffStage++;
// 第三阶段从第一个航点位置15米垂直飞行
if (info.takeOffStage == 2)
{

View File

@ -47,6 +47,9 @@
Command="{Binding SwitchAppModeCommand}"
CommandParameter="{x:Static m:AppMode.ControllingCopters}"
Visibility="{Binding Source={x:Static local:AppEx.Current}, Path=AppMode, Converter={StaticResource AppModeToVisibilityConverter}, ConverterParameter=SwitchToControllingCoptersModeButton}" />-->
<Button Name="btnShowLog"
Content="日志"
Click="btnShowLog_Click" />
<Button Name="btnGoHome"
Content="回家"
Click="btnGoHome_Click" />
@ -56,6 +59,39 @@
<Button Name="btnConnect"
Content="连接"
Click="btnConnect_Click" />
<Menu Name="menuTask" VerticalAlignment="Center" >
<MenuItem Header="导入导出" Foreground="#969696">
<Grid>
<Grid.RowDefinitions>
<RowDefinition/>
<RowDefinition/>
</Grid.RowDefinitions>
<Grid.ColumnDefinitions>
<ColumnDefinition/>
<ColumnDefinition/>
</Grid.ColumnDefinitions>
<Button BorderThickness="1" Content="导出任务" Margin="0,8,0,8"
Command="{Binding ExportTasksCommand}"/>
<Button BorderThickness="1" BorderBrush="#FFFFFF" Content="导入任务" Margin="0,8,0,8" Grid.Row="1"
Command="{Binding ImportTasksCommand}"></Button>
<StackPanel VerticalAlignment="Center" Margin="0,8,0,8" Grid.Row="1" Grid.Column="1" Orientation="Horizontal">
<TextBlock Foreground="#969696" VerticalAlignment="Center" Text="起始步骤:"/>
<TextBox VerticalAlignment="Bottom" Width="40"
Text="{Binding txtStarindex, UpdateSourceTrigger=PropertyChanged}"/>
<TextBlock Foreground="#969696" VerticalAlignment="Center" Text="截止:"/>
<TextBox VerticalAlignment="Bottom" Width="40"
Text="{Binding txtendindex, UpdateSourceTrigger=PropertyChanged}"/>
</StackPanel>
</Grid>
</MenuItem>
</Menu>
</c:WindowCommands>
</c:MetroWindow.RightWindowCommands>
@ -135,7 +171,7 @@
Background="{StaticResource HighlightBrush}">
<StackPanel Orientation="Horizontal">
<TextBlock Margin="4"
Text="{Binding Message}" />
Text="{Binding Message}"/>
<TextBlock Margin="4"
Text="{Binding CopterListViewModel.SelectedCopter.StatusText}" />
</StackPanel>

View File

@ -417,5 +417,14 @@ namespace Plane.FormationCreator
}
}
}
private void btnShowLog_Click(object sender, RoutedEventArgs e)
{
MainViewModel vm = DataContext as MainViewModel;
LogWindow logWindows = new LogWindow(vm.Messages);
logWindows.Show();
}
}
}

View File

@ -111,6 +111,7 @@
<Compile Include="Converters\HeartbeatCountToBrushConverter.cs" />
<Compile Include="Formation\AppMode.cs" />
<Compile Include="Formation\Copter.cs" />
<Compile Include="Formation\FlightTaskSingleCopterInfo_Land.cs" />
<Compile Include="Formation\FlightTaskSingleCopterInfo_LED.cs" />
<Compile Include="Formation\FlightTaskSingleCopterInfo_LoiterTime.cs" />
<Compile Include="Formation\FlightTaskSingleCopterInfo_ReturnToLand.cs" />
@ -125,6 +126,7 @@
<Compile Include="Formation\FlightTaskStatus.cs" />
<Compile Include="Formation\FlightTask_FlyTo.cs" />
<Compile Include="Formation\FlightTaskSingleCopterInfo_FlyTo.cs" />
<Compile Include="Formation\FlightTask_Land.cs" />
<Compile Include="Formation\FlightTask_LoiterTime.cs" />
<Compile Include="Formation\FlightTask_ReturnToLand.cs" />
<Compile Include="Formation\FlightTask_SimpleCircle.cs" />
@ -167,6 +169,9 @@
<Compile Include="Views\ConnectWindow.xaml.cs">
<DependentUpon>ConnectWindow.xaml</DependentUpon>
</Compile>
<Compile Include="Views\LogWindow.xaml.cs">
<DependentUpon>LogWindow.xaml</DependentUpon>
</Compile>
<Compile Include="Views\MapView.xaml.cs">
<DependentUpon>MapView.xaml</DependentUpon>
</Compile>
@ -221,6 +226,11 @@
<Generator>MSBuild:Compile</Generator>
<SubType>Designer</SubType>
</Page>
<Page Include="Properties\DesignTimeResources.xaml">
<SubType>Designer</SubType>
<Generator>MSBuild:Compile</Generator>
<ContainsDesignTimeResources>true</ContainsDesignTimeResources>
</Page>
<Page Include="Styles.xaml">
<SubType>Designer</SubType>
<Generator>MSBuild:Compile</Generator>
@ -269,6 +279,10 @@
<SubType>Designer</SubType>
<Generator>MSBuild:Compile</Generator>
</Page>
<Page Include="Views\LogWindow.xaml">
<SubType>Designer</SubType>
<Generator>MSBuild:Compile</Generator>
</Page>
<Page Include="Views\MapView.xaml">
<SubType>Designer</SubType>
<Generator>MSBuild:Compile</Generator>

View File

@ -20,6 +20,10 @@ using Plane.Copters;
using Plane.Windows.Messages;
using Plane.FormationCreator.Properties;
using System.IO;
using Plane.CommunicationManagement;
using Plane.Protocols;
using Microsoft.Practices.ServiceLocation;
using System.Windows.Media;
namespace Plane.FormationCreator.ViewModels
{
@ -69,88 +73,230 @@ namespace Plane.FormationCreator.ViewModels
{
return _ConnectCommand ?? (_ConnectCommand = new RelayCommand<string>(async connectionType =>
{
if (!_ipListRegex.IsMatch(IPs))
await ConnectAsync();
}
));
}
}
private ICommand _SendCommand;
public ICommand SendCommand
{
get
{
return _SendCommand ?? (_SendCommand = new RelayCommand(async () =>
{
await SendCommandAsync();
}
));
}
}
// private ICommand _WriteCommand;
// public ICommand WriteCommand
// {
// get
// {
// return _WriteCommand ?? (_WriteCommand = new RelayCommand(async () =>
// {
// await WriteCommandAsync();
// }
// ));
// }
// }
private ICommand _WriteIdCommand;
public ICommand WriteIdCommand
{
get
{
return _WriteIdCommand ?? (_WriteIdCommand = new RelayCommand(async () =>
{
await WriteIdCommandAsync();
}
));
}
}
private ICommand _CommWriteMissionCommand;
public ICommand CommWriteMissionCommand
{
get
{
return _CommWriteMissionCommand ?? (_CommWriteMissionCommand = new RelayCommand(async () =>
{
var _flightTaskManager = ServiceLocator.Current.GetInstance<FlightTaskManager>();
if (_flightTaskManager.OriginLat == 0 && _flightTaskManager.OriginLng == 0)
{
Alert.Show($"您输入的 IP 格式不对!形如{Environment.NewLine}192.168.1.10{Environment.NewLine}192.168.1.11");
Alert.Show("作为参照的原点未设置,无法写入相对位置!", "提示");
return;
}
IsProcessing = true;
int coptercount = _copterManager.Copters.Count;
int taskcount = _flightTaskManager.Tasks.Count;
// bool havewritefault = true;
if (taskcount < 2) return;
var connectionStatusDict =
IPs.Split(new string[] { Environment.NewLine }, StringSplitOptions.RemoveEmptyEntries)
.Where(ip => _copterManager.Copters.All(c => c.Id != ip))
.OrderBy(ip => ip)
.Distinct()
.ToDictionary(ip => ip, ip => (bool?)null);
var timeIsOut = false;
var uiThreadContext = SynchronizationContext.Current;
new Action(async () =>
for (int i = 0; i < coptercount; i++)
{
foreach (var ip in connectionStatusDict.Keys.ToList())
///写航线开始
//var missions = new IMission[taskcount]; //不要起飞任务但增加一个起飞后低空航点,见起飞任务,再增加一个降落低空航点,见降落部分
var missions = new List<IMission>();
int missindex = 0;
ICopter copter = _copterManager.Copters[i];
if (copter is PLCopter)
{
var Connection =
connectionType == "SerialPort"
? new SerialPortConnection("COM10") as IConnection
: connectionType == "UDP"
? new UdpConnection(ip, PORT) as IConnection
: new TcpConnection(ip, PORT);
var c = new Copter(Connection, uiThreadContext)
//var c = new Copter(new SerialPortConnection("COM3"), uiThreadContext)
for (int j = 0; j < _flightTaskManager.Tasks.Count; j++)
{
Id = ip,
Name = ip.Substring(ip.LastIndexOf('.') + 1)
};
try
{
await c.ConnectAsync().ConfigureAwait(false);
if (!timeIsOut)
switch (_flightTaskManager.Tasks[j].TaskType)
{
connectionStatusDict[ip] = true;
App.Current.Dispatcher.Invoke(() =>
{
_copterManager.Copters.Add(c);
});
//await c.GetCopterDataAsync();
case FlightTaskType.TakeOff:
//计算起飞需要的时间,5秒是上升加速和最后稳定时间
int takeofftime = (int)(_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetAlt / 2.5 + 5);
missions.Add(Mission.CreateTakeoffMission(
1,//1,
5,//takeofftime,
_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetLat - _flightTaskManager.OriginLat,
_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetLng - _flightTaskManager.OriginLng,
_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetAlt)
);
//要起飞任务
break;
case FlightTaskType.FlyTo:
foreach (LEDInfo ledInfo in _flightTaskManager.Tasks[j].SingleCopterInfos[i].LEDInfos)
{
Color color = (Color)ColorConverter.ConvertFromString("#" + ledInfo.LEDRGB);
IMission LEDMission = Mission.CreateLEDControlMission(
(int)(ledInfo.Delay * 10),
ledInfo.LEDMode,
ledInfo.LEDRate,
0, //ledInfo.LEDTimes,
color.R,
color.G,
color.B
);
missions.Add(LEDMission);
}
missions.Add(Mission.CreateWaypointMission(
_flightTaskManager.Tasks[j].LoiterTime,
_flightTaskManager.Tasks[j].FlytoTime,
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLat - _flightTaskManager.OriginLat,
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLng - _flightTaskManager.OriginLng,
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetAlt)
);
break;
case FlightTaskType.Loiter:
break;
case FlightTaskType.ReturnToLand:
missions.Add(Mission.CreateReturnToLaunchMission());
break;
case FlightTaskType.Land:
missions.Add(Mission.CreateLandMission(5));
break;
default:
break;
}
}
catch (SocketException)
{
connectionStatusDict[ip] = false;
}
catch (IOException)
{ // A device attached to the system is not functioning.
connectionStatusDict[ip] = false;
}
await WriteCommandAsync(copter, missions);
}
}).Invoke();
for (int waitedTime = 0, timeStep = 500; waitedTime < 2000; waitedTime += timeStep)
{
await Task.Delay(timeStep).ConfigureAwait(false);
if (connectionStatusDict.All(item => item.Value == true))
//_copterManager.Copters[i].WriteMissionListAsync(missions);
/*
if (!result)
{
break;
Alert.Show($"飞机:{_copterManager.Copters[i].Name} 任务写入失败!");
return;
}
*/
}
timeIsOut = true;
IsProcessing = false;
var ipsCanNotConnect = string.Join(Environment.NewLine, connectionStatusDict.Where(item => !(item.Value ?? false)).Select(item => item.Key));
if (!string.IsNullOrEmpty(ipsCanNotConnect))
{
var message = $"无法连接以下 IP{Environment.NewLine}{ipsCanNotConnect}";
App.Current.Dispatcher.Invoke(() =>
{
Alert.Show(message);
});
}
else
{
CloseWindow();
}
Alert.Show($"所有任务写入成功!");
}));
}
}
private async Task WriteIdCommandAsync()
{
await commModule.GeneratePacketAsync(3, (byte)Protocols.MavComm.COMMANDTYPE4);
}
private async Task SendCommandAsync()
{
Protocols.MavComm.comm_set_mav_count mavCount = new Protocols.MavComm.comm_set_mav_count();
mavCount.mav_count = 200;
await commModule.GeneratePacketAsync(0, (byte)Protocols.MavComm.COMM_SET_MAV_COUNT, mavCount);
}
private async Task WriteCommandAsync(ICopter copter, List<IMission> missions)
{
List<MAVLink.mavlink_mission_item_t> mission_list = new List<MAVLink.mavlink_mission_item_t>();
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();
PLCopter plCopter = (PLCopter)copter;
req.target_system = plCopter._internalCopter.sysid;
req.target_component = plCopter._internalCopter.compid;
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);
}
await commModule.GeneratePacketAsyncNew(short.Parse(copter.Name), (byte)Protocols.MavComm.COMM_WRITE_MISSION, mission_list.ToArray());
}
CommModule commModule = new CommModule();
private async Task ConnectAsync()
{
await commModule.ConnectAsync();
}
private Action _closeWindowCallback;
public void SetCloseWindowAction(Action closeWindowAction)
{

View File

@ -63,6 +63,117 @@ namespace Plane.FormationCreator.ViewModels
set { Set(nameof(RTKbtntxt), ref _RTKbtntxt, value); }
}
private ICommand _LockAllCommand;
public ICommand LockAllCommand
{
get
{
return _LockAllCommand ?? (_LockAllCommand = new RelayCommand(async () =>
{
// await Task.WhenAll(_copterManager.AcceptingControlCopters.Select(copter => copter.UnlockAsync()));
if (Alert.Show("您确定要上锁吗?所有飞行器将无视转速,立即强制停止运转!!!!", "警告", MessageBoxButton.OKCancel, MessageBoxImage.Warning)
== MessageBoxResult.OK)
{
if (Alert.Show("再次确认上锁?请确认所有飞行器都在地面,否则将自由落体", "再次警告", MessageBoxButton.OKCancel, MessageBoxImage.Warning)
== MessageBoxResult.OK)
{
await Task.WhenAll(_copterManager.Copters.Select(async c =>
{
await c.LockAsync();
}));
}
}
}));
}
}
private ICommand _DetectionVoltage;
public ICommand DetectionVoltage
{
get
{
return _DetectionVoltage ?? (_DetectionVoltage = new RelayCommand(async () =>
{
Dictionary<string, float> dic_voltage = new Dictionary<string, float>();
await Task.WhenAll(_copterManager.Copters.Select(async c =>
{
float voltageSum = 0.0f;
for (int i = 0; i < 5; i++)
{
voltageSum += c.Voltage;
await Task.Delay(1000).ConfigureAwait(false);
}
float voltageAverage = voltageSum / 5;
dic_voltage.Add(c.Name, voltageAverage);
}));
dic_voltage = dic_voltage.OrderByDescending(o => o.Value).ToDictionary(p => p.Key, o => o.Value);
Message.Show("--------------开始检测电压--------------");
foreach (KeyValuePair<string, float> kv in dic_voltage)
{
Message.Show(string.Format("{0} --> 5秒平均电压{1}", kv.Key, kv.Value));
await Task.Delay(5).ConfigureAwait(false);
}
Message.Show("--------------检测电压完成--------------");
}));
}
}
private ICommand _AllLandCommand;
public ICommand AllLandCommand
{
get
{
return _AllLandCommand ?? (_AllLandCommand = new RelayCommand(async () =>
{
await Task.WhenAll(_copterManager.Copters.Select(async c =>
{
await c.LandAsync();
}));
}));
}
}
private ICommand _MotorTestCommand;
public ICommand MotorTestCommand
{
get
{
return _MotorTestCommand ?? (_MotorTestCommand = new RelayCommand(async () =>
{
await Task.WhenAll(_copterManager.Copters.Select(async c =>
{
for (int i = 1; i <= 4; i++)
{
await c.MotorTestAsync(i).ConfigureAwait(false);
await Task.Delay(10);
}
})).ConfigureAwait(false);
}));
}
}
private ICommand _GuidAsyncCommand;
public ICommand GuidAsyncCommand
{
get
{
return _GuidAsyncCommand ?? (_GuidAsyncCommand = new RelayCommand(async () =>
{
await Task.WhenAll(_copterManager.AcceptingControlCopters.Select(async c =>
{
await c.GuidAsync();
await Task.Delay(100).ConfigureAwait(false);
await c.TakeOffAsync(1);
}));
}));
}
}
private ICommand _UnlockAllCommand;
public ICommand UnlockAllCommand
@ -149,7 +260,7 @@ namespace Plane.FormationCreator.ViewModels
{
return _LockCommand ?? (_LockCommand = new RelayCommand(async () =>
{
if (Alert.Show("您确定要上锁吗?飞行器将立即停止运转!", "警告", MessageBoxButton.OKCancel, MessageBoxImage.Warning)
if (Alert.Show("您确定要上锁吗?飞行器将无视转速,立即强制停止运转", "警告", MessageBoxButton.OKCancel, MessageBoxImage.Warning)
== MessageBoxResult.OK)
{
await Task.WhenAll(_copterManager.AcceptingControlCopters.Select(copter => copter.LockAsync()));
@ -503,6 +614,9 @@ namespace Plane.FormationCreator.ViewModels
}
}
private ICommand _ConnectCommand;
public ICommand ConnectCommand
{
@ -611,19 +725,20 @@ namespace Plane.FormationCreator.ViewModels
int utchour = DateTime.UtcNow.AddSeconds(5).Hour;
int utcminute = DateTime.UtcNow.AddSeconds(5).Minute;
int utcsecond = DateTime.UtcNow.AddSeconds(5).Second;
foreach (var vcopter in _copterManager.Copters)
//循环3次 发送起飞命令 避免通信问题
for (int i = 0; i < 3; i++)
{
await vcopter.MissionStartAsync(utchour,
utcminute,
utcsecond,
_flightTaskManager.OriginLng,
_flightTaskManager.OriginLat
//110.23456,
//40.23432
);
foreach (var vcopter in _copterManager.Copters)
{
await vcopter.MissionStartAsync(utchour,
utcminute,
utcsecond,
_flightTaskManager.OriginLng,
_flightTaskManager.OriginLat
);
}
await Task.Delay(10).ConfigureAwait(false);
}
}));
}
@ -651,11 +766,8 @@ namespace Plane.FormationCreator.ViewModels
get
{
return _WriteMissionCommand ?? (_WriteMissionCommand = new RelayCommand(async () =>
{
ViewModels.ModifyTaskViewModel _taskmodimodel = ServiceLocator.Current.GetInstance<ViewModels.ModifyTaskViewModel>();
var _flightTaskManager = _taskmodimodel.FlightTaskManager;
{
var _flightTaskManager = ServiceLocator.Current.GetInstance<FlightTaskManager>();
if (_flightTaskManager.OriginLat == 0 && _flightTaskManager.OriginLng == 0)
{
Alert.Show("作为参照的原点未设置,无法写入相对位置!", "提示");
@ -684,9 +796,11 @@ namespace Plane.FormationCreator.ViewModels
//计算起飞需要的时间,5秒是上升加速和最后稳定时间
int takeofftime = (int)(_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetAlt / 2.5 + 5);
missions.AddRange(CreateLEDMissions(_flightTaskManager.Tasks[j].SingleCopterInfos[i].LEDInfos));
missions.Add(Mission.CreateTakeoffMission(
1,//1,
5,//takeofftime,
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TakeOffWaitTime,
_flightTaskManager.Tasks[j].TakeOffTime,
_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetLat - _flightTaskManager.OriginLat,
_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetLng - _flightTaskManager.OriginLng,
_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetAlt)
@ -697,30 +811,22 @@ namespace Plane.FormationCreator.ViewModels
break;
case FlightTaskType.FlyTo:
missions.AddRange(CreateLEDMissions(_flightTaskManager.Tasks[j].SingleCopterInfos[i].LEDInfos));
foreach (LEDInfo ledInfo in _flightTaskManager.Tasks[j].SingleCopterInfos[i].LEDInfos)
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)
{
Color color = (Color)ColorConverter.ConvertFromString("#" + ledInfo.LEDRGB);
IMission LEDMission = Mission.CreateLEDControlMission(
ledInfo.Delay * 10,
ledInfo.LEDMode,
ledInfo.LEDRate,
0, //ledInfo.LEDTimes,
color.R,
color.G,
color.B
);
missions.Add(LEDMission);
Lat = 90;
Lng = 180;
}
missions.Add(Mission.CreateWaypointMission(
//5,//_flightTaskManager.Tasks[j].SingleCopterInfos[i].LoiterTime,
//5,// _flightTaskManager.Tasks[j].SingleCopterInfos[i].FlytoTime,
_flightTaskManager.Tasks[j].LoiterTime,
_flightTaskManager.Tasks[j].FlytoTime,
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLat - _flightTaskManager.OriginLat,
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLng - _flightTaskManager.OriginLng,
//_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLat,
//_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLng,
Lat,
Lng,
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetAlt)
);
@ -736,7 +842,14 @@ namespace Plane.FormationCreator.ViewModels
//返航
missions.Add(Mission.CreateReturnToLaunchMission());
break;
case FlightTaskType.Land:
missions.AddRange(CreateLEDMissions(_flightTaskManager.Tasks[j].SingleCopterInfos[i].LEDInfos));
missions.Add(Mission.CreateLandMission(
_flightTaskManager.Tasks[j].SingleCopterInfos[i].LandWaitTime)
);
break;
default:
break;
@ -879,6 +992,26 @@ namespace Plane.FormationCreator.ViewModels
}
}
private List<IMission> CreateLEDMissions(IEnumerable<LEDInfo> LEDInfos)
{
List<IMission> missions = new List<IMission>();
foreach (LEDInfo ledInfo in LEDInfos)
{
Color color = (Color)ColorConverter.ConvertFromString("#" + ledInfo.LEDRGB);
IMission LEDMission = Mission.CreateLEDControlMission(
(int)(ledInfo.Delay * 10),
ledInfo.LEDMode,
ledInfo.LEDRate,
0, //ledInfo.LEDTimes,
color.R,
color.G,
color.B
);
missions.Add(LEDMission);
}
return missions;
}

View File

@ -9,6 +9,9 @@ using System.Linq;
using System.Text;
using System.Threading.Tasks;
using System.Windows.Input;
using Microsoft.Win32;
using Microsoft.Practices.ServiceLocation;
using System.IO;
namespace Plane.FormationCreator.ViewModels
{
@ -27,7 +30,7 @@ namespace Plane.FormationCreator.ViewModels
private CopterListViewModel _copterListViewModel;
public CopterListViewModel CopterListViewModel { get { return _copterListViewModel; } }
private FlightTaskManager _flightTaskManager = ServiceLocator.Current.GetInstance<FlightTaskManager>();
public AppEx AppEx { get; } = AppEx.Current;
private void AppEx_PropertyChanged(object sender, System.ComponentModel.PropertyChangedEventArgs e)
@ -53,7 +56,16 @@ namespace Plane.FormationCreator.ViewModels
public string Message
{
get { return _Message; }
set { Set(nameof(Message), ref _Message, value); }
set {
Set(nameof(Message), ref _Message, value);
_MessageList.Add(value);
}
}
private List<string> _MessageList = new List<string>();
public string Messages
{
get { return string.Join("\r\n", _MessageList.ToArray()); }
}
private ICommand _RestartListeningCommand;
@ -115,6 +127,89 @@ namespace Plane.FormationCreator.ViewModels
}
}
private ICommand _ExportTasksCommand;
public ICommand ExportTasksCommand
{
get
{
return _ExportTasksCommand ?? (_ExportTasksCommand = new RelayCommand(() =>
{
if (_flightTaskManager.OriginLat == 0 && _flightTaskManager.OriginLng == 0)
{
Alert.Show("作为参照的原点未设置,无法导出相对位置!", "提示");
return;
}
var exportedText = _flightTaskManager.ExportTasks();
var dialog = new SaveFileDialog
{
DefaultExt = "fcg",
Filter = "编队飞行任务 (*.fcg)|*.fcg"
};
if (dialog.ShowDialog() == true)
{
File.WriteAllText(dialog.FileName, exportedText);
}
}));
}
}
private int _txtStarindex = 0;
public int txtStarindex
{
get { return _txtStarindex; }
set { Set(nameof(txtStarindex), ref _txtStarindex, value); }
}
private int _txtendindex = 0;
public int txtendindex
{
get { return _txtendindex; }
set { Set(nameof(txtendindex), ref _txtendindex, value); }
}
private ICommand _ImportTasksCommand;
public ICommand ImportTasksCommand
{
get
{
return _ImportTasksCommand ?? (_ImportTasksCommand = new RelayCommand(() =>
{
if (_flightTaskManager.OriginLat == 0 && _flightTaskManager.OriginLng == 0)
{
Alert.Show("作为参照的原点未设置,无法导入相对位置!", "提示");
return;
}
var dialog = new OpenFileDialog
{
DefaultExt = "fcg",
Filter = "编队飞行任务 (*.fcg)|*.fcg"
};
if (dialog.ShowDialog() == true)
{
int _startindex = txtStarindex;
int _endindex = txtendindex;
var tasksText = File.ReadAllText(dialog.FileName);
if ((txtStarindex == 0) && (txtendindex == 0))
_flightTaskManager.ImportTasks(tasksText);
else
{
_endindex = txtendindex;
if (_startindex == 0)
_startindex = 1;
if (_endindex == 0)
_endindex = _startindex;
_flightTaskManager.ImportTasksindex(tasksText, _startindex, _endindex);
}
}
}));
}
}
private string GetSwitchVelocityModeButtonContent()
=> AppEx.Current.IsInFastMode ? "高速模式" : "低速模式";
}

View File

@ -490,6 +490,21 @@ namespace Plane.FormationCreator.ViewModels
}
}
private ICommand _BackTakeOffPointCommand;
public ICommand BackTakeOffPointCommand
{
get
{
return _BackTakeOffPointCommand ?? (_BackTakeOffPointCommand = new RelayCommand<int>(async =>
{
foreach (FlightTaskSingleCopterInfo info in _flightTaskManager.SelectedTask.SingleCopterInfos)
{
info.TargetLat = info.Copter.Latitude;
info.TargetLng = info.Copter.Longitude;
}
}));
}
}
private ICommand _LevelAlignmentCommand;
@ -1338,5 +1353,17 @@ public ICommand VerticlAlignmentCommand
}
}
//缩放
private ICommand _BackToPreviousTaskPoint;
public ICommand BackToPreviousTaskPoint
{
get
{
return _BackToPreviousTaskPoint ?? (_BackToPreviousTaskPoint = new RelayCommand<int>(async =>
{
_flightTaskManager.SelectedTask.VerticalLift = true;
}));
}
}
}
}

View File

@ -8,8 +8,8 @@
xmlns:ec="clr-namespace:Plane.Windows.Controls;assembly=Plane.Windows"
mc:Ignorable="d"
Title="连接"
Width="422"
Height="339"
Width="429.175"
Height="570.371"
Style="{StaticResource VSWindowStyleKey}"
WindowStartupLocation="CenterScreen"
FontFamily="Microsoft YaHei"
@ -65,6 +65,7 @@
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
</Grid.RowDefinitions>
<Grid.ColumnDefinitions>
<ColumnDefinition Width="Auto" />
@ -119,5 +120,14 @@
Command="{Binding Path=ConnectCommand}"
CommandParameter="UDP" />-->
</StackPanel>
<StackPanel Orientation="Horizontal"
HorizontalAlignment="Center"
Grid.Row="2"
Grid.ColumnSpan="3">
<Button Content="设置20台" Margin="10" Command="{Binding Path=SendCommand}" />
<Button Content="写入航点" Margin="10" Command="{Binding Path=CommWriteMissionCommand}" />
<Button Content="广播编号3" Margin="10" Command="{Binding Path=WriteIdCommand}" />
</StackPanel>
</Grid>
</c:MetroWindow>

View File

@ -63,19 +63,29 @@
Visibility="Hidden"
Text="{Binding AltP, UpdateSourceTrigger=PropertyChanged}" />
</WrapPanel>
<WrapPanel>
<Button Content="起飞测试"
Command="{Binding GuidAsyncCommand}" />
<Button Content="全部降落"
Command="{Binding AllLandCommand}" />
<Button Content="测试电机"
Command="{Binding MotorTestCommand}" />
<Button Content="全部加锁"
Command="{Binding LockAllCommand}" />
<Button Content="检测电压"
Command="{Binding DetectionVoltage}" />
</WrapPanel>
<WrapPanel>
<Button Content="写入航点"
Command="{Binding WriteMissionCommand}" />
<Button Content="全部解锁"
Command="{Binding UnlockAllCommand}" />
<Button Content="开始任务"
<Button Content="开始任务"
Command="{Binding MissionStartCommand}" />
</WrapPanel>
<WrapPanel>
<TextBox
Grid.Column="1"
@ -92,8 +102,6 @@
Text="{Binding Path=RTKState}"
/>
</WrapPanel>
<!--// 林俊清, 20150920, 目前不再使用 FormationController删除相关按钮。
<StackPanel Visibility="{Binding Source={x:Static fc:AppEx.Current}, Path=AppMode, Converter={StaticResource AppModeToVisibilityConverter}, ConverterParameter=ControlPanelView_Formation}">

View File

@ -66,6 +66,10 @@
<Button Content="清除"
Margin="5,0,5,0"
Command="{Binding ClearCoptersCommand}" />
<TextBlock Text="总数"
Margin="5,5,0,0"/>
<TextBlock Text="{Binding Path=CopterManager.Copters.Count}"
Margin="0,5,0,0"/>
<TextBlock Text="{Binding Path=Communinfo}"
Margin="5,5,0,0"/>

View File

@ -38,6 +38,13 @@ namespace Plane.FormationCreator.Views
{
_copterManager.RaiseSelectedCoptersChanged(e.AddedItems.Cast<ICopter>(), e.RemovedItems.Cast<ICopter>());
};
lvwDrones.KeyDown += (sender, e) =>
{
if (e.IsDown)
{
//e.can
}
};
}
private CopterManager _copterManager = ServiceLocator.Current.GetInstance<CopterManager>();

View File

@ -348,31 +348,33 @@ namespace Plane.FormationCreator.Views
}
Microsoft.Expression.Shapes.RegularPolygon original = null;
const double ORIGIN_RADIUS = 12;
private void FlightTaskManager_SetOriginal(object sender, FlightTaskAddedOriginalEventArgs e)
{
if (_copterManager.Copters.Count == 0) return;
if (map.Children.Contains(original))
return;
Location location = new Location();
if (e.Lat == 0 && e.Lng == 0)
location = map.Center;
else
location = new Location(e.Lat, e.Lng);
map.Children.Remove(original);
Location location = new Location(_copterManager.Copters[0].Latitude, _copterManager.Copters[0].Longitude);
Point point = map.LocationToViewportPoint(location);
point.X -= ORIGIN_RADIUS;
point.Y -= ORIGIN_RADIUS;
Location mapLocation = map.ViewportPointToLocation(point);
original = new Microsoft.Expression.Shapes.RegularPolygon
{
Tag = ORIGINALPOINT_TAG,
Fill = new SolidColorBrush(Color.FromRgb(237, 155, 3)),
Fill = new SolidColorBrush(Color.FromArgb(200,237, 155, 3)),
Stroke = new SolidColorBrush(Color.FromArgb(200, 238, 80, 238)),
StrokeThickness = 1,
Stroke = new SolidColorBrush(Color.FromRgb(255, 255, 255)),
Width = 25,
Height = 25,
Width = ORIGIN_RADIUS * 2,
Height = ORIGIN_RADIUS * 2,
InnerRadius = 0.5,
PointCount = 5,
};
map.Children.Add(original);
MapLayer.SetPosition(original, location);
MapLayer.SetPosition(original, mapLocation);
MapLayer.SetZIndex(original, 200);
original.ToolTip = location.ToString();
originaDrag = false;
_flightTaskManager.OriginLat = location.Latitude;
@ -382,11 +384,19 @@ namespace Plane.FormationCreator.Views
}
private bool originaDrag = false;
double originX = 0;
double originY = 0;
double wpOffsetX = 0;
double wpOffsetY = 0;
private void OriginalMouseDown(object sender, MouseButtonEventArgs e)
{
originaDrag = true;
var originPoint = e.GetPosition(map);
originX = originPoint.X;
originY = originPoint.Y;
var posInObject = e.GetPosition(original);
wpOffsetX = posInObject.X;
wpOffsetY = posInObject.Y;
@ -406,13 +416,16 @@ namespace Plane.FormationCreator.Views
private void OriginalMouseUp(object sender, MouseButtonEventArgs e)
{
if (originaDrag)
{
{
Point eventPos = e.GetPosition(map);
Location location = map.ViewportPointToLocation(eventPos);
var centrePos = new Point(eventPos.X - wpOffsetX + ORIGIN_RADIUS, eventPos.Y - wpOffsetY + ORIGIN_RADIUS);
Location location = map.ViewportPointToLocation(centrePos);
_flightTaskManager.OriginLat = location.Latitude;
_flightTaskManager.OriginLng = location.Longitude;
original.ToolTip = location.ToString();
Console.WriteLine("original-----------"+original.ToolTip);
Clipboard.SetDataObject(string.Format("{0},{1}", location.Latitude, location.Longitude), true);
originaDrag = false;
}

View File

@ -69,6 +69,7 @@ namespace Plane.FormationCreator.Views
const double COPTER_RADIUS = 12;
const double WAYPOINT_RADIUS = 6;
public ICopter Copter { get; set; }
public Grid DotContainer { get; set; }
@ -323,7 +324,7 @@ namespace Plane.FormationCreator.Views
//否则多选拖动
if (_flightTaskManager.SelectedTaskIndex != taskIndex || !_copterManager.SelectedCopters.Contains(this.Copter))
{
_copterManager.Select(null);
//_copterManager.Select(null);
_copterManager.Select(this.Copter);
_flightTaskManager.Select(taskIndex, this.Copter);
}

View File

@ -9,283 +9,169 @@
mc:Ignorable="d"
d:DesignWidth="300" Height="420">
<TabControl>
<TabItem Header="航点设计">
<StackPanel Orientation="Vertical" Margin="0,0,0,-30">
<StackPanel.Resources>
<Style TargetType="StackPanel">
<Setter Property="Orientation"
Value="Horizontal" />
</Style>
</StackPanel.Resources>
<StackPanel>
<Button Content="导出任务"
Margin="0,5,0,0"
Command="{Binding ExportTasksCommand}" />
<Button Content="导入任务"
Margin="5,5,0,0"
Command="{Binding ImportTasksCommand}"
/>
<TextBlock Text="起始步骤" Margin="5, 10, 5, 0"/>
<TextBox x:Name="txtStarindex"
Width="45"
Margin="0,5,5,0"
VerticalContentAlignment="Center"
Text="{Binding txtStarindex, UpdateSourceTrigger=PropertyChanged}"
/>
<TextBlock Text="结束" Margin="0, 10, 5, 0"/>
<TextBox x:Name="txtendindex"
Width="45"
Margin="0,5,5,0"
VerticalContentAlignment="Center"
Text="{Binding txtendindex, UpdateSourceTrigger=PropertyChanged}"
/>
</StackPanel>
<StackPanel>
<Button Content="上边对齐"
Margin="0,5,5,0"
Command="{Binding LevelAlignmentCommand}" />
<Button Content="右边对齐"
Margin="0,5,5,0"
Command="{Binding VerticlAlignmentCommand}" />
<Button Content="水平均分"
Margin="0,5,5,0"
Command="{Binding LevelAverageCommand}" />
<Button Content="垂直均分"
Margin="0,5,5,0"
Command="{Binding VerticlAverageCommand}" />
</StackPanel>
<StackPanel>
<Button Content="水平旋转"
Margin="0,5,5,0"
Command="{Binding LevelRotateCommand}"
CommandParameter="{Binding ElementName=txtAlignmentLine, Path=Text}"/>
<Button Content="垂直旋转"
Margin="0,5,5,0"
Command="{Binding VerticlRotateCommand}"
CommandParameter="{Binding ElementName=txtAlignmentLine, Path=Text}"/>
<Button Content="整体旋转"
Margin="0,5,5,0"
Command="{Binding TaskRotateCommand}"
CommandParameter="{Binding ElementName=txtAlignmentLine, Path=Text}"/>
<TextBox x:Name="txtAlignmentLine"
Width="35"
Margin="0,5,5,0"
Text="0"
VerticalContentAlignment="Center" />
<TextBlock Text="度" Margin="0, 10, 5, 0"/>
</StackPanel>
<StackPanel>
<Button Content="缩放比例"
Margin="0,5,5,0"
Command="{Binding ScaleCommand}"
CommandParameter="{Binding ElementName=txtScaleVale, Path=Text}"/>
<TextBox x:Name="txtScaleVale"
Width="35"
Margin="0,5,5,0"
Text="100"
VerticalContentAlignment="Center" />
<TextBlock Text="%" Margin="0, 10, 5, 0"/>
<Button Content="计算距离"
Margin="0,5,5,0"
Command="{Binding calDistinceCommand}"/>
<TextBox Grid.Column="1"
Width="35"
Margin="0, 5, 5, 0"
HorizontalContentAlignment="Right"
Text="{Binding Distancevalue, UpdateSourceTrigger=PropertyChanged}"/>
<TextBlock Text="米" Margin="0, 10, 5, 0"/>
<Button Content="前一高度"
Margin="0,5,5,0"
Command="{Binding PrealtCommand}" />
</StackPanel>
<StackPanel>
<Button Content="整体提高"
Margin="0,5,5,0"
Command="{Binding ModiAltCommand}"/>
<Button Content="整体移动"
Margin="0,5,5,0"
Command="{Binding ModiAllPosCommand}" />
<TextBox
Grid.Column="1"
Width="40"
Margin="0, 5, 5, 0"
HorizontalContentAlignment="Right"
Text="{Binding Modialtvalue, UpdateSourceTrigger=PropertyChanged}"/>
<TextBlock Text="米 方向" Margin="0, 10, 5, 0"/>
<TextBox Grid.Column="1"
Width="35"
Margin="0, 5, 5, 0"
HorizontalContentAlignment="Right"
Text="{Binding directionvalue, UpdateSourceTrigger=PropertyChanged}"/>
<TextBlock Text="度" Margin="0, 10, 5, 0"/>
</StackPanel>
<Separator />
<StackPanel>
<TextBlock Text="起飞数量:" Margin="5,10,5,0" />
<TextBox x:Name="txttakeoff"
Width="25"
Margin="0,5,5,0"
VerticalContentAlignment="Center"
DataContext="{Binding FlightTaskManager}"
Text="{Binding TakeOffNumAttr, UpdateSourceTrigger=PropertyChanged}"/>
</StackPanel>
</StackPanel>
</TabItem>
<TabItem Header="航点参数">
<TabControl Margin="0,5"
Grid.IsSharedSizeScope="True"
DataContext="{Binding FlightTaskManager.SelectedTask}"
SelectedIndex="{Binding TaskTypeIndex}">
<TabControl.Resources>
<Style TargetType="TextBlock">
<Setter Property="VerticalAlignment"
Value="Center" />
</Style>
<Style TargetType="TextBox"
BasedOn="{StaticResource {x:Type TextBox}}">
<Setter Property="VerticalAlignment"
Value="Center" />
<Setter Property="Margin"
Value="2" />
<Setter Property="MinWidth"
Value="100" />
</Style>
<Style TargetType="CheckBox"
BasedOn="{StaticResource {x:Type CheckBox}}">
<Setter Property="VerticalAlignment"
Value="Center" />
<Setter Property="Margin"
Value="2" />
</Style>
</TabControl.Resources>
<TabItem Header="航点">
<Grid Margin="5">
<Grid.RowDefinitions>
<RowDefinition SharedSizeGroup="TabItem" />
</Grid.RowDefinitions>
<Grid>
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition />
<RowDefinition />
<RowDefinition />
<RowDefinition />
</Grid.RowDefinitions>
<Grid Grid.Row="0" >
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition />
</Grid.RowDefinitions>
<TabControl SelectedIndex="{Binding FlightTaskManager.SelectedTask.TaskTypeIndex,UpdateSourceTrigger=PropertyChanged}">
<TabControl.Resources>
<Style TargetType="TabItem"
BasedOn="{StaticResource {x:Type TabItem}}">
<Setter Property="Visibility"
Value="Collapsed"/>
</Style>
</TabControl.Resources>
<TabItem Header="起飞">
<StackPanel Orientation="Vertical" Margin="0,0,0,-30">
<StackPanel.Resources>
<Style TargetType="StackPanel">
<Setter Property="Orientation"
Value="Horizontal" />
</Style>
</StackPanel.Resources>
<TextBlock Margin="5" Text="起飞任务"/>
<Separator/>
<!-- <StackPanel>
<TextBlock Text="起飞数量:" Margin="5,10,5,0" />
<TextBox x:Name="txttakeoff"
Width="25"
Margin="0,10,5,0"
VerticalContentAlignment="Center"
Text="{Binding FlightTaskManager.TakeOffNumAttr, UpdateSourceTrigger=PropertyChanged}"/>
</StackPanel>-->
<Separator />
<Grid DataContext="{Binding FlightTaskManager.SelectedTask.ModifyingSingleCopterInfo}"
>
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
<ColumnDefinition/>
<ColumnDefinition/>
<ColumnDefinition/>
<ColumnDefinition/>
</Grid.ColumnDefinitions>
<TextBlock Grid.Row="0" Text="飞行时间: " />
<TextBox Grid.Column="1" Margin="0,5,10,0"
Text="{Binding FlytoTime, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="1" Text="悬停时间: " />
<TextBox Grid.Row="1" Margin="0,5,10,0" Grid.Column="1"
Text="{Binding LoiterTime, UpdateSourceTrigger=PropertyChanged}" />
</Grid>
<Separator Grid.Row="1" />
<Grid Grid.Row="2" DataContext="{Binding ModifyingSingleCopterInfo}">
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
</Grid.ColumnDefinitions>
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition />
</Grid.RowDefinitions>
<TextBlock Text="灯光控制: " />
<Button Content="添加"
Grid.Column="1"
<TextBlock Margin="5" Text="起飞延时"/>
<TextBox Margin="5" Grid.Column="2"
Text="{Binding TakeOffWaitTime, UpdateSourceTrigger=PropertyChanged}"/>
<Button Content="应用所选" Margin="5" Grid.Column="3"
Command="{Binding SetSelTakeOffWaitCommand}"/>
</Grid>
</StackPanel>
</TabItem>
<TabItem Header="航点">
<StackPanel Orientation="Vertical" Margin="0,0,0,-30">
<StackPanel.Resources>
<Style TargetType="StackPanel">
<Setter Property="Orientation" Value="Horizontal" />
</Style>
</StackPanel.Resources>
<TextBlock Margin="5" Text="航点任务"/>
<Separator/>
<StackPanel>
<Button Content="上边对齐"
Margin="0,5,5,0"
Command="{Binding AddLEDCommand}" />
<ItemsControl Name="LEDItems"
Grid.Row="1"
Grid.ColumnSpan="2"
Height="Auto"
MaxHeight="200"
ScrollViewer.VerticalScrollBarVisibility="Auto"
ScrollViewer.HorizontalScrollBarVisibility="Disabled"
ItemsSource="{Binding Path= LEDInfos}">
<ItemsControl.ItemsPanel>
<ItemsPanelTemplate>
<StackPanel Orientation="Vertical" />
</ItemsPanelTemplate>
</ItemsControl.ItemsPanel>
<ItemsControl.ItemTemplate>
<DataTemplate>
<StackPanel Margin="0,8,0,0" Orientation="Horizontal" >
<TextBlock Text="类型" Margin="0,0,0,0" VerticalAlignment="Center" ></TextBlock>
<ComboBox MinWidth="80" Margin="5,0,0,0" Foreground="White" VerticalContentAlignment="Center"
SelectedIndex="{Binding Path=LEDMode}">
<ComboBox.ItemContainerStyle>
<Style>
<Setter Property="ComboBoxItem.Foreground" Value="White"/>
</Style>
</ComboBox.ItemContainerStyle>
<ComboBoxItem Content="常亮" />
<ComboBoxItem Content="闪烁" />
<ComboBoxItem Content="随机" />
<ComboBoxItem Content="渐亮" />
<ComboBoxItem Content="渐暗" />
</ComboBox>
Command="{Binding LevelAlignmentCommand}" />
<Button Content="右边对齐"
Margin="0,5,5,0"
Command="{Binding VerticlAlignmentCommand}" />
<Button Content="水平均分"
Margin="0,5,5,0"
Command="{Binding LevelAverageCommand}" />
<Button Content="垂直均分"
Margin="0,5,5,0"
Command="{Binding VerticlAverageCommand}" />
<Button Content="回起飞点"
Margin="0,5,5,0"
Command="{Binding BackTakeOffPointCommand}" />
</StackPanel>
<TextBlock Text="时间" Margin="12,0,0,0" VerticalAlignment="Center"></TextBlock>
<TextBox MinWidth="40" MaxWidth="50" Margin="5,0,0,0"
ToolTip="单位:秒最小设置0.1秒"
Text="{Binding Delay, UpdateSourceTrigger=PropertyChanged}" />
<StackPanel>
<Button Content="水平旋转"
Margin="0,5,5,0"
Command="{Binding LevelRotateCommand}"
CommandParameter="{Binding ElementName=txtAlignmentLine, Path=Text}"/>
<Button Content="垂直旋转"
Margin="0,5,5,0"
Command="{Binding VerticlRotateCommand}"
CommandParameter="{Binding ElementName=txtAlignmentLine, Path=Text}"/>
<TextBlock Text="频率" Margin="12,0,0,0" VerticalAlignment="Center"></TextBlock>
<TextBox MinWidth="40" MaxWidth="50" Margin="5,0,0,0"
Text="{Binding Path=LEDRate, UpdateSourceTrigger=PropertyChanged}" />
<Button Content="整体旋转"
Margin="0,5,5,0"
Command="{Binding TaskRotateCommand}"
CommandParameter="{Binding ElementName=txtAlignmentLine, Path=Text}"/>
<TextBlock Text="颜色" Margin="12,0,0,0" VerticalAlignment="Center"></TextBlock>
<TextBox Margin="5,0,0,0"
Text="{Binding LEDRGB, UpdateSourceTrigger=PropertyChanged}" />
<TextBox x:Name="txtAlignmentLine"
Width="35"
Margin="0,5,5,0"
Text="0"
VerticalContentAlignment="Center" />
<TextBlock Text="度" Margin="0, 10, 5, 0"/>
<Button Content="删除" Margin="12,0,0,0"
Command="{Binding RemoveLEDCommand}"/>
<Button Content="回上一任务"
Margin="0,5,5,0"
Command="{Binding BackToPreviousTaskPoint}" />
</StackPanel>
</StackPanel>
</DataTemplate>
</ItemsControl.ItemTemplate>
</ItemsControl>
</Grid>
<Separator Grid.Row="3" />
<Grid Grid.Row="4"
DataContext="{Binding ModifyingSingleCopterInfo}"
IsEnabled="{Binding CanModifySingleCopterInfo}">
<StackPanel>
<Button Content="缩放比例"
Margin="0,5,5,0"
Command="{Binding ScaleCommand}"
CommandParameter="{Binding ElementName=txtScaleVale, Path=Text}"/>
<TextBox x:Name="txtScaleVale"
Width="35"
Margin="0,5,5,0"
Text="100"
VerticalContentAlignment="Center" />
<TextBlock Text="%" Margin="0, 10, 5, 0"/>
<Button Content="计算距离"
Margin="0,5,5,0"
Command="{Binding calDistinceCommand}"/>
<TextBox Grid.Column="1"
Width="35"
Margin="0, 5, 5, 0"
HorizontalContentAlignment="Right"
Text="{Binding Distancevalue, UpdateSourceTrigger=PropertyChanged}"/>
<TextBlock Text="米" Margin="0, 10, 5, 0"/>
<Button Content="前一高度"
Margin="0,5,5,0"
Command="{Binding PrealtCommand}" />
</StackPanel>
<StackPanel>
<Button Content="整体提高"
Margin="0,5,5,0"
Command="{Binding ModiAltCommand}"/>
<Button Content="整体移动"
Margin="0,5,5,0"
Command="{Binding ModiAllPosCommand}" />
<TextBox
Grid.Column="1"
Width="40"
Margin="0, 5, 5, 0"
HorizontalContentAlignment="Right"
Text="{Binding Modialtvalue, UpdateSourceTrigger=PropertyChanged}"/>
<TextBlock Text="米 方向" Margin="0, 10, 5, 0"/>
<TextBox Grid.Column="1"
Width="35"
Margin="0, 5, 5, 0"
HorizontalContentAlignment="Right"
Text="{Binding directionvalue, UpdateSourceTrigger=PropertyChanged}"/>
<TextBlock Text="度" Margin="0, 10, 5, 0"/>
</StackPanel>
<Separator />
<Grid Margin="5,10,5,0"
DataContext="{Binding FlightTaskManager.SelectedTask.ModifyingSingleCopterInfo}"
IsEnabled="{Binding CanModifySingleCopterInfo}" >
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition />
<RowDefinition />
<RowDefinition />
</Grid.RowDefinitions>
<Grid.ColumnDefinitions>
<ColumnDefinition />
@ -294,7 +180,7 @@
<TextBlock Text="纬度: " />
<TextBox Grid.Column="1"
Margin="0,5,10,0"
Margin="0,5,10,0"
Text="{Binding TargetLat, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="1"
@ -310,327 +196,143 @@
Grid.Column="1"
Margin="0,5,10,0"
Text="{Binding TargetAlt, UpdateSourceTrigger=PropertyChanged}" />
<Button Grid.Row="3"
Content="应用高度到所选"
Grid.Column="1" Margin="0,5,10,0"
Command="{Binding SetAllCopterAltCommand}"/>
</Grid>
</Grid>
</Grid>
</TabItem>
<TabItem Header="转向" Visibility="Collapsed">
<Grid Margin="5">
<Grid.RowDefinitions>
<RowDefinition SharedSizeGroup="TabItem" />
</Grid.RowDefinitions>
<Grid>
<Grid.RowDefinitions>
<RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
</Grid.RowDefinitions>
<Separator Grid.Row="1" />
<Grid Grid.Row="2"
DataContext="{Binding ModifyingSingleCopterInfo}"
IsEnabled="{Binding CanModifySingleCopterInfo}">
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition />
</Grid.RowDefinitions>
<Separator/>
<Grid DataContext="{Binding FlightTaskManager.SelectedTask.ModifyingSingleCopterInfo}"
IsEnabled="{Binding CanModifySingleCopterInfo}" >
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
<ColumnDefinition Width="Auto" />
<ColumnDefinition/>
<ColumnDefinition/>
</Grid.ColumnDefinitions>
<TextBlock Text="目标偏航: " />
<TextBox Grid.Column="1"
Text="{Binding TargetHeading, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Column="2"
Text="°" />
<CheckBox Margin="5" IsChecked="{Binding IsLandWaypoint,UpdateSourceTrigger=PropertyChanged}" Content="下降点"/>
<Button Margin="5" Command="{Binding SetIsLandCommand}" Content="应用到所选" Grid.Column="1"/>
</Grid>
</Grid>
</Grid>
</TabItem>
<TabItem Header="画圈" Visibility="Collapsed">
<Grid Margin="5">
<Grid.RowDefinitions>
<RowDefinition SharedSizeGroup="TabItem" />
</Grid.RowDefinitions>
<Grid>
<Grid.RowDefinitions>
<RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
</Grid.RowDefinitions>
<Separator Grid.Row="1" />
<Grid Grid.Row="2"
DataContext="{Binding ModifyingSingleCopterInfo}"
IsEnabled="{Binding CanModifySingleCopterInfo}">
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition />
<RowDefinition />
<RowDefinition />
<RowDefinition />
</Grid.RowDefinitions>
</StackPanel>
</TabItem>
<TabItem Header="降落">
<StackPanel Orientation="Vertical" Margin="0,0,0,-30">
<StackPanel.Resources>
<Style TargetType="StackPanel">
<Setter Property="Orientation"
Value="Horizontal" />
</Style>
</StackPanel.Resources>
<TextBlock Margin="5" Text="降落任务"/>
<Separator/>
<Grid DataContext="{Binding FlightTaskManager.SelectedTask.ModifyingSingleCopterInfo}"
IsEnabled="{Binding CanModifySingleCopterInfo}" >
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
<ColumnDefinition Width="Auto" />
<ColumnDefinition/>
<ColumnDefinition/>
<ColumnDefinition/>
<ColumnDefinition/>
</Grid.ColumnDefinitions>
<TextBlock Text="圆心方向: " />
<TextBox Grid.Column="1"
Text="{Binding CenterDirectionDeg, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Column="2"
Text="°" />
<TextBlock Grid.Row="1"
Text="半径: " />
<TextBox Grid.Row="1"
Grid.Column="1"
Text="{Binding Radius, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="1"
Grid.Column="2"
Text="cm" />
<TextBlock Grid.Row="2"
Text="角速度: " />
<TextBox Grid.Row="2"
Grid.Column="1"
Text="{Binding Rate, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="2"
Grid.Column="2"
Text="°/s" />
<TextBlock Grid.Row="3"
Text="圈数: " />
<TextBox Grid.Row="3"
Grid.Column="1"
Text="{Binding Turns, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="3"
Grid.Column="2"
Text="圈" />
<TextBlock Grid.Row="4"
Text="通道3: " />
<TextBox Grid.Row="4"
Grid.Column="1"
Text="{Binding Channel3, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Margin="5" Text="降落延时"/>
<TextBox Margin="5" Grid.Column="2"
Text="{Binding LandWaitTime, UpdateSourceTrigger=PropertyChanged}"/>
<Button Content="应用所选" Command="{Binding SetSelLandWaitTimeCommand}" Grid.Column="3"/>
</Grid>
</StackPanel>
</TabItem>
</TabControl>
</TabItem>
<TabItem Header="灯光设计">
<StackPanel DataContext="{Binding FlightTaskManager.SelectedTask.ModifyingSingleCopterInfo}">
<Grid >
<Grid.ColumnDefinitions>
<ColumnDefinition/>
<ColumnDefinition/>
</Grid.ColumnDefinitions>
<TextBlock Text="灯光控制: " Margin="5, 10, 5, 0" VerticalAlignment="Center"/>
<Grid Grid.Column="1" VerticalAlignment="Center">
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
</Grid.ColumnDefinitions>
<Button Content="应用到全部" VerticalAlignment="Center"
Margin="0,5,5,0"
Command="{Binding SetAllCopterLEDCommand}" />
<Button Content="添加" VerticalAlignment="Center"
Grid.Column="1"
Margin="0,5,5,0"
Command="{Binding AddLEDCommand}" />
</Grid>
</Grid>
</TabItem>
<TabItem Header="悬停">
<Grid Margin="5">
<Grid.RowDefinitions>
<RowDefinition SharedSizeGroup="TabItem" />
</Grid.RowDefinitions>
<Grid>
<Grid.RowDefinitions>
<RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
</Grid.RowDefinitions>
<Grid>
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition />
<RowDefinition />
<RowDefinition />
<RowDefinition />
</Grid.RowDefinitions>
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
</Grid.ColumnDefinitions>
<TextBlock Text="悬停时间:(秒) " />
<TextBox Grid.Column="1"
Text="{Binding LoiterTimeAttr, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="1" Grid.Column="0" Text="闪烁:(次数) " />
<Grid Grid.Row="1" Grid.Column="1">
<Grid.RowDefinitions>
<RowDefinition />
</Grid.RowDefinitions>
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
</Grid.ColumnDefinitions>
<CheckBox Grid.Row="0" Grid.Column="0"
IsChecked="{Binding flashAttr, UpdateSourceTrigger=PropertyChanged}" />
<TextBox Grid.Column="1" Grid.Row="0"
Text="{Binding flashPeriodAttr, UpdateSourceTrigger=PropertyChanged}" />
</Grid>
<TextBlock Grid.Row="2" Grid.Column="0" Text="走马灯: " />
<Grid Grid.Row="2" Grid.Column="1">
<Grid.RowDefinitions>
<RowDefinition />
</Grid.RowDefinitions>
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
</Grid.ColumnDefinitions>
<CheckBox Grid.Row="0" Grid.Column="0"
IsChecked="{Binding oneByOneAttr, UpdateSourceTrigger=PropertyChanged}" />
<TextBox Grid.Column="1" Grid.Row="0"
Text="{Binding oneByOnePeriodAttr, UpdateSourceTrigger=PropertyChanged}" />
</Grid>
<TextBox Grid.Row="3" Grid.ColumnSpan="2" Text="{Binding flashCopterNameArray, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="4" Grid.Column="0" Text="机头方向: " />
<Grid Grid.Row="4" Grid.Column="1">
<Grid.RowDefinitions>
<RowDefinition />
</Grid.RowDefinitions>
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
</Grid.ColumnDefinitions>
<CheckBox Grid.Row="0" Grid.Column="0"
IsChecked="{Binding ChangeYaw, UpdateSourceTrigger=PropertyChanged}" />
<TextBox Grid.Column="1" Grid.Row="0"
Text="{Binding HeadYaw, UpdateSourceTrigger=PropertyChanged}" />
</Grid>
</Grid>
</Grid>
</Grid>
</TabItem>
<!--
<TabItem Header="LED控制">
<Grid Margin="5">
<Grid.RowDefinitions>
<RowDefinition SharedSizeGroup="TabItem" />
</Grid.RowDefinitions>
<Grid>
<Grid.RowDefinitions>
<RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
</Grid.RowDefinitions>
<ItemsControl Name="LEDItems" Margin="5"
Grid.Row="1"
Grid.ColumnSpan="2"
MinHeight="180"
MaxHeight="350"
ScrollViewer.VerticalScrollBarVisibility="Visible"
ScrollViewer.HorizontalScrollBarVisibility="Hidden"
ItemsSource="{Binding Path= LEDInfos}">
<ItemsControl.Template>
<ControlTemplate>
<ScrollViewer x:Name="ScrollViewer" Padding="{TemplateBinding Padding}">
<ItemsPresenter />
</ScrollViewer>
</ControlTemplate>
</ItemsControl.Template>
<ItemsControl.ItemsPanel>
<ItemsPanelTemplate>
<StackPanel Orientation="Vertical" />
</ItemsPanelTemplate>
</ItemsControl.ItemsPanel>
<ItemsControl.ItemTemplate>
<DataTemplate>
<StackPanel Margin="0,5,0,0" Orientation="Horizontal" >
<TextBlock Text="类型" Margin="0,0,0,0" VerticalAlignment="Center" ></TextBlock>
<ComboBox MinWidth="80" Margin="5,0,0,0" Foreground="White" VerticalContentAlignment="Center"
SelectedIndex="{Binding Path=LEDMode}">
<ComboBox.ItemContainerStyle>
<Style>
<Setter Property="ComboBoxItem.Foreground" Value="White"/>
</Style>
</ComboBox.ItemContainerStyle>
<ComboBoxItem Content="常亮" />
<ComboBoxItem Content="闪烁" />
<ComboBoxItem Content="随机" />
<ComboBoxItem Content="渐亮" />
<ComboBoxItem Content="渐暗" />
</ComboBox>
<Separator Grid.Row="1" />
<TextBlock Text="时间" Margin="12,0,0,0" VerticalAlignment="Center"></TextBlock>
<TextBox MinWidth="40" MaxWidth="50" Margin="5,0,0,0"
ToolTip="单位:秒最小设置0.1秒"
Text="{Binding Delay,UpdateSourceTrigger=PropertyChanged}" />
<Grid Grid.Row="2"
DataContext="{Binding ModifyingSingleCopterInfo}"
IsEnabled="{Binding CanModifySingleCopterInfo}">
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition />
</Grid.RowDefinitions>
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
<ColumnDefinition Width="Auto" />
</Grid.ColumnDefinitions>
<TextBlock Text="频率" Margin="12,0,0,0" VerticalAlignment="Center"></TextBlock>
<TextBox MinWidth="40" MaxWidth="50" Margin="5,0,0,0"
Text="{Binding Path=LEDRate, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="0" Grid.Column="0" Text="全部闪烁: " />
<TextBox Grid.Column="1" Grid.Row="0"
Text="15" />
<TextBlock Text="颜色" Margin="12,0,0,0" VerticalAlignment="Center"></TextBlock>
<TextBox Margin="5,0,0,0"
Text="{Binding LEDRGB, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="1" Grid.Column="0" Text="走马灯: " />
<TextBox Grid.Column="1" Grid.Row="1"
Text="15" />
</Grid>
</Grid>
</Grid>
</TabItem>
-->
<TabItem Header="返航">
<Grid Margin="5">
<Grid.RowDefinitions>
<RowDefinition SharedSizeGroup="TabItem" />
</Grid.RowDefinitions>
<Grid>
<Grid.RowDefinitions>
<RowDefinition Height="Auto" />
</Grid.RowDefinitions>
<Button Content="删除" Margin="12,0,0,0"
Command="{Binding RemoveLEDCommand}"/>
<Grid>
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition />
</Grid.RowDefinitions>
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
</Grid.ColumnDefinitions>
<TextBlock Text="返航高度: " />
<TextBox Grid.Column="1" Grid.Row="0"
Text="{Binding RTLAlt, UpdateSourceTrigger=PropertyChanged}" />
</StackPanel>
</DataTemplate>
</ItemsControl.ItemTemplate>
<TextBlock Text="同时返航数量: " Grid.Row="1" Grid.Column="0" />
<TextBox Grid.Column="1" Grid.Row="1"
Text="{Binding RetNumAttr, UpdateSourceTrigger=PropertyChanged}" />
</Grid>
</Grid>
</Grid>
</TabItem>
<!--<TabItem Header="简单画圈">
<Grid Margin="5">
<Grid.RowDefinitions>
<RowDefinition SharedSizeGroup="TabItem" />
</Grid.RowDefinitions>
<Grid>
<Grid.RowDefinitions>
<RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
</Grid.RowDefinitions>
<Separator Grid.Row="1" />
<Grid Grid.Row="2"
DataContext="{Binding ModifyingSingleCopterInfo}"
IsEnabled="{Binding CanModifySingleCopterInfo}">
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition />
<RowDefinition />
</Grid.RowDefinitions>
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
<ColumnDefinition Width="Auto" />
</Grid.ColumnDefinitions>
<TextBlock Grid.Row="0"
Text="角速度: " />
<TextBox Grid.Row="0"
Grid.Column="1"
Text="{Binding Rate, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="0"
Grid.Column="2"
Text="°/s" />
<TextBlock Grid.Row="1"
Text="圈数: " />
<TextBox Grid.Row="1"
Grid.Column="1"
Text="{Binding Turns, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="1"
Grid.Column="2"
Text="圈" />
<TextBlock Grid.Row="2"
Text="通道3: " />
<TextBox Grid.Row="2"
Grid.Column="1"
Text="{Binding Channel3, UpdateSourceTrigger=PropertyChanged}" />
</Grid>
</Grid>
</Grid>
</TabItem>-->
</TabControl>
</ItemsControl>
</StackPanel>
</TabItem>
</TabControl>
</UserControl>

View File

@ -24,11 +24,12 @@ namespace Plane.FormationCreator.Views
/// </summary>
public partial class ModifyTaskView : UserControl
{
ModifyTaskViewModel _modifyTaskViewModel = ServiceLocator.Current.GetInstance<ModifyTaskViewModel>();
public ModifyTaskView()
{
InitializeComponent();
this.DataContext = ServiceLocator.Current.GetInstance<ModifyTaskViewModel>();
this.DataContext = _modifyTaskViewModel;
}
private void Button_Click(object sender, RoutedEventArgs e)

View File

@ -105,9 +105,9 @@
Foreground="Black"
Text="{Binding TaskType}" />
</Border>
</Grid>
</DataTemplate>
</ItemsControl.ItemTemplate>
</ItemsControl>
@ -117,27 +117,28 @@
<RowDefinition/>
<RowDefinition/>
</Grid.RowDefinitions>
<StackPanel Visibility="Hidden">
<ComboBox Width="100" HorizontalAlignment="Left" Foreground="White"
DataContext="{Binding FlightTaskManager.SelectedTask}"
SelectedIndex="{Binding TaskTypeIndex}">
<ComboBox.ItemContainerStyle>
<Style>
<Setter Property="ComboBoxItem.Foreground" Value="White"/>
</Style>
</ComboBox.ItemContainerStyle>
<ComboBoxItem Content="航点" />
<ComboBoxItem Content="转向" />
<ComboBoxItem Content="画圈" />
<ComboBoxItem Content="悬停" />
<ComboBoxItem Content="返航" />
</ComboBox>
<StackPanel Height="100" Background="#FF2D2D2D">
<TabControl
DataContext="{Binding FlightTaskManager.SelectedTask}"
SelectedIndex="{Binding TaskTypeIndex}">
SelectedIndex="{Binding TaskTypeIndex,UpdateSourceTrigger=PropertyChanged}">
<TabItem Header="起飞">
<Grid Margin="10">
<Grid.ColumnDefinitions>
<ColumnDefinition/>
<ColumnDefinition/>
</Grid.ColumnDefinitions>
<TextBlock Text="起飞时间"/>
<TextBox Grid.Column="1" Margin="2"
Text="{Binding TakeOffTime, UpdateSourceTrigger=PropertyChanged}" />
</Grid>
</TabItem>
<TabItem Header="航点">
<Grid>
<Grid Margin="10">
<Grid.RowDefinitions>
<RowDefinition />
<RowDefinition />
@ -147,25 +148,29 @@
<ColumnDefinition />
</Grid.ColumnDefinitions>
<TextBlock Grid.Row="0" Text="飞行时间: " />
<TextBox Grid.Column="1" Margin="0,5,10,0"
<TextBox Grid.Column="1" Margin="2"
Text="{Binding FlytoTime, UpdateSourceTrigger=PropertyChanged}" />
<TextBlock Grid.Row="1" Text="悬停时间: " />
<TextBox Grid.Row="1" Margin="0,5,10,0" Grid.Column="1"
<TextBox Grid.Row="1" Grid.Column="1" Margin="2"
Text="{Binding LoiterTime, UpdateSourceTrigger=PropertyChanged}" />
</Grid>
</TabItem>
<TabItem Header="转向">
</TabItem>
<TabItem Header="画圈">
</TabItem>
<TabItem Header="悬停">
</TabItem>
<TabItem Header="返航">
<TabItem Header="降落">
<Grid Margin="10" >
<Grid.RowDefinitions>
<RowDefinition />
</Grid.RowDefinitions>
<Grid.ColumnDefinitions>
<ColumnDefinition />
<ColumnDefinition />
</Grid.ColumnDefinitions>
<TextBlock Text="等待时间: " />
<TextBox Grid.Column="1" Margin="2"
Text="{Binding LandWaitTime, UpdateSourceTrigger=PropertyChanged}" />
</Grid>
</TabItem>
</TabControl>
</StackPanel>
<StackPanel Grid.Row="1"
@ -183,14 +188,14 @@
<Button Content="强制下一步"
Background="#232323"
Command="{Binding NextTasksCommand}" />
<Button Content="设原点"
<Button Content="设原点"
Background="#232323"
Command="{Binding SetOriginCommand}" />
<!--<Button Content="保存" />
<Button Content="取消" />-->
</StackPanel>
</Grid>
</Grid>
</UserControl>

View File

@ -36,7 +36,7 @@ namespace Plane.FormationCreator.Views
{
var elem = sender as FrameworkElement;
var task = elem.DataContext as FlightTask;
if (task.TaskType != FlightTaskType.TakeOff) // 不让选起飞任务。
//if (task.TaskType != FlightTaskType.TakeOff) // 不让选起飞任务。 现在可以选择起飞任务
{
_flightTaskManager.Select(task);
}