飞机LED灯光修改
GPS不精准时,显示飞机位置(用于室内写航点)
This commit is contained in:
parent
c471dc560a
commit
273988c34a
@ -35,6 +35,7 @@ namespace Plane.FormationCreator
|
|||||||
_logger = ServiceLocator.Current.GetInstance<ILogger>();
|
_logger = ServiceLocator.Current.GetInstance<ILogger>();
|
||||||
_copterManager = ServiceLocator.Current.GetInstance<CopterManager>();
|
_copterManager = ServiceLocator.Current.GetInstance<CopterManager>();
|
||||||
_formationController = ServiceLocator.Current.GetInstance<FormationController>();
|
_formationController = ServiceLocator.Current.GetInstance<FormationController>();
|
||||||
|
_mapManager = ServiceLocator.Current.GetInstance<MapManager>();
|
||||||
|
|
||||||
AppDomain.CurrentDomain.AssemblyResolve += (s, e) =>
|
AppDomain.CurrentDomain.AssemblyResolve += (s, e) =>
|
||||||
{
|
{
|
||||||
@ -71,6 +72,7 @@ namespace Plane.FormationCreator
|
|||||||
private ILogger _logger;
|
private ILogger _logger;
|
||||||
private CopterManager _copterManager;
|
private CopterManager _copterManager;
|
||||||
private FormationController _formationController;
|
private FormationController _formationController;
|
||||||
|
private MapManager _mapManager;
|
||||||
|
|
||||||
private Assembly LoadAssembly(string simpleName)
|
private Assembly LoadAssembly(string simpleName)
|
||||||
{
|
{
|
||||||
@ -154,11 +156,14 @@ namespace Plane.FormationCreator
|
|||||||
{
|
{
|
||||||
await Dispatcher.BeginInvoke(new Action(() =>
|
await Dispatcher.BeginInvoke(new Action(() =>
|
||||||
{
|
{
|
||||||
copter = new Copter(Connection, SynchronizationContext.Current)
|
copter = new Copter(Connection, SynchronizationContext.Current, _mapManager.Center.Lat, _mapManager.Center.Lng)
|
||||||
{
|
{
|
||||||
Id = ip,
|
Id = ip,
|
||||||
Name = ip.Substring(ip.LastIndexOf('.') + 1)
|
Name = ip.Substring(ip.LastIndexOf('.') + 1)
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
int _index;
|
int _index;
|
||||||
_index=copters.AddCopter(copter);
|
_index=copters.AddCopter(copter);
|
||||||
copterStatus.Insert(_index,false);
|
copterStatus.Insert(_index,false);
|
||||||
|
@ -15,6 +15,15 @@ namespace Plane.FormationCreator.Formation
|
|||||||
public Copter(IConnection Connection, SynchronizationContext uiThreadContext) : base(Connection, uiThreadContext,false)
|
public Copter(IConnection Connection, SynchronizationContext uiThreadContext) : base(Connection, uiThreadContext,false)
|
||||||
{
|
{
|
||||||
Brush = _brushes[NextBrushIndex()];
|
Brush = _brushes[NextBrushIndex()];
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public Copter(IConnection Connection, SynchronizationContext uiThreadContext, double lat, double lng) : base(Connection, uiThreadContext, false)
|
||||||
|
{
|
||||||
|
Brush = _brushes[NextBrushIndex()];
|
||||||
|
RecordLat = lat;
|
||||||
|
RecordLng = lng;
|
||||||
|
//RaiseLocationChangedIfNeeded();
|
||||||
}
|
}
|
||||||
|
|
||||||
static SolidColorBrush[] _brushes = new[]
|
static SolidColorBrush[] _brushes = new[]
|
||||||
|
@ -674,6 +674,20 @@ namespace Plane.FormationCreator.ViewModels
|
|||||||
|
|
||||||
case FlightTaskType.FlyTo:
|
case FlightTaskType.FlyTo:
|
||||||
|
|
||||||
|
foreach (LEDInfo ledInfo in _flightTaskManager.Tasks[j].SingleCopterInfos[i].LEDInfos)
|
||||||
|
{
|
||||||
|
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);
|
||||||
|
}
|
||||||
missions.Add(Mission.CreateWaypointMission(
|
missions.Add(Mission.CreateWaypointMission(
|
||||||
//5,//_flightTaskManager.Tasks[j].SingleCopterInfos[i].LoiterTime,
|
//5,//_flightTaskManager.Tasks[j].SingleCopterInfos[i].LoiterTime,
|
||||||
//5,// _flightTaskManager.Tasks[j].SingleCopterInfos[i].FlytoTime,
|
//5,// _flightTaskManager.Tasks[j].SingleCopterInfos[i].FlytoTime,
|
||||||
@ -685,20 +699,7 @@ namespace Plane.FormationCreator.ViewModels
|
|||||||
//_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLng,
|
//_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLng,
|
||||||
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetAlt)
|
_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetAlt)
|
||||||
);
|
);
|
||||||
foreach(LEDInfo ledInfo in _flightTaskManager.Tasks[j].SingleCopterInfos[i].LEDInfos)
|
|
||||||
{
|
|
||||||
Color color = (Color)ColorConverter.ConvertFromString("#" + ledInfo.LEDRGB);
|
|
||||||
IMission LEDMission = Mission.CreateLEDControlMission(
|
|
||||||
ledInfo.Delay,
|
|
||||||
ledInfo.LEDMode,
|
|
||||||
ledInfo.LEDRate,
|
|
||||||
0, //ledInfo.LEDTimes,
|
|
||||||
color.R,
|
|
||||||
color.G,
|
|
||||||
color.B
|
|
||||||
);
|
|
||||||
missions.Add(LEDMission);
|
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
case FlightTaskType.Loiter:
|
case FlightTaskType.Loiter:
|
||||||
// missions[missindex++] = Mission.CreateWaypointMission(10,10,_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLat,
|
// missions[missindex++] = Mission.CreateWaypointMission(10,10,_flightTaskManager.Tasks[j].SingleCopterInfos[i].TargetLat,
|
||||||
|
@ -95,6 +95,17 @@ namespace Plane.FormationCreator.Views
|
|||||||
try
|
try
|
||||||
{
|
{
|
||||||
var location = new Location(Copter.Latitude, Copter.Longitude, Copter.Altitude);
|
var location = new Location(Copter.Latitude, Copter.Longitude, Copter.Altitude);
|
||||||
|
|
||||||
|
if (this.Dot != null )
|
||||||
|
{
|
||||||
|
if (Copter is PLCopter && !Copter.IsGpsAccurate)
|
||||||
|
this.Dot.Fill = new SolidColorBrush(Color.FromRgb(0, 0, 0));
|
||||||
|
else
|
||||||
|
this.Dot.Fill = _brush;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
Point center = _map.LocationToViewportPoint(location);
|
Point center = _map.LocationToViewportPoint(location);
|
||||||
bool locationUpdated = true;
|
bool locationUpdated = true;
|
||||||
SolidColorBrush blackBrush = new SolidColorBrush();
|
SolidColorBrush blackBrush = new SolidColorBrush();
|
||||||
@ -114,6 +125,7 @@ namespace Plane.FormationCreator.Views
|
|||||||
Dot.Points.Add(new Point(-COPTER_RADIUS * 2 / 3, COPTER_RADIUS));
|
Dot.Points.Add(new Point(-COPTER_RADIUS * 2 / 3, COPTER_RADIUS));
|
||||||
Dot.Points.Add(new Point(COPTER_RADIUS * 2 / 3, COPTER_RADIUS));
|
Dot.Points.Add(new Point(COPTER_RADIUS * 2 / 3, COPTER_RADIUS));
|
||||||
|
|
||||||
|
|
||||||
Dot.Fill = _brush; // new SolidColorBrush(Color.FromArgb(200, 0, 122, 204));
|
Dot.Fill = _brush; // new SolidColorBrush(Color.FromArgb(200, 0, 122, 204));
|
||||||
Dot.StrokeThickness = 1;
|
Dot.StrokeThickness = 1;
|
||||||
Dot.Width = COPTER_RADIUS * 2;
|
Dot.Width = COPTER_RADIUS * 2;
|
||||||
@ -218,6 +230,10 @@ namespace Plane.FormationCreator.Views
|
|||||||
public void AddWaypoint(Location location, FlightTaskType type)
|
public void AddWaypoint(Location location, FlightTaskType type)
|
||||||
{
|
{
|
||||||
// Add waypoint.
|
// Add waypoint.
|
||||||
|
/*
|
||||||
|
if (!Copter.IsGpsAccurate && !(Copter is FakeCopter))
|
||||||
|
location = _map.Center;
|
||||||
|
*/
|
||||||
var wp = new Ellipse
|
var wp = new Ellipse
|
||||||
{
|
{
|
||||||
Tag = WAYPOINT_TAG,
|
Tag = WAYPOINT_TAG,
|
||||||
|
@ -249,6 +249,7 @@
|
|||||||
|
|
||||||
<TextBlock Text="时间" Margin="12,0,0,0" VerticalAlignment="Center"></TextBlock>
|
<TextBlock Text="时间" Margin="12,0,0,0" VerticalAlignment="Center"></TextBlock>
|
||||||
<TextBox MinWidth="40" MaxWidth="50" Margin="5,0,0,0"
|
<TextBox MinWidth="40" MaxWidth="50" Margin="5,0,0,0"
|
||||||
|
ToolTip="单位:秒,最小设置0.1秒"
|
||||||
Text="{Binding Delay, UpdateSourceTrigger=PropertyChanged}" />
|
Text="{Binding Delay, UpdateSourceTrigger=PropertyChanged}" />
|
||||||
|
|
||||||
<TextBlock Text="频率" Margin="12,0,0,0" VerticalAlignment="Center"></TextBlock>
|
<TextBlock Text="频率" Margin="12,0,0,0" VerticalAlignment="Center"></TextBlock>
|
||||||
|
@ -7,7 +7,7 @@
|
|||||||
xmlns:ed="http://schemas.microsoft.com/expression/2010/drawing"
|
xmlns:ed="http://schemas.microsoft.com/expression/2010/drawing"
|
||||||
x:Class="Plane.FormationCreator.Views.TaskBarView"
|
x:Class="Plane.FormationCreator.Views.TaskBarView"
|
||||||
mc:Ignorable="d"
|
mc:Ignorable="d"
|
||||||
d:DesignHeight="40"
|
d:DesignHeight="156.968"
|
||||||
d:DesignWidth="500">
|
d:DesignWidth="500">
|
||||||
<Grid>
|
<Grid>
|
||||||
<Grid.ColumnDefinitions>
|
<Grid.ColumnDefinitions>
|
||||||
@ -112,7 +112,63 @@
|
|||||||
</ItemsControl.ItemTemplate>
|
</ItemsControl.ItemTemplate>
|
||||||
</ItemsControl>
|
</ItemsControl>
|
||||||
|
|
||||||
<StackPanel Grid.Column="2"
|
<Grid Grid.Column="2">
|
||||||
|
<Grid.RowDefinitions>
|
||||||
|
<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>
|
||||||
|
<TabControl
|
||||||
|
DataContext="{Binding FlightTaskManager.SelectedTask}"
|
||||||
|
SelectedIndex="{Binding TaskTypeIndex}">
|
||||||
|
|
||||||
|
<TabItem Header="航点">
|
||||||
|
<Grid>
|
||||||
|
<Grid.RowDefinitions>
|
||||||
|
<RowDefinition />
|
||||||
|
<RowDefinition />
|
||||||
|
</Grid.RowDefinitions>
|
||||||
|
<Grid.ColumnDefinitions>
|
||||||
|
<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>
|
||||||
|
</TabItem>
|
||||||
|
|
||||||
|
<TabItem Header="转向">
|
||||||
|
</TabItem>
|
||||||
|
|
||||||
|
<TabItem Header="画圈">
|
||||||
|
</TabItem>
|
||||||
|
|
||||||
|
<TabItem Header="悬停">
|
||||||
|
</TabItem>
|
||||||
|
|
||||||
|
<TabItem Header="返航">
|
||||||
|
</TabItem>
|
||||||
|
</TabControl>
|
||||||
|
</StackPanel>
|
||||||
|
<StackPanel Grid.Row="1"
|
||||||
Orientation="Horizontal"
|
Orientation="Horizontal"
|
||||||
VerticalAlignment="Bottom">
|
VerticalAlignment="Bottom">
|
||||||
<Button Content="添加任务"
|
<Button Content="添加任务"
|
||||||
@ -133,6 +189,8 @@
|
|||||||
<!--<Button Content="保存" />
|
<!--<Button Content="保存" />
|
||||||
<Button Content="取消" />-->
|
<Button Content="取消" />-->
|
||||||
</StackPanel>
|
</StackPanel>
|
||||||
|
</Grid>
|
||||||
|
|
||||||
|
|
||||||
</Grid>
|
</Grid>
|
||||||
</UserControl>
|
</UserControl>
|
||||||
|
Loading…
Reference in New Issue
Block a user