间隔选中

通信模式测试的一些修改(目前未启用)
This commit is contained in:
zxd 2018-08-04 17:06:22 +08:00
parent cb188feb48
commit b427d32b44
6 changed files with 158 additions and 62 deletions

View File

@ -92,18 +92,38 @@ namespace Plane.FormationCreator.ViewModels
} }
} }
// private ICommand _WriteCommand; // private ICommand _WriteCommand;
// public ICommand WriteCommand // public ICommand WriteCommand
// { // {
// get // get
// { // {
// return _WriteCommand ?? (_WriteCommand = new RelayCommand(async () => // return _WriteCommand ?? (_WriteCommand = new RelayCommand(async () =>
// { // {
// await WriteCommandAsync(); // await WriteCommandAsync();
// } // }
// )); // ));
// } // }
// } // }
private ICommand _CloseCommand;
public ICommand CloseCommand
{
get
{
return _CloseCommand ?? (_CloseCommand = new RelayCommand(() =>
{
commModule.Close();
}
));
}
}
private int _CopterNum;
public int CopterNum
{
get { return _CopterNum; }
set { Set(nameof(CopterNum), ref _CopterNum, value); }
}
private ICommand _WriteIdCommand; private ICommand _WriteIdCommand;
public ICommand WriteIdCommand public ICommand WriteIdCommand
@ -112,7 +132,7 @@ namespace Plane.FormationCreator.ViewModels
{ {
return _WriteIdCommand ?? (_WriteIdCommand = new RelayCommand(async () => return _WriteIdCommand ?? (_WriteIdCommand = new RelayCommand(async () =>
{ {
await WriteIdCommandAsync(); await WriteIdCommandAsync(CopterNum);
} }
)); ));
} }
@ -143,22 +163,27 @@ namespace Plane.FormationCreator.ViewModels
///写航线开始 ///写航线开始
//var missions = new IMission[taskcount]; //不要起飞任务但增加一个起飞后低空航点,见起飞任务,再增加一个降落低空航点,见降落部分 //var missions = new IMission[taskcount]; //不要起飞任务但增加一个起飞后低空航点,见起飞任务,再增加一个降落低空航点,见降落部分
var missions = new List<IMission>(); var missions = new List<IMission>();
missions.Add(PLCopter.PRE_TAKE_OFF_MISSION);
int missindex = 0; int missindex = 0;
ICopter copter = _copterManager.Copters[i]; ICopter copter = _copterManager.Copters[i];
if (copter is PLCopter) //if (copter is PLCopter)
{ {
for (int j = 0; j < _flightTaskManager.Tasks.Count; j++) for (int j = 0; j < _flightTaskManager.Tasks.Count; j++)
{ {
switch (_flightTaskManager.Tasks[j].TaskType) switch (_flightTaskManager.Tasks[j].TaskType)
{ {
case FlightTaskType.TakeOff: case FlightTaskType.TakeOff:
//计算起飞需要的时间,5秒是上升加速和最后稳定时间 //计算起飞需要的时间,5秒是上升加速和最后稳定时间
int takeofftime = (int)(_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetAlt / 2.5 + 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( missions.Add(Mission.CreateTakeoffMission(
1,//1, _flightTaskManager.Tasks[j].SingleCopterInfos[i].TakeOffWaitTime,
5,//takeofftime, _flightTaskManager.Tasks[j].TakeOffTime,
_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetLat - _flightTaskManager.OriginLat, _flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetLat - _flightTaskManager.OriginLat,
_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetLng - _flightTaskManager.OriginLng, _flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetLng - _flightTaskManager.OriginLng,
_flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetAlt) _flightTaskManager.Tasks[j + 1].SingleCopterInfos[i].TargetAlt)
@ -169,42 +194,44 @@ namespace Plane.FormationCreator.ViewModels
break; break;
case FlightTaskType.FlyTo: 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); Lat = 90;
IMission LEDMission = Mission.CreateLEDControlMission( Lng = 180;
(int)(ledInfo.Delay * 10),
ledInfo.LEDMode,
ledInfo.LEDRate,
0, //ledInfo.LEDTimes,
color.R,
color.G,
color.B
);
missions.Add(LEDMission);
} }
missions.Add(Mission.CreateWaypointMission( 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].LoiterTime,
_flightTaskManager.Tasks[j].FlytoTime, _flightTaskManager.Tasks[j].FlytoTime,
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLat - _flightTaskManager.OriginLat, Lat,
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLng - _flightTaskManager.OriginLng, Lng,
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetAlt) _flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetAlt)
); );
break; break;
case FlightTaskType.Loiter: case FlightTaskType.Loiter:
// missions[missindex++] = Mission.CreateWaypointMission(10,10,_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLat,
// _flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLng, _flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetAlt);
break; break;
case FlightTaskType.ReturnToLand: case FlightTaskType.ReturnToLand:
//降落低空航点
// missions[missindex++] = Mission.CreateWaypointMission(_flightTaskManager.Tasks[j - 1].SingleCopterInfos[i].TargetLat,
// _flightTaskManager.Tasks[j - 1].SingleCopterInfos[i].TargetLng, 3);
//返航
missions.Add(Mission.CreateReturnToLaunchMission()); missions.Add(Mission.CreateReturnToLaunchMission());
break; break;
case FlightTaskType.Land: case FlightTaskType.Land:
missions.Add(Mission.CreateLandMission(5)); missions.AddRange(CreateLEDMissions(_flightTaskManager.Tasks[j].SingleCopterInfos[i].LEDInfos));
missions.Add(Mission.CreateLandMission(
_flightTaskManager.Tasks[j].SingleCopterInfos[i].LandWaitTime)
);
break; break;
default: default:
break; break;
@ -231,10 +258,30 @@ namespace Plane.FormationCreator.ViewModels
} }
} }
private List<IMission> CreateLEDMissions(IEnumerable<LEDInfo> LEDInfos)
private async Task WriteIdCommandAsync()
{ {
await commModule.GeneratePacketAsync(3, (byte)Protocols.MavComm.COMMANDTYPE4); 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;
}
private async Task WriteIdCommandAsync(int num)
{
await commModule.GeneratePacketAsync((short)num, (byte)Protocols.MavComm.COMMANDTYPE4);
} }
@ -254,9 +301,11 @@ namespace Plane.FormationCreator.ViewModels
var req = new MAVLink.mavlink_mission_item_t(); var req = new MAVLink.mavlink_mission_item_t();
PLCopter plCopter = (PLCopter)copter; //PLCopter plCopter = (PLCopter)copter;
req.target_system = plCopter._internalCopter.sysid; //req.target_system = plCopter._internalCopter.sysid;
req.target_component = plCopter._internalCopter.compid; //req.target_component = plCopter._internalCopter.compid;
req.target_system = 1;
req.target_component = 1;
req.command = (byte)mission.Command; req.command = (byte)mission.Command;
@ -297,6 +346,11 @@ namespace Plane.FormationCreator.ViewModels
await commModule.ConnectAsync(); await commModule.ConnectAsync();
} }
private async Task DisConnetAsync()
{
await Task.Delay(20).ConfigureAwait(false);
}
private Action _closeWindowCallback; private Action _closeWindowCallback;
public void SetCloseWindowAction(Action closeWindowAction) public void SetCloseWindowAction(Action closeWindowAction)
{ {

View File

@ -624,10 +624,12 @@ namespace Plane.FormationCreator.ViewModels
{ {
return _ConnectCommand ?? (_ConnectCommand = new RelayCommand(async () => return _ConnectCommand ?? (_ConnectCommand = new RelayCommand(async () =>
{ {
//await ConnectAsync();
await Task.WhenAll(_copterManager.AcceptingControlCopters.Select(async copter => await Task.WhenAll(_copterManager.AcceptingControlCopters.Select(async copter =>
{ {
//await commModule.ConnectAsync();
await copter.ConnectAsync(); await copter.ConnectAsync();
await copter.GetCopterDataAsync(); //await copter.GetCopterDataAsync();
})); }));
})); }));
} }

View File

@ -81,6 +81,36 @@ namespace Plane.FormationCreator.ViewModels
set { Set(nameof(Communinfo), ref _Communinfo, value); } set { Set(nameof(Communinfo), ref _Communinfo, value); }
} }
private int _IntervalNum;
public int IntervalNum
{
get { return _IntervalNum; }
set { Set(nameof(IntervalNum), ref _IntervalNum, value); }
}
private ICommand _IntervalSelectCoptersCommand;
public ICommand IntervalSelectCoptersCommand
{
get
{
return _IntervalSelectCoptersCommand ?? (_IntervalSelectCoptersCommand = new RelayCommand(() =>
{
if (_copterManager.AcceptingControlCopters.Count() == 0 || IntervalNum == 0)
return;
ICopter copter = _copterManager.AcceptingControlCopters.FirstOrDefault();
_copterManager.Select(null);
int index = _copterManager.Copters.IndexOf(copter);
_copterManager.shiftkeydown = true;
for (; index < _copterManager.Copters.Count; index += IntervalNum + 1)
{
_copterManager.Select(_copterManager.Copters[index]);
}
_copterManager.shiftkeydown = false;
}));
}
}
private ICommand _AddVirtualCopterCommand; private ICommand _AddVirtualCopterCommand;
public ICommand AddVirtualCopterCommand public ICommand AddVirtualCopterCommand

