自动按照位置排序虚拟ID

This commit is contained in:
zxd 2019-12-11 20:39:44 +08:00
parent b098acc7d0
commit 6e7d33ed91
14 changed files with 446 additions and 73 deletions

View File

@ -442,8 +442,70 @@ namespace Plane.FormationCreator.Formation
public void ImportC4DFlytoTask(string txt) public void ImportC4DFlytoTask(string txt)
{ {
string[] lines = txt.Replace("\r\n", "\n").Split('\n'); 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; return;
}
int taskCount = lines.Length / (_copterManager.Copters.Count + 1);
int startIndex;
string line;
Dictionary<int, string[]> PointDic;
for (int i = 0; i < taskCount; i++)
{
startIndex = i * (_copterManager.Copters.Count + 1);
string taskName = lines[startIndex];
PointDic = new Dictionary<int, string[]>();
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<double, double> 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<int, string[]> PointDic = new Dictionary<int, string[]>(); Dictionary<int, string[]> PointDic = new Dictionary<int, string[]>();
foreach (string line in lines) foreach (string line in lines)
{ {
@ -451,9 +513,9 @@ namespace Plane.FormationCreator.Formation
int id = Convert.ToInt32(parameters[0]); int id = Convert.ToInt32(parameters[0]);
string frame = parameters[1]; string frame = parameters[1];
string[] point = new string[3]; string[] point = new string[3];
point[0] = parameters[2]; //左右 经度 point[0] = parameters[1]; //左右 经度
point[1] = parameters[3]; //上下 高度 point[1] = parameters[2]; //上下 高度
point[2] = parameters[4]; //前后 纬度 point[2] = parameters[3]; //前后 纬度
PointDic.Add(id, point); PointDic.Add(id, point);
} }
@ -489,6 +551,7 @@ namespace Plane.FormationCreator.Formation
} }
Tasks.Add(newTask); Tasks.Add(newTask);
TaskAdded?.Invoke(this, new FlightTaskAddedEventArgs { LastTask = lastTask, AddedTask = 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; var copters = _copterManager.Copters;
float tagalt = 15; float tagalt = 15;
@ -559,9 +622,18 @@ namespace Plane.FormationCreator.Formation
{ {
var singleCopterInfoObj = singleCopterInfos[i]; var singleCopterInfoObj = singleCopterInfos[i];
tagalt = (float)singleCopterInfoObj.targetAlt; tagalt = (float)singleCopterInfoObj.targetAlt;
newSingleCopterInfo = FlightTaskSingleCopterInfo.CreateForFlyToTask( if (isMeter)
copter, new LatLng((double)singleCopterInfoObj.latOffset, newSingleCopterInfo = FlightTaskSingleCopterInfo.CreateForFlyToTask(
(double)singleCopterInfoObj.lngOffset), (float)singleCopterInfoObj.targetAlt - copter.GroundAlt, (bool)singleCopterInfoObj.isLandWaypoint); 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; var jsonArray = singleCopterInfoObj.ledInfos as Newtonsoft.Json.Linq.JArray;
ObservableCollection<LEDInfo> ledList = jsonArray.ToObject<ObservableCollection<LEDInfo>>(); ObservableCollection<LEDInfo> ledList = jsonArray.ToObject<ObservableCollection<LEDInfo>>();
@ -767,6 +839,165 @@ namespace Plane.FormationCreator.Formation
SelectedTaskIndex = Tasks.Count - 1; SelectedTaskIndex = Tasks.Count - 1;
} }
//导出任务 (单位:米)
public IEnumerable<object> ExportTasksToMeter()
{
var tasks = Tasks.Select<FlightTask, object>(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<object> ExportTasks() public IEnumerable<object> 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; var copters = _copterManager.Copters;
@ -1041,7 +1272,7 @@ namespace Plane.FormationCreator.Formation
RestoreTakeOffTask((byte)task.takeoffTime, task.singleCopterInfos); RestoreTakeOffTask((byte)task.takeoffTime, task.singleCopterInfos);
break; break;
case FlightTaskType.FlyTo: 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; break;
case FlightTaskType.Turn: case FlightTaskType.Turn:
RestoreTurnTask(task.singleCopterInfos); 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; var copters = _copterManager.Copters;
@ -1394,7 +1627,7 @@ namespace Plane.FormationCreator.Formation
RestoreTakeOffTask((byte)task.takeoffTime, task.singleCopterInfos); RestoreTakeOffTask((byte)task.takeoffTime, task.singleCopterInfos);
break; break;
case FlightTaskType.FlyTo: 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; break;
case FlightTaskType.Turn: case FlightTaskType.Turn:
RestoreTurnTask(task.singleCopterInfos); RestoreTurnTask(task.singleCopterInfos);

View File

@ -8,6 +8,7 @@ using System.Text;
using System.Threading.Tasks; using System.Threading.Tasks;
using System.Windows.Input; using System.Windows.Input;
using GalaSoft.MvvmLight.Command; using GalaSoft.MvvmLight.Command;
using Plane.Geography;
namespace Plane.FormationCreator.Formation 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<double, double> 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<double, double> observationLatLng = null;
observationLatLng = GeographyUtils.CalcLatLngSomeMetersAway2D(
_flightTaskManager.OriginLat,
_flightTaskManager.OriginLng,
0,
Convert.ToSingle(value));
TargetLat = observationLatLng.Item1;
}
}
public LatLng LatLngOffset public LatLng LatLngOffset
{ {
@ -200,6 +246,8 @@ namespace Plane.FormationCreator.Formation
} }
} }
public LatLng GetOrigin() public LatLng GetOrigin()
{ {
return _copterManager.Copters.GetCenter() ?? LatLng.Empty; return _copterManager.Copters.GetCenter() ?? LatLng.Empty;

View File

@ -34,7 +34,19 @@ namespace Plane.FormationCreator.Formation
return info; 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 public bool FlytoShowLED
{ {
get { return _FlytoShowLED; } get { return _FlytoShowLED; }

View File

@ -238,15 +238,16 @@ namespace Plane.FormationCreator.Formation
public async Task Close() public async Task Close()
{ {
await _commModuleManager.CloseRtcmLoop();
Rtcmthreadrun = false; Rtcmthreadrun = false;
comPort.Close(); comPort.Close();
await Task.Delay(1);
} }
private async Task RtcmLoop() private async Task RtcmLoop()
{ {
int reconnecttimeout = 10; int reconnecttimeout = 10;
DateTime lastrecv = DateTime.MinValue; DateTime lastrecv = DateTime.MinValue;
await _commModuleManager.StartRtcmLoop();
while (Rtcmthreadrun) while (Rtcmthreadrun)
{ {
try try
@ -289,7 +290,7 @@ namespace Plane.FormationCreator.Formation
if ((seenmsg = rtcm.Read(buffer[a])) > 0) if ((seenmsg = rtcm.Read(buffer[a])) > 0)
{ {
bpsusefull += rtcm.length; bpsusefull += rtcm.length;
Message.Show($"{DateTime.Now.ToString("HH-mm-ss:fff")} rtcm.length = {rtcm.length}");
await _commModuleManager.InjectGpsRTCMDataAsync(rtcm.packet, rtcm.length); await _commModuleManager.InjectGpsRTCMDataAsync(rtcm.packet, rtcm.length);
string msgname = "Rtcm" + seenmsg; string msgname = "Rtcm" + seenmsg;

View File

@ -116,6 +116,7 @@
<MenuItem Header="窗口" Margin="0,2,0,0" Foreground="#969696"> <MenuItem Header="窗口" Margin="0,2,0,0" Foreground="#969696">
<CheckBox Content="属性设置" Margin="0,8,0,8" IsChecked="False" Click="btnAttribute_Click"/> <CheckBox Content="属性设置" Margin="0,8,0,8" IsChecked="False" Click="btnAttribute_Click"/>
<CheckBox Content="分组设置" Margin="0,8,0,8" IsChecked="False" Click="btnGroup_Click"/> <CheckBox Content="分组设置" Margin="0,8,0,8" IsChecked="False" Click="btnGroup_Click"/>
<CheckBox Content="自动编号" Margin="0,8,0,8" IsChecked="False" Click="btnVirtualId_Click"/>
</MenuItem> </MenuItem>
</Menu> </Menu>
</c:WindowCommands> </c:WindowCommands>
@ -164,6 +165,10 @@
x:Name="groupsView" x:Name="groupsView"
Visibility="Collapsed"> Visibility="Collapsed">
</v:CopterGroupsView> </v:CopterGroupsView>
<v:ConfigVirtualIdView
x:Name="configVirtualView"
Visibility="Collapsed">
</v:ConfigVirtualIdView>
</WrapPanel> </WrapPanel>
</Grid> </Grid>

View File

@ -35,13 +35,7 @@ namespace Plane.FormationCreator
this.DataContext = ServiceLocator.Current.GetInstance<MainViewModel>(); this.DataContext = ServiceLocator.Current.GetInstance<MainViewModel>();
DateTime dateTimeClose = DateTime.Parse("2019-12-7");
if (DateTime.UtcNow > dateTimeClose)
{
MessageBox.Show("软件过旧,请更新!");
Application.Current.Shutdown();
throw new NotImplementedException();
}
//ShowConnectDialog(); //ShowConnectDialog();
//if (_copterManager.CoptersForControlling.Count <= 0) //if (_copterManager.CoptersForControlling.Count <= 0)
//{ //{
@ -532,5 +526,14 @@ namespace Plane.FormationCreator
else else
groupsView.Visibility = Visibility.Visible; 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;
}
} }
} }

View File

@ -119,6 +119,8 @@
<HintPath>..\packages\System.Data.SQLite.Linq.1.0.109.0\lib\net46\System.Data.SQLite.Linq.dll</HintPath> <HintPath>..\packages\System.Data.SQLite.Linq.1.0.109.0\lib\net46\System.Data.SQLite.Linq.dll</HintPath>
<Private>True</Private> <Private>True</Private>
</Reference> </Reference>
<Reference Include="System.Drawing" />
<Reference Include="System.Windows.Forms" />
<Reference Include="System.Windows.Interactivity, Version=4.5.0.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35, processorArchitecture=MSIL"> <Reference Include="System.Windows.Interactivity, Version=4.5.0.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35, processorArchitecture=MSIL">
<HintPath>..\packages\MahApps.Metro.1.5.0\lib\net45\System.Windows.Interactivity.dll</HintPath> <HintPath>..\packages\MahApps.Metro.1.5.0\lib\net45\System.Windows.Interactivity.dll</HintPath>
<Private>True</Private> <Private>True</Private>
@ -205,6 +207,7 @@
<Compile Include="Util\rtcm3.cs" /> <Compile Include="Util\rtcm3.cs" />
<Compile Include="Util\VersionControl.cs" /> <Compile Include="Util\VersionControl.cs" />
<Compile Include="ViewModels\CalibrationViewModel.cs" /> <Compile Include="ViewModels\CalibrationViewModel.cs" />
<Compile Include="ViewModels\ConfigVirtualIdViewModel.cs" />
<Compile Include="ViewModels\ConnectViewModel.cs" /> <Compile Include="ViewModels\ConnectViewModel.cs" />
<Compile Include="ViewModels\ControlPanelViewModel.cs" /> <Compile Include="ViewModels\ControlPanelViewModel.cs" />
<Compile Include="ViewModels\CopterListViewModel.cs" /> <Compile Include="ViewModels\CopterListViewModel.cs" />
@ -219,6 +222,9 @@
<Compile Include="Views\CalibrationWindow.xaml.cs"> <Compile Include="Views\CalibrationWindow.xaml.cs">
<DependentUpon>CalibrationWindow.xaml</DependentUpon> <DependentUpon>CalibrationWindow.xaml</DependentUpon>
</Compile> </Compile>
<Compile Include="Views\ConfigVirtualIdView.xaml.cs">
<DependentUpon>ConfigVirtualIdView.xaml</DependentUpon>
</Compile>
<Compile Include="Views\ControlPanelView.xaml.cs"> <Compile Include="Views\ControlPanelView.xaml.cs">
<DependentUpon>ControlPanelView.xaml</DependentUpon> <DependentUpon>ControlPanelView.xaml</DependentUpon>
</Compile> </Compile>
@ -348,6 +354,10 @@
<SubType>Designer</SubType> <SubType>Designer</SubType>
<Generator>MSBuild:Compile</Generator> <Generator>MSBuild:Compile</Generator>
</Page> </Page>
<Page Include="Views\ConfigVirtualIdView.xaml">
<SubType>Designer</SubType>
<Generator>MSBuild:Compile</Generator>
</Page>
<Page Include="Views\ControlPanelView.xaml"> <Page Include="Views\ControlPanelView.xaml">
<SubType>Designer</SubType> <SubType>Designer</SubType>
<Generator>MSBuild:Compile</Generator> <Generator>MSBuild:Compile</Generator>

View File

@ -36,6 +36,7 @@ namespace Plane.FormationCreator
_container.Register<CalibrationViewModel>(); _container.Register<CalibrationViewModel>();
_container.Register<GroupsViewModel>(); _container.Register<GroupsViewModel>();
_container.Register<RtcmInfoViewModel>(); _container.Register<RtcmInfoViewModel>();
_container.Register<ConfigVirtualIdViewModel>();
_container.Register<ILogger>(() => new LocalFileLogger(new DebugLogger())); _container.Register<ILogger>(() => new LocalFileLogger(new DebugLogger()));

View File

@ -1330,7 +1330,6 @@ namespace Plane.FormationCreator.ViewModels
var _flightTaskManager = ServiceLocator.Current.GetInstance<FlightTaskManager>(); var _flightTaskManager = ServiceLocator.Current.GetInstance<FlightTaskManager>();
for (j = 0; j < _flightTaskManager.Tasks.Count; j++) for (j = 0; j < _flightTaskManager.Tasks.Count; j++)
{ {
switch (_flightTaskManager.Tasks[j].TaskType) switch (_flightTaskManager.Tasks[j].TaskType)
{ {
case FlightTaskType.TakeOff: case FlightTaskType.TakeOff:
@ -1389,7 +1388,8 @@ namespace Plane.FormationCreator.ViewModels
break; 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); //CommWriteMissinState state = new CommWriteMissinState(result);
//_commModuleManager.missionWriteState.Add(int.Parse(_copterManager.Copters[i].Id), state); //_commModuleManager.missionWriteState.Add(int.Parse(_copterManager.Copters[i].Id), state);
if (!result) if (!result)

View File

@ -20,6 +20,7 @@ using Plane.FormationCreator.Util;
using Newtonsoft.Json; using Newtonsoft.Json;
using System.IO; using System.IO;
using Newtonsoft.Json.Linq; using Newtonsoft.Json.Linq;
using Plane.Windows.Messages;
namespace Plane.FormationCreator.ViewModels namespace Plane.FormationCreator.ViewModels
{ {
@ -99,6 +100,13 @@ namespace Plane.FormationCreator.ViewModels
set { Set(nameof(ContinuousNum), ref _ContinuousNum, value); } 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<string[]> CopterGroups { get; } = new ObservableCollection<string[]>(); public ObservableCollection<string[]> CopterGroups { get; } = new ObservableCollection<string[]>();
@ -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; private ICommand _AddVirtualCopterCommand;
public ICommand AddVirtualCopterCommand public ICommand AddVirtualCopterCommand
{ {
@ -292,6 +319,9 @@ namespace Plane.FormationCreator.ViewModels
} }
} }
private ICommand _SetCoptersPutCommand; private ICommand _SetCoptersPutCommand;
public ICommand SetCoptersPutCommand public ICommand SetCoptersPutCommand
{ {

View File

@ -13,6 +13,7 @@ using Microsoft.Win32;
using Microsoft.Practices.ServiceLocation; using Microsoft.Practices.ServiceLocation;
using System.IO; using System.IO;
using Newtonsoft.Json; using Newtonsoft.Json;
using Plane.Geography;
namespace Plane.FormationCreator.ViewModels namespace Plane.FormationCreator.ViewModels
{ {
@ -195,36 +196,44 @@ namespace Plane.FormationCreator.ViewModels
return; 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 var dialog = new SaveFileDialog
{ {
DefaultExt = "fcg", DefaultExt = "fcgm",
Filter = "编队飞行任务 (*.fcg)|*.fcg" Filter = "编队任务 (*.fcgm)|*.fcgm|旧编队任务(*.fcg)|*.fcg"
}; };
if (dialog.ShowDialog() == true) if (dialog.ShowDialog() == true)
{ {
IEnumerable<object> 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); File.WriteAllText(dialog.FileName, exportedText);
} }
})); }));
@ -245,21 +254,6 @@ namespace Plane.FormationCreator.ViewModels
return locateList; return locateList;
} }
//导出航点 单位米
private List<object> ExportLocateToMeter()
{
List<object> locateList = new List<object>();
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; private int _txtStarindex = 0;
public int txtStarindex public int txtStarindex
@ -289,11 +283,14 @@ namespace Plane.FormationCreator.ViewModels
} }
var dialog = new OpenFileDialog var dialog = new OpenFileDialog
{ {
DefaultExt = "fcg", DefaultExt = "fcgm",
Filter = "编队飞行任务 (*.fcg)|*.fcg" Filter = "编队任务 (*.fcgm)|*.fcgm|旧编队任务(*.fcg)|*.fcg"
}; };
if (dialog.ShowDialog() == true) if (dialog.ShowDialog() == true)
{ {
int _startindex = txtStarindex; int _startindex = txtStarindex;
int _endindex = txtendindex; int _endindex = txtendindex;
@ -320,10 +317,13 @@ namespace Plane.FormationCreator.ViewModels
//int task Newtonsoft.Json.Linq.JArray //int task Newtonsoft.Json.Linq.JArray
string extension = Path.GetExtension(dialog.FileName);
bool isMeter = extension == ".fcgm";
if ((txtStarindex == 0) && (txtendindex == 0)) if ((txtStarindex == 0) && (txtendindex == 0))
{ {
_flightTaskManager.ImportTasks(taskinfo, isMeter);
_flightTaskManager.ImportTasks(taskinfo);
} }
else else
{ {
@ -332,7 +332,7 @@ namespace Plane.FormationCreator.ViewModels
_startindex = 1; _startindex = 1;
if (_endindex == 0) if (_endindex == 0)
_endindex = _startindex; _endindex = _startindex;
_flightTaskManager.ImportTasksindex(taskinfo, _startindex, _endindex); _flightTaskManager.ImportTasksindex(taskinfo, _startindex, _endindex, isMeter);
} }

View File

@ -17,6 +17,9 @@
<MenuItem Header="显示所有飞机" <MenuItem Header="显示所有飞机"
Foreground="White" Foreground="White"
Command="{Binding ShowAllCoptersCommand}"/> Command="{Binding ShowAllCoptersCommand}"/>
<MenuItem Header="显示自动编号"
Foreground="White"
Command="{Binding SwitchIdVirtualIdCommand}"/>
</ContextMenu> </ContextMenu>
</UserControl.Resources> </UserControl.Resources>
<Grid> <Grid>
@ -59,6 +62,10 @@
</Rectangle> </Rectangle>
<TextBlock MaxWidth="100" <TextBlock MaxWidth="100"
Text="{Binding Name}" /> Text="{Binding Name}" />
<TextBlock MaxWidth="100"
Margin="2,0,0,0"
Foreground="Red"
Text="{Binding VirtualId}" />
</StackPanel> </StackPanel>
</DataTemplate> </DataTemplate>
</ListBox.ItemTemplate> </ListBox.ItemTemplate>
@ -83,7 +90,7 @@
Margin="0,0,5,0" Margin="0,0,5,0"
Text="10" Text="10"
VerticalContentAlignment="Center" /> VerticalContentAlignment="Center" />
<Button Content="添加虚拟飞机" <Button Content="添加飞机"
VerticalContentAlignment="Center" VerticalContentAlignment="Center"
Command="{Binding AddVirtualCopterCommand}" Command="{Binding AddVirtualCopterCommand}"
CommandParameter="{Binding Text, ElementName=txtVirtualCopterCount}" /> CommandParameter="{Binding Text, ElementName=txtVirtualCopterCount}" />
@ -96,6 +103,9 @@
<Button Content="缺号统计" <Button Content="缺号统计"
Margin="5,0,0,0" Margin="5,0,0,0"
Command="{Binding ShowLackCopterNumsCommand}"/> Command="{Binding ShowLackCopterNumsCommand}"/>
<Button Content="自动编号"
Margin="5,0,0,0"
Command="{Binding AutoLocationNumsCommand}"/>
<Button Content="设置" <Button Content="设置"
Margin="5,0,5,0" Margin="5,0,5,0"
Command="{Binding SetCoptersPutCommand}" /> Command="{Binding SetCoptersPutCommand}" />

View File

@ -92,5 +92,12 @@ namespace Plane.FormationCreator.Views
e.Handled = true; e.Handled = true;
} }
} }
private void ShouAutoID_Click(object sender, RoutedEventArgs e)
{
//lvwDrones.ItemTemplate
}
} }
} }

View File

@ -224,7 +224,8 @@ namespace Plane.FormationCreator.Views
{ {
CopterText.Foreground = new SolidColorBrush(Colors.Red); CopterText.Foreground = new SolidColorBrush(Colors.Red);
} }
else { else
{
CopterText.Foreground = new SolidColorBrush(Colors.White); CopterText.Foreground = new SolidColorBrush(Colors.White);
} }
@ -240,6 +241,18 @@ namespace Plane.FormationCreator.Views
} }
} }
if (Copter.DisplayVirtualId)
{
CopterText.Text = Copter.VirtualId.ToString();
CopterText.Foreground = new SolidColorBrush(Colors.Red);
}
else
{
CopterText.Text = Copter.Name;
CopterText.Foreground = new SolidColorBrush(Colors.White);
}
if (Copter.GetShowLEDAsync()) if (Copter.GetShowLEDAsync())
blackBrush.Color = Colors.White; blackBrush.Color = Colors.White;
else else