APM Planner 1.1.12

touch up geofence.
remove reset tab
This commit is contained in:
Michael Oborne 2011-12-21 08:22:28 +08:00
parent e372dcc7a7
commit ace823fccf
5 changed files with 247 additions and 67 deletions

View File

@ -121,12 +121,14 @@
this.geoFenceToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.geoFenceToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.GeoFenceuploadToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.GeoFenceuploadToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.GeoFencedownloadToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.GeoFencedownloadToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.setReturnLocationToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.loadFromFileToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.trackBar1 = new ArdupilotMega.MyTrackBar(); this.trackBar1 = new ArdupilotMega.MyTrackBar();
this.label11 = new System.Windows.Forms.Label(); this.label11 = new System.Windows.Forms.Label();
this.panelBASE = new System.Windows.Forms.Panel(); this.panelBASE = new System.Windows.Forms.Panel();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.timer1 = new System.Windows.Forms.Timer(this.components); this.timer1 = new System.Windows.Forms.Timer(this.components);
this.setReturnLocationToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.saveToFileToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
((System.ComponentModel.ISupportInitialize)(this.Commands)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.Commands)).BeginInit();
this.panel5.SuspendLayout(); this.panel5.SuspendLayout();
this.panel1.SuspendLayout(); this.panel1.SuspendLayout();
@ -833,7 +835,9 @@
this.geoFenceToolStripMenuItem.DropDownItems.AddRange(new System.Windows.Forms.ToolStripItem[] { this.geoFenceToolStripMenuItem.DropDownItems.AddRange(new System.Windows.Forms.ToolStripItem[] {
this.GeoFenceuploadToolStripMenuItem, this.GeoFenceuploadToolStripMenuItem,
this.GeoFencedownloadToolStripMenuItem, this.GeoFencedownloadToolStripMenuItem,
this.setReturnLocationToolStripMenuItem}); this.setReturnLocationToolStripMenuItem,
this.loadFromFileToolStripMenuItem,
this.saveToFileToolStripMenuItem});
this.geoFenceToolStripMenuItem.Name = "geoFenceToolStripMenuItem"; this.geoFenceToolStripMenuItem.Name = "geoFenceToolStripMenuItem";
resources.ApplyResources(this.geoFenceToolStripMenuItem, "geoFenceToolStripMenuItem"); resources.ApplyResources(this.geoFenceToolStripMenuItem, "geoFenceToolStripMenuItem");
// //
@ -849,6 +853,18 @@
resources.ApplyResources(this.GeoFencedownloadToolStripMenuItem, "GeoFencedownloadToolStripMenuItem"); resources.ApplyResources(this.GeoFencedownloadToolStripMenuItem, "GeoFencedownloadToolStripMenuItem");
this.GeoFencedownloadToolStripMenuItem.Click += new System.EventHandler(this.GeoFencedownloadToolStripMenuItem_Click); this.GeoFencedownloadToolStripMenuItem.Click += new System.EventHandler(this.GeoFencedownloadToolStripMenuItem_Click);
// //
// setReturnLocationToolStripMenuItem
//
this.setReturnLocationToolStripMenuItem.Name = "setReturnLocationToolStripMenuItem";
resources.ApplyResources(this.setReturnLocationToolStripMenuItem, "setReturnLocationToolStripMenuItem");
this.setReturnLocationToolStripMenuItem.Click += new System.EventHandler(this.setReturnLocationToolStripMenuItem_Click);
//
// loadFromFileToolStripMenuItem
//
this.loadFromFileToolStripMenuItem.Name = "loadFromFileToolStripMenuItem";
resources.ApplyResources(this.loadFromFileToolStripMenuItem, "loadFromFileToolStripMenuItem");
this.loadFromFileToolStripMenuItem.Click += new System.EventHandler(this.loadFromFileToolStripMenuItem_Click);
//
// trackBar1 // trackBar1
// //
resources.ApplyResources(this.trackBar1, "trackBar1"); resources.ApplyResources(this.trackBar1, "trackBar1");
@ -885,11 +901,11 @@
this.timer1.Interval = 1000; this.timer1.Interval = 1000;
this.timer1.Tick += new System.EventHandler(this.timer1_Tick); this.timer1.Tick += new System.EventHandler(this.timer1_Tick);
// //
// setReturnLocationToolStripMenuItem // saveToFileToolStripMenuItem
// //
this.setReturnLocationToolStripMenuItem.Name = "setReturnLocationToolStripMenuItem"; this.saveToFileToolStripMenuItem.Name = "saveToFileToolStripMenuItem";
resources.ApplyResources(this.setReturnLocationToolStripMenuItem, "setReturnLocationToolStripMenuItem"); resources.ApplyResources(this.saveToFileToolStripMenuItem, "saveToFileToolStripMenuItem");
this.setReturnLocationToolStripMenuItem.Click += new System.EventHandler(this.setReturnLocationToolStripMenuItem_Click); this.saveToFileToolStripMenuItem.Click += new System.EventHandler(this.saveToFileToolStripMenuItem_Click);
// //
// FlightPlanner // FlightPlanner
// //
@ -1009,5 +1025,7 @@
private System.Windows.Forms.ToolStripMenuItem GeoFenceuploadToolStripMenuItem; private System.Windows.Forms.ToolStripMenuItem GeoFenceuploadToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem GeoFencedownloadToolStripMenuItem; private System.Windows.Forms.ToolStripMenuItem GeoFencedownloadToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem setReturnLocationToolStripMenuItem; private System.Windows.Forms.ToolStripMenuItem setReturnLocationToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem loadFromFileToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem saveToFileToolStripMenuItem;
} }
} }