View File

@ -124,9 +124,11 @@
HorizontalAlignment="Center" HorizontalAlignment="Center"
Grid.Row="2" Grid.Row="2"
Grid.ColumnSpan="3"> Grid.ColumnSpan="3">
<Button Content="设置20台" Margin="10" Command="{Binding Path=SendCommand}" /> <Button Content="关闭TCP" Margin="5" Command="{Binding CloseCommand}"/>
<Button Content="写入航点" Margin="10" Command="{Binding Path=CommWriteMissionCommand}" /> <Button Content="设置20台" Margin="5" Command="{Binding Path=SendCommand}" />
<Button Content="广播编号3" Margin="10" Command="{Binding Path=WriteIdCommand}" /> <Button Content="写入航点" Margin="5" Command="{Binding Path=CommWriteMissionCommand}" />
<Button Content="广播编号" Margin="5,5,0,5" Command="{Binding Path=WriteIdCommand}" />
<TextBox Margin="2,5,5,5" Width="30" Text="{Binding CopterNum}"></TextBox>
</StackPanel> </StackPanel>
</Grid> </Grid>

View File

@ -1,10 +1,11 @@
<UserControl x:Class="Plane.FormationCreator.Views.CopterListView" <UserControl
xmlns="http://schemas.microsoft.com/winfx/2006/xaml/presentation" xmlns="http://schemas.microsoft.com/winfx/2006/xaml/presentation"
xmlns:x="http://schemas.microsoft.com/winfx/2006/xaml" xmlns:x="http://schemas.microsoft.com/winfx/2006/xaml"
xmlns:mc="http://schemas.openxmlformats.org/markup-compatibility/2006" xmlns:mc="http://schemas.openxmlformats.org/markup-compatibility/2006"
xmlns:d="http://schemas.microsoft.com/expression/blend/2008" xmlns:d="http://schemas.microsoft.com/expression/blend/2008"
xmlns:local="clr-namespace:Plane.FormationCreator.Views" xmlns:local="clr-namespace:Plane.FormationCreator.Views"
xmlns:m="clr-namespace:Plane.FormationCreator.Formation" xmlns:m="clr-namespace:Plane.FormationCreator.Formation"
xmlns:ControlzEx="clr-namespace:ControlzEx;assembly=MahApps.Metro" x:Class="Plane.FormationCreator.Views.CopterListView"
mc:Ignorable="d" mc:Ignorable="d"
d:DesignHeight="600" d:DesignHeight="600"
d:DesignWidth="300"> d:DesignWidth="300">
@ -13,11 +14,12 @@
<Grid.RowDefinitions> <Grid.RowDefinitions>
<RowDefinition /> <RowDefinition />
<RowDefinition Height="Auto" /> <RowDefinition Height="Auto" />
<RowDefinition Height="Auto" />
</Grid.RowDefinitions> </Grid.RowDefinitions>
<ListBox x:Name="lvwDrones" <ListBox x:Name="lvwDrones"
ItemsSource="{Binding Path=CopterManager.Copters}" ItemsSource="{Binding CopterManager.Copters}"
SelectedItem="{Binding Path=SelectedCopter}" SelectedItem="{Binding SelectedCopter}"
Background="Transparent" Background="Transparent"
BorderThickness="0" BorderThickness="0"
SelectionMode="Extended" SelectionMode="Extended"
@ -32,9 +34,8 @@
<DataTemplate> <DataTemplate>
<StackPanel Orientation="Horizontal"> <StackPanel Orientation="Horizontal">
<CheckBox Width="20" <CheckBox Width="20"
IsChecked="{Binding Path=IsConnected, Mode=OneWay}" IsChecked="{Binding IsConnected, Mode=OneWay}"
IsEnabled="False"> IsEnabled="False"/>
</CheckBox>
<Rectangle Width="15" <Rectangle Width="15"
Height="15" Height="15"
Margin="3,0"> Margin="3,0">
@ -46,31 +47,38 @@
</Rectangle.Fill> </Rectangle.Fill>
</Rectangle> </Rectangle>
<TextBlock MaxWidth="100" <TextBlock MaxWidth="100"
Text="{Binding Path=Name}" /> Text="{Binding Name}" />
</StackPanel> </StackPanel>
</DataTemplate> </DataTemplate>
</ListBox.ItemTemplate> </ListBox.ItemTemplate>
</ListBox> </ListBox>
<StackPanel Grid.Row="1" <StackPanel Grid.Row="1" Margin="0,0,0,5"
Orientation="Horizontal">
<Button Content="间隔选中" Command="{Binding IntervalSelectCoptersCommand}"/>
<TextBlock Text="间隔数量" Margin="5,5,0,0"/>
<TextBox Width="30" Margin="5,0,0,0" Text="{Binding IntervalNum}"/>
</StackPanel>
<StackPanel Grid.Row="2"
Orientation="Horizontal"> Orientation="Horizontal">
<TextBox x:Name="txtVirtualCopterCount" <TextBox x:Name="txtVirtualCopterCount"
Width="35" Width="35"
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 ElementName=txtVirtualCopterCount, Path=Text}" /> CommandParameter="{Binding Text, ElementName=txtVirtualCopterCount}" />
<Button Content="清除" <Button Content="清除"
Margin="5,0,5,0" Margin="5,0,5,0"
Command="{Binding ClearCoptersCommand}" /> Command="{Binding ClearCoptersCommand}" />
<TextBlock Text="总数" <TextBlock Text="总数"
Margin="5,5,0,0"/> Margin="5,5,0,0"/>
<TextBlock Text="{Binding Path=CopterManager.Copters.Count}" <TextBlock Text="{Binding CopterManager.Copters.Count}"
Margin="0,5,0,0"/> Margin="0,5,0,0"/>
<TextBlock Text="{Binding Path=Communinfo}" <TextBlock Text="{Binding Communinfo}"
Margin="5,5,0,0"/> Margin="5,5,0,0"/>
</StackPanel> </StackPanel>

View File

@ -29,7 +29,7 @@
</StackPanel.Resources> </StackPanel.Resources>
<TextBlock Margin="5" Text="起飞任务"/> <TextBlock Margin="5" Text="起飞任务"/>
<Separator/> <Separator/>
<!-- <StackPanel> <StackPanel>
<TextBlock Text="起飞数量:" Margin="5,10,5,0" /> <TextBlock Text="起飞数量:" Margin="5,10,5,0" />
<TextBox x:Name="txttakeoff" <TextBox x:Name="txttakeoff"
@ -37,7 +37,7 @@
Margin="0,10,5,0" Margin="0,10,5,0"
VerticalContentAlignment="Center" VerticalContentAlignment="Center"
Text="{Binding FlightTaskManager.TakeOffNumAttr, UpdateSourceTrigger=PropertyChanged}"/> Text="{Binding FlightTaskManager.TakeOffNumAttr, UpdateSourceTrigger=PropertyChanged}"/>
</StackPanel>--> </StackPanel>
<Separator /> <Separator />
<Grid DataContext="{Binding FlightTaskManager.SelectedTask.ModifyingSingleCopterInfo}" <Grid DataContext="{Binding FlightTaskManager.SelectedTask.ModifyingSingleCopterInfo}"