View File

@ -660,17 +660,22 @@ namespace ArdupilotMega.GCSViews
isonline = false; isonline = false;
} }
// setup geofence
List<PointLatLng> polygonPoints = new List<PointLatLng>(); List<PointLatLng> polygonPoints = new List<PointLatLng>();
gf = new GMapPolygon(polygonPoints, "geofence"); gf = new GMapPolygon(polygonPoints, "geofence");
gf.Stroke = new Pen(Color.Pink, 5); gf.Stroke = new Pen(Color.Pink, 5);
//setup drawnpolgon
List<PointLatLng> polygonPoints2 = new List<PointLatLng>();
drawnpolygon = new GMapPolygon(polygonPoints2, "drawnpoly");
drawnpolygon.Stroke = new Pen(Color.Red, 2);
updateCMDParams(); updateCMDParams();
// mono // mono
panelMap.Dock = DockStyle.None; panelMap.Dock = DockStyle.None;
panelMap.Dock = DockStyle.Fill; panelMap.Dock = DockStyle.Fill;
panelMap_Resize(null,null); panelMap_Resize(null, null);
writeKML(); writeKML();
} }
@ -701,45 +706,46 @@ namespace ArdupilotMega.GCSViews
//Console.WriteLine("feat " + feat.GetType()); //Console.WriteLine("feat " + feat.GetType());
//processKML((Element)feat); //processKML((Element)feat);
} }
} else }
if (folder != null ) else
{ if (folder != null)
foreach (Feature feat in folder.Features)
{ {
//Console.WriteLine("feat "+feat.GetType()); foreach (Feature feat in folder.Features)
//processKML(feat); {
//Console.WriteLine("feat "+feat.GetType());
//processKML(feat);
}
} }
} else if (pm != null)
else if (pm != null)
{
}
else if (polygon != null)
{
GMapPolygon kmlpolygon = new GMapPolygon(new List<PointLatLng>(), "kmlpolygon");
kmlpolygon.Stroke.Color = Color.Purple;
foreach (var loc in polygon.OuterBoundary.LinearRing.Coordinates)
{ {
kmlpolygon.Points.Add(new PointLatLng(loc.Latitude, loc.Longitude));
} }
else if (polygon != null)
kmlpolygons.Polygons.Add(kmlpolygon);
}
else if (ls != null)
{
GMapRoute kmlroute = new GMapRoute(new List<PointLatLng>(), "kmlroute");
kmlroute.Stroke.Color = Color.Purple;
foreach (var loc in ls.Coordinates)
{ {
kmlroute.Points.Add(new PointLatLng(loc.Latitude, loc.Longitude)); GMapPolygon kmlpolygon = new GMapPolygon(new List<PointLatLng>(), "kmlpolygon");
}
kmlpolygons.Routes.Add(kmlroute); kmlpolygon.Stroke.Color = Color.Purple;
}
foreach (var loc in polygon.OuterBoundary.LinearRing.Coordinates)
{
kmlpolygon.Points.Add(new PointLatLng(loc.Latitude, loc.Longitude));
}
kmlpolygons.Polygons.Add(kmlpolygon);
}
else if (ls != null)
{
GMapRoute kmlroute = new GMapRoute(new List<PointLatLng>(), "kmlroute");
kmlroute.Stroke.Color = Color.Purple;
foreach (var loc in ls.Coordinates)
{
kmlroute.Points.Add(new PointLatLng(loc.Latitude, loc.Longitude));
}
kmlpolygons.Routes.Add(kmlroute);
}
} }
private void ChangeColumnHeader(string command) private void ChangeColumnHeader(string command)
@ -791,7 +797,7 @@ namespace ArdupilotMega.GCSViews
if (tcell.Value == null) if (tcell.Value == null)
tcell.Value = "0"; tcell.Value = "0";
} }
} }
DataGridViewComboBoxCell cell = Commands.Rows[e.RowIndex].Cells[Command.Index] as DataGridViewComboBoxCell; DataGridViewComboBoxCell cell = Commands.Rows[e.RowIndex].Cells[Command.Index] as DataGridViewComboBoxCell;
if (cell.Value == null) if (cell.Value == null)
@ -985,8 +991,8 @@ namespace ArdupilotMega.GCSViews
{ {
if (Commands.Rows[a].HeaderCell.Value == null) if (Commands.Rows[a].HeaderCell.Value == null)
{ {
Commands.Rows[a].HeaderCell.Style.Alignment = DataGridViewContentAlignment.MiddleCenter; Commands.Rows[a].HeaderCell.Style.Alignment = DataGridViewContentAlignment.MiddleCenter;
Commands.Rows[a].HeaderCell.Value = (a + 1).ToString(); Commands.Rows[a].HeaderCell.Value = (a + 1).ToString();
} }
// skip rows with the correct number // skip rows with the correct number
string rowno = Commands.Rows[a].HeaderCell.Value.ToString(); string rowno = Commands.Rows[a].HeaderCell.Value.ToString();
@ -2175,7 +2181,7 @@ namespace ArdupilotMega.GCSViews
} }
private void comboBoxMapType_SelectedValueChanged(object sender, EventArgs e) private void comboBoxMapType_SelectedValueChanged(object sender, EventArgs e)
{ {
MainMap.MapType = (MapType)comboBoxMapType.SelectedItem; MainMap.MapType = (MapType)comboBoxMapType.SelectedItem;
FlightData.mymap.MapType = (MapType)comboBoxMapType.SelectedItem; FlightData.mymap.MapType = (MapType)comboBoxMapType.SelectedItem;
MainV2.config["MapType"] = comboBoxMapType.Text; MainV2.config["MapType"] = comboBoxMapType.Text;
@ -2701,7 +2707,7 @@ namespace ArdupilotMega.GCSViews
{ {
if (polygongridmode == false) if (polygongridmode == false)
{ {
MessageBox.Show("You will remain in polygon mode until you clear the polygon or create a grid"); MessageBox.Show("You will remain in polygon mode until you clear the polygon or create a grid/upload a fence");
} }
polygongridmode = true; polygongridmode = true;
@ -2709,8 +2715,7 @@ namespace ArdupilotMega.GCSViews
List<PointLatLng> polygonPoints = new List<PointLatLng>(); List<PointLatLng> polygonPoints = new List<PointLatLng>();
if (drawnpolygons.Polygons.Count == 0) if (drawnpolygons.Polygons.Count == 0)
{ {
drawnpolygon = new GMapPolygon(polygonPoints, "drawnpoly"); drawnpolygon.Points.Clear();
drawnpolygon.Stroke = new Pen(Color.Red, 2);
drawnpolygons.Polygons.Add(drawnpolygon); drawnpolygons.Polygons.Add(drawnpolygon);
} }
drawnpolygon.Points.Add(new PointLatLng(start.Lat, start.Lng)); drawnpolygon.Points.Add(new PointLatLng(start.Lat, start.Lng));
@ -2869,8 +2874,8 @@ namespace ArdupilotMega.GCSViews
{ {
// this is a mono fix for the zoom bar // this is a mono fix for the zoom bar
//Console.WriteLine("panelmap "+panelMap.Size.ToString()); //Console.WriteLine("panelmap "+panelMap.Size.ToString());
MainMap.Size = new Size(panelMap.Size.Width - 50,panelMap.Size.Height); MainMap.Size = new Size(panelMap.Size.Width - 50, panelMap.Size.Height);
trackBar1.Location = new System.Drawing.Point(panelMap.Size.Width - 50,trackBar1.Location.Y); trackBar1.Location = new System.Drawing.Point(panelMap.Size.Width - 50, trackBar1.Location.Y);
trackBar1.Size = new System.Drawing.Size(trackBar1.Size.Width, panelMap.Size.Height - trackBar1.Location.Y); trackBar1.Size = new System.Drawing.Size(trackBar1.Size.Width, panelMap.Size.Height - trackBar1.Location.Y);
label11.Location = new System.Drawing.Point(panelMap.Size.Width - 50, label11.Location.Y); label11.Location = new System.Drawing.Point(panelMap.Size.Width - 50, label11.Location.Y);
} }
@ -2918,7 +2923,7 @@ namespace ArdupilotMega.GCSViews
var parser = new SharpKml.Base.Parser(); var parser = new SharpKml.Base.Parser();
parser.ElementAdded += parser_ElementAdded; parser.ElementAdded += parser_ElementAdded;
parser.ParseString(kml,true); parser.ParseString(kml, true);
if (DialogResult.Yes == MessageBox.Show("Do you want to load this into the flight data screen?", "Load data", MessageBoxButtons.YesNo)) if (DialogResult.Yes == MessageBox.Show("Do you want to load this into the flight data screen?", "Load data", MessageBoxButtons.YesNo))
{ {
@ -2989,6 +2994,17 @@ namespace ArdupilotMega.GCSViews
return; return;
} }
// check if return is inside polygon
List<PointLatLng> plll = new List<PointLatLng>(drawnpolygon.Points.ToArray());
// close it
plll.Add(plll[0]);
// check it
if (!pnpoly(plll.ToArray(), start.Lat, start.Lng))
{
MessageBox.Show("Your return location is outside the polygon");
return;
}
string minalts = (int.Parse(MainV2.comPort.param["FENCE_MINALT"].ToString()) * MainV2.cs.multiplierdist).ToString("0"); string minalts = (int.Parse(MainV2.comPort.param["FENCE_MINALT"].ToString()) * MainV2.cs.multiplierdist).ToString("0");
Common.InputBox("Min Alt", "Box Minimum Altitude?", ref minalts); Common.InputBox("Min Alt", "Box Minimum Altitude?", ref minalts);
@ -2998,13 +3014,13 @@ namespace ArdupilotMega.GCSViews
int minalt = 0; int minalt = 0;
int maxalt = 0; int maxalt = 0;
if (!int.TryParse(minalts,out minalt)) if (!int.TryParse(minalts, out minalt))
{ {
MessageBox.Show("Bad Min Alt"); MessageBox.Show("Bad Min Alt");
return; return;
} }
if (!int.TryParse(maxalts,out maxalt)) if (!int.TryParse(maxalts, out maxalt))
{ {
MessageBox.Show("Bad Max Alt"); MessageBox.Show("Bad Max Alt");
return; return;
@ -3015,9 +3031,10 @@ namespace ArdupilotMega.GCSViews
MainV2.comPort.setParam("FENCE_MINALT", minalt); MainV2.comPort.setParam("FENCE_MINALT", minalt);
MainV2.comPort.setParam("FENCE_MAXALT", maxalt); MainV2.comPort.setParam("FENCE_MAXALT", maxalt);
} }
catch { catch
MessageBox.Show("Failed to set min/max fence alt"); {
return; MessageBox.Show("Failed to set min/max fence alt");
return;
} }
try try
@ -3053,11 +3070,21 @@ namespace ArdupilotMega.GCSViews
drawnpolygons.Polygons.Clear(); drawnpolygons.Polygons.Clear();
drawnpolygons.Markers.Clear(); drawnpolygons.Markers.Clear();
geofence.Polygons.Clear();
gf.Points.Clear(); gf.Points.Clear();
gf.Points.AddRange(drawnpolygon.Points); gf.Points.AddRange(drawnpolygon.Points.ToArray());
drawnpolygon.Points.Clear(); drawnpolygon.Points.Clear();
geofence.Polygons.Add(gf);
// update flightdata
FlightData.geofence.Markers.Clear();
FlightData.geofence.Polygons.Clear();
FlightData.geofence.Polygons.Add(gf);
FlightData.geofence.Markers.Add(geofence.Markers[0]);
MainMap.UpdatePolygonLocalPosition(gf); MainMap.UpdatePolygonLocalPosition(gf);
MainMap.Invalidate(); MainMap.Invalidate();
@ -3082,12 +3109,8 @@ namespace ArdupilotMega.GCSViews
geofence.Polygons.Clear(); geofence.Polygons.Clear();
geofence.Markers.Clear(); geofence.Markers.Clear();
gf.Points.Clear(); gf.Points.Clear();
geofence.Polygons.Add(gf);
FlightData.geofence.Polygons.Clear();
FlightData.geofence.Polygons.Add(gf);
for (int a = 0; a < count; a++) for (int a = 0; a < count; a++)
{ {
@ -3099,7 +3122,14 @@ namespace ArdupilotMega.GCSViews
geofence.Markers.Add(new GMapMarkerGoogleRed(new PointLatLng(gf.Points[0].Lat, gf.Points[0].Lng)) { ToolTipMode = MarkerTooltipMode.OnMouseOver, ToolTipText = "GeoFence Return" }); geofence.Markers.Add(new GMapMarkerGoogleRed(new PointLatLng(gf.Points[0].Lat, gf.Points[0].Lng)) { ToolTipMode = MarkerTooltipMode.OnMouseOver, ToolTipText = "GeoFence Return" });
gf.Points.RemoveAt(0); gf.Points.RemoveAt(0);
MainMap.UpdatePolygonLocalPosition(gf); // add now - so local points are calced
geofence.Polygons.Add(gf);
// update flight data
FlightData.geofence.Markers.Clear();
FlightData.geofence.Polygons.Clear();
FlightData.geofence.Polygons.Add(gf);
FlightData.geofence.Markers.Add(geofence.Markers[0]);
MainMap.Invalidate(); MainMap.Invalidate();
} }
@ -3111,5 +3141,113 @@ namespace ArdupilotMega.GCSViews
MainMap.Invalidate(); MainMap.Invalidate();
} }
/// <summary>
/// from http://www.ecse.rpi.edu/Homepages/wrf/Research/Short_Notes/pnpoly.html
/// </summary>
/// <param name="array"> a closed polygon</param>
/// <param name="testx"></param>
/// <param name="testy"></param>
/// <returns> true = outside</returns>
bool pnpoly(PointLatLng[] array, double testx, double testy)
{
int nvert = array.Length;
int i, j = 0;
bool c = false;
for (i = 0, j = nvert - 1; i < nvert; j = i++)
{
if (((array[i].Lng > testy) != (array[j].Lng > testy)) &&
(testx < (array[j].Lat - array[i].Lat) * (testy - array[i].Lng) / (array[j].Lng - array[i].Lng) + array[i].Lat))
c = !c;
}
return c;
}
private void loadFromFileToolStripMenuItem_Click(object sender, EventArgs e)
{
OpenFileDialog fd = new OpenFileDialog();
fd.Filter = "Fence (*.fen)|*.fen";
fd.ShowDialog();
if (File.Exists(fd.FileName))
{
StreamReader sr = new StreamReader(fd.OpenFile());
drawnpolygons.Markers.Clear();
drawnpolygons.Polygons.Clear();
drawnpolygon.Points.Clear();
int a = 0;
while (!sr.EndOfStream)
{
string line = sr.ReadLine();
if (line.StartsWith("#"))
{
continue;
}
else
{
string[] items = line.Split(new char[] { ' ', '\t' }, StringSplitOptions.RemoveEmptyEntries);
if (a == 0)
{
geofence.Markers.Add(new GMapMarkerGoogleRed(new PointLatLng( double.Parse(items[0]),double.Parse(items[1]))) { ToolTipMode = MarkerTooltipMode.OnMouseOver, ToolTipText = "GeoFence Return" });
}
else
{
drawnpolygon.Points.Add(new PointLatLng(double.Parse(items[0]), double.Parse(items[1])));
addpolygonmarkergrid(drawnpolygon.Points.Count.ToString(), double.Parse(items[1]), double.Parse(items[0]), 0);
}
a++;
}
}
drawnpolygons.Polygons.Add(drawnpolygon);
MainMap.Invalidate();
}
}
private void saveToFileToolStripMenuItem_Click(object sender, EventArgs e)
{
if (geofence.Markers.Count == 0)
{
MessageBox.Show("Please set a return location");
return;
}
SaveFileDialog sf = new SaveFileDialog();
sf.Filter = "Fence (*.fen)|*.fen";
sf.ShowDialog();
if (sf.FileName != "")
{
try
{
StreamWriter sw = new StreamWriter(sf.OpenFile());
sw.WriteLine("#saved by APM Planner " + Application.ProductVersion);
sw.WriteLine(geofence.Markers[0].Position.Lat + " " + geofence.Markers[0].Position.Lng);
if (drawnpolygon.Points.Count > 0)
{
foreach (var pll in drawnpolygon.Points)
{
sw.WriteLine(pll.Lat + " " + pll.Lng);
}
}
else
{
foreach (var pll in gf.Points)
{
sw.WriteLine(pll.Lat + " " + pll.Lng);
}
}
sw.Close();
}
catch { MessageBox.Show("Failed to write fence file"); }
}
}
} }
} }

View File

@ -1704,6 +1704,18 @@
<data name="setReturnLocationToolStripMenuItem.Text" xml:space="preserve"> <data name="setReturnLocationToolStripMenuItem.Text" xml:space="preserve">
<value>Set Return Location</value> <value>Set Return Location</value>
</data> </data>
<data name="loadFromFileToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
<value>177, 22</value>
</data>
<data name="loadFromFileToolStripMenuItem.Text" xml:space="preserve">
<value>Load from File</value>
</data>
<data name="saveToFileToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
<value>177, 22</value>
</data>
<data name="saveToFileToolStripMenuItem.Text" xml:space="preserve">
<value>Save to File</value>
</data>
<data name="geoFenceToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing"> <data name="geoFenceToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
<value>167, 22</value> <value>167, 22</value>
</data> </data>
@ -2200,6 +2212,18 @@
<data name="&gt;&gt;GeoFencedownloadToolStripMenuItem.Type" xml:space="preserve"> <data name="&gt;&gt;GeoFencedownloadToolStripMenuItem.Type" xml:space="preserve">
<value>System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value> <value>System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data> </data>
<data name="&gt;&gt;setReturnLocationToolStripMenuItem.Name" xml:space="preserve">
<value>setReturnLocationToolStripMenuItem</value>
</data>
<data name="&gt;&gt;setReturnLocationToolStripMenuItem.Type" xml:space="preserve">
<value>System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;loadFromFileToolStripMenuItem.Name" xml:space="preserve">
<value>loadFromFileToolStripMenuItem</value>
</data>
<data name="&gt;&gt;loadFromFileToolStripMenuItem.Type" xml:space="preserve">
<value>System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;toolTip1.Name" xml:space="preserve"> <data name="&gt;&gt;toolTip1.Name" xml:space="preserve">
<value>toolTip1</value> <value>toolTip1</value>
</data> </data>
@ -2212,10 +2236,10 @@
<data name="&gt;&gt;timer1.Type" xml:space="preserve"> <data name="&gt;&gt;timer1.Type" xml:space="preserve">
<value>System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value> <value>System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data> </data>
<data name="&gt;&gt;setReturnLocationToolStripMenuItem.Name" xml:space="preserve"> <data name="&gt;&gt;saveToFileToolStripMenuItem.Name" xml:space="preserve">
<value>setReturnLocationToolStripMenuItem</value> <value>saveToFileToolStripMenuItem</value>
</data> </data>
<data name="&gt;&gt;setReturnLocationToolStripMenuItem.Type" xml:space="preserve"> <data name="&gt;&gt;saveToFileToolStripMenuItem.Type" xml:space="preserve">
<value>System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value> <value>System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data> </data>
<data name="&gt;&gt;$this.Name" xml:space="preserve"> <data name="&gt;&gt;$this.Name" xml:space="preserve">

View File

@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below: // by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")] // [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.0.0.0")] [assembly: AssemblyVersion("1.0.0.0")]
[assembly: AssemblyFileVersion("1.1.11")] [assembly: AssemblyFileVersion("1.1.12")]
[assembly: NeutralResourcesLanguageAttribute("")] [assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -200,7 +200,7 @@
// //
// tabControl1 // tabControl1
// //
this.tabControl1.Controls.Add(this.tabReset); //this.tabControl1.Controls.Add(this.tabReset);
this.tabControl1.Controls.Add(this.tabRadioIn); this.tabControl1.Controls.Add(this.tabRadioIn);
this.tabControl1.Controls.Add(this.tabModes); this.tabControl1.Controls.Add(this.tabModes);
this.tabControl1.Controls.Add(this.tabHardware); this.tabControl1.Controls.Add(this.tabHardware);