APM Planner 1.1.72

fix turn radius length (100m)
modify 3dr radio options
modify heli Setup
This commit is contained in:
Michael Oborne 2012-04-21 15:30:15 +08:00
parent f60cd5f7f9
commit 77766bfb73
28 changed files with 2722 additions and 592 deletions

View File

@ -152,7 +152,7 @@
</Reference>
<Reference Include="Microsoft.DirectX.DirectInput, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
<SpecificVersion>False</SpecificVersion>
<Private>True</Private>
<Private>False</Private>
</Reference>
<Reference Include="Microsoft.Dynamic">
</Reference>
@ -238,6 +238,12 @@
<Compile Include="Controls\BackstageView\BackStageViewMenuPanel.cs">
<SubType>Component</SubType>
</Compile>
<Compile Include="Controls\ConnectionControl.cs">
<SubType>UserControl</SubType>
</Compile>
<Compile Include="Controls\ConnectionControl.Designer.cs">
<DependentUpon>ConnectionControl.cs</DependentUpon>
</Compile>
<Compile Include="Controls\ConfigPanel.cs">
<SubType>Form</SubType>
</Compile>
@ -254,6 +260,9 @@
<Compile Include="Controls\ProgressReporterDialogue.designer.cs">
<DependentUpon>ProgressReporterDialogue.cs</DependentUpon>
</Compile>
<Compile Include="Controls\ToolStripConnectionControl.cs">
<SubType>Component</SubType>
</Compile>
<Compile Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibrationQuad.cs">
<SubType>UserControl</SubType>
</Compile>
@ -558,6 +567,9 @@
<EmbeddedResource Include="Controls\BackstageView\BackstageView.resx">
<DependentUpon>BackstageView.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="Controls\ConnectionControl.resx">
<DependentUpon>ConnectionControl.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="Controls\ConfigPanel.resx">
<DependentUpon>ConfigPanel.cs</DependentUpon>
</EmbeddedResource>

View File

@ -104,8 +104,9 @@ namespace ArdupilotMega
float cog = -1;
float target = -1;
float nav_bearing = -1;
public GMapControl MainMap;
public GMapMarkerPlane(PointLatLng p, float heading, float cog, float nav_bearing,float target)
public GMapMarkerPlane(PointLatLng p, float heading, float cog, float nav_bearing,float target, GMapControl map)
: base(p)
{
this.heading = heading;
@ -113,6 +114,7 @@ namespace ArdupilotMega
this.target = target;
this.nav_bearing = nav_bearing;
Size = SizeSt;
MainMap = map;
}
public override void OnRender(Graphics g)
@ -136,7 +138,11 @@ namespace ArdupilotMega
float desired_lead_dist = 100;
float alpha = (desired_lead_dist / MainV2.cs.radius) * rad2deg;
double width = (MainMap.Manager.GetDistance(MainMap.FromLocalToLatLng(0, 0), MainMap.FromLocalToLatLng(MainMap.Width, 0)) * 1000.0);
double m2pixelwidth = MainMap.Width / width;
float alpha = ((desired_lead_dist * (float)m2pixelwidth) / MainV2.cs.radius) * rad2deg;
if (MainV2.cs.radius < 0)
{
@ -643,7 +649,7 @@ namespace ArdupilotMega
while (dataStream.CanRead && bytes > 0)
{
Application.DoEvents();
log.Info(saveto + " " + bytes);
log.Debug(saveto + " " + bytes);
int len = dataStream.Read(buf1, 0, buf1.Length);
bytes -= len;
fs.Write(buf1, 0, len);

View File

@ -0,0 +1,88 @@
namespace ArdupilotMega.Controls
{
partial class ConnectionControl
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Component Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
private void InitializeComponent()
{
this.cmb_Baud = new System.Windows.Forms.ComboBox();
this.cmb_ConnectionType = new System.Windows.Forms.ComboBox();
this.cmb_Connection = new System.Windows.Forms.ComboBox();
this.SuspendLayout();
//
// cmb_Baud
//
this.cmb_Baud.FormattingEnabled = true;
this.cmb_Baud.Location = new System.Drawing.Point(130, 12);
this.cmb_Baud.Name = "cmb_Baud";
this.cmb_Baud.Size = new System.Drawing.Size(70, 21);
this.cmb_Baud.TabIndex = 0;
this.cmb_Baud.Items.AddRange(new object[] {
"4800",
"9600",
"14400",
"19200",
"28800",
"38400",
"57600",
"115200"});
//
// cmb_ConnectionType
//
this.cmb_ConnectionType.FormattingEnabled = true;
this.cmb_ConnectionType.Location = new System.Drawing.Point(79, 39);
this.cmb_ConnectionType.Name = "cmb_ConnectionType";
this.cmb_ConnectionType.Size = new System.Drawing.Size(121, 21);
this.cmb_ConnectionType.TabIndex = 1;
//
// cmb_Connection
//
this.cmb_Connection.FormattingEnabled = true;
this.cmb_Connection.Location = new System.Drawing.Point(3, 12);
this.cmb_Connection.Name = "cmb_Connection";
this.cmb_Connection.Size = new System.Drawing.Size(121, 21);
this.cmb_Connection.TabIndex = 2;
//
// ConnectionControl
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.Controls.Add(this.cmb_Connection);
this.Controls.Add(this.cmb_ConnectionType);
this.Controls.Add(this.cmb_Baud);
this.Name = "ConnectionControl";
this.Size = new System.Drawing.Size(211, 75);
this.ResumeLayout(false);
}
#endregion
private System.Windows.Forms.ComboBox cmb_Baud;
private System.Windows.Forms.ComboBox cmb_ConnectionType;
private System.Windows.Forms.ComboBox cmb_Connection;
}
}

View File

@ -0,0 +1,23 @@
using System;
using System.Collections.Generic;
using System.ComponentModel;
using System.Drawing;
using System.Data;
using System.Linq;
using System.Text;
using System.Windows.Forms;
namespace ArdupilotMega.Controls
{
public partial class ConnectionControl : UserControl
{
public ConnectionControl()
{
InitializeComponent();
}
public ComboBox CMB_baudrate { get { return this.cmb_Baud; } }
public ComboBox CMB_serialport { get { return this.cmb_Connection; } }
public ComboBox TOOL_APMFirmware { get { return this.cmb_ConnectionType; } }
}
}

View File

@ -0,0 +1,120 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
</root>

View File

@ -0,0 +1,120 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
</root>

View File

@ -0,0 +1,17 @@
using System.Windows.Forms;
namespace ArdupilotMega.Controls
{
public class ToolStripConnectionControl : ToolStripControlHost
{
// Call the base constructor passing in a MonthCalendar instance.
public ToolStripConnectionControl()
: base(new ConnectionControl())
{
}
public ConnectionControl ConnectionControl
{
get { return Control as ConnectionControl; }
}
}
}

View File

@ -69,7 +69,7 @@ namespace ArdupilotMega.GCSViews
XTRK_GAIN_SC1.Name = "XTRK_GAIN_SC";
// enable disable relevbant hardware tabs
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
this.ConfigTabs.SuspendLayout();
ConfigTabs.SelectedIndex = 0;
@ -656,7 +656,7 @@ namespace ArdupilotMega.GCSViews
{
StreamWriter sw = new StreamWriter(sfd.OpenFile());
string input = DateTime.Now + " Frame : + | Arducopter Kit | Kit motors";
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
input = DateTime.Now + " Plane: Skywalker";
}
@ -986,7 +986,7 @@ namespace ArdupilotMega.GCSViews
if (startup)
return;
MainV2.config["distunits"] = CMB_distunits.Text;
MainV2.instance.changeunits();
MainV2.instance.ChangeUnits();
}
private void CMB_speedunits_SelectedIndexChanged(object sender, EventArgs e)
@ -994,7 +994,7 @@ namespace ArdupilotMega.GCSViews
if (startup)
return;
MainV2.config["speedunits"] = CMB_speedunits.Text;
MainV2.instance.changeunits();
MainV2.instance.ChangeUnits();
}

View File

@ -237,8 +237,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
((MyButton)sender).Enabled = true;
startup = true;
// AR todo: fix this up
//Configuration_Load(null, null);
startup = false;
}
private void CHK_speechbattery_CheckedChanged(object sender, EventArgs e)
@ -276,7 +277,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (startup)
return;
MainV2.config["distunits"] = CMB_distunits.Text;
MainV2.instance.changeunits();
MainV2.instance.ChangeUnits();
}
private void CMB_speedunits_SelectedIndexChanged(object sender, EventArgs e)
@ -284,7 +285,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (startup)
return;
MainV2.config["speedunits"] = CMB_speedunits.Text;
MainV2.instance.changeunits();
MainV2.instance.ChangeUnits();
}
private void CMB_rateattitude_SelectedIndexChanged(object sender, EventArgs e)

View File

@ -162,7 +162,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
StreamWriter sw = new StreamWriter(sfd.OpenFile());
string input = DateTime.Now + " Frame : + | Arducopter Kit | Kit motors";
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
input = DateTime.Now + " Plane: Skywalker";
}

View File

@ -31,21 +31,21 @@
this.components = new System.ComponentModel.Container();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigTradHeli));
this.groupBox5 = new System.Windows.Forms.GroupBox();
this.H1_ENABLE = new System.Windows.Forms.RadioButton();
this.H_SWASH_TYPE = new System.Windows.Forms.RadioButton();
this.CCPM = new System.Windows.Forms.RadioButton();
this.BUT_swash_manual = new ArdupilotMega.MyButton();
this.label41 = new System.Windows.Forms.Label();
this.groupBox3 = new System.Windows.Forms.GroupBox();
this.label46 = new System.Windows.Forms.Label();
this.label45 = new System.Windows.Forms.Label();
this.GYR_ENABLE = new System.Windows.Forms.CheckBox();
this.GYR_GAIN = new System.Windows.Forms.TextBox();
this.H_GYR_ENABLE = new System.Windows.Forms.CheckBox();
this.H_GYR_GAIN = new System.Windows.Forms.TextBox();
this.BUT_HS4save = new ArdupilotMega.MyButton();
this.label21 = new System.Windows.Forms.Label();
this.COL_MIN = new System.Windows.Forms.TextBox();
this.H_COL_MIN = new System.Windows.Forms.TextBox();
this.groupBox1 = new System.Windows.Forms.GroupBox();
this.COL_MID = new System.Windows.Forms.TextBox();
this.COL_MAX = new System.Windows.Forms.TextBox();
this.H_COL_MID = new System.Windows.Forms.TextBox();
this.H_COL_MAX = new System.Windows.Forms.TextBox();
this.BUT_0collective = new ArdupilotMega.MyButton();
this.groupBox2 = new System.Windows.Forms.GroupBox();
this.label24 = new System.Windows.Forms.Label();
@ -60,17 +60,17 @@
this.label37 = new System.Windows.Forms.Label();
this.label36 = new System.Windows.Forms.Label();
this.label26 = new System.Windows.Forms.Label();
this.PIT_MAX = new System.Windows.Forms.TextBox();
this.H_PIT_MAX = new System.Windows.Forms.TextBox();
this.label25 = new System.Windows.Forms.Label();
this.ROL_MAX = new System.Windows.Forms.TextBox();
this.H_ROL_MAX = new System.Windows.Forms.TextBox();
this.label23 = new System.Windows.Forms.Label();
this.label22 = new System.Windows.Forms.Label();
this.label20 = new System.Windows.Forms.Label();
this.label19 = new System.Windows.Forms.Label();
this.label18 = new System.Windows.Forms.Label();
this.SV3_POS = new System.Windows.Forms.TextBox();
this.SV2_POS = new System.Windows.Forms.TextBox();
this.SV1_POS = new System.Windows.Forms.TextBox();
this.H_SV3_POS = new System.Windows.Forms.TextBox();
this.H_SV2_POS = new System.Windows.Forms.TextBox();
this.H_SV1_POS = new System.Windows.Forms.TextBox();
this.HS3_REV = new System.Windows.Forms.CheckBox();
this.HS2_REV = new System.Windows.Forms.CheckBox();
this.HS1_REV = new System.Windows.Forms.CheckBox();
@ -97,19 +97,19 @@
//
// groupBox5
//
this.groupBox5.Controls.Add(this.H1_ENABLE);
this.groupBox5.Controls.Add(this.H_SWASH_TYPE);
this.groupBox5.Controls.Add(this.CCPM);
resources.ApplyResources(this.groupBox5, "groupBox5");
this.groupBox5.Name = "groupBox5";
this.groupBox5.TabStop = false;
//
// H1_ENABLE
// H_SWASH_TYPE
//
resources.ApplyResources(this.H1_ENABLE, "H1_ENABLE");
this.H1_ENABLE.Name = "H1_ENABLE";
this.H1_ENABLE.TabStop = true;
this.H1_ENABLE.UseVisualStyleBackColor = true;
this.H1_ENABLE.CheckedChanged += new System.EventHandler(this.H1_ENABLE_CheckedChanged);
resources.ApplyResources(this.H_SWASH_TYPE, "H_SWASH_TYPE");
this.H_SWASH_TYPE.Name = "H_SWASH_TYPE";
this.H_SWASH_TYPE.TabStop = true;
this.H_SWASH_TYPE.UseVisualStyleBackColor = true;
this.H_SWASH_TYPE.CheckedChanged += new System.EventHandler(this.H_SWASH_TYPE_CheckedChanged);
//
// CCPM
//
@ -134,8 +134,8 @@
//
this.groupBox3.Controls.Add(this.label46);
this.groupBox3.Controls.Add(this.label45);
this.groupBox3.Controls.Add(this.GYR_ENABLE);
this.groupBox3.Controls.Add(this.GYR_GAIN);
this.groupBox3.Controls.Add(this.H_GYR_ENABLE);
this.groupBox3.Controls.Add(this.H_GYR_GAIN);
resources.ApplyResources(this.groupBox3, "groupBox3");
this.groupBox3.Name = "groupBox3";
this.groupBox3.TabStop = false;
@ -150,18 +150,18 @@
resources.ApplyResources(this.label45, "label45");
this.label45.Name = "label45";
//
// GYR_ENABLE
// H_GYR_ENABLE
//
resources.ApplyResources(this.GYR_ENABLE, "GYR_ENABLE");
this.GYR_ENABLE.Name = "GYR_ENABLE";
this.GYR_ENABLE.UseVisualStyleBackColor = true;
this.GYR_ENABLE.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged);
resources.ApplyResources(this.H_GYR_ENABLE, "H_GYR_ENABLE");
this.H_GYR_ENABLE.Name = "H_GYR_ENABLE";
this.H_GYR_ENABLE.UseVisualStyleBackColor = true;
this.H_GYR_ENABLE.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged);
//
// GYR_GAIN
// H_GYR_GAIN
//
resources.ApplyResources(this.GYR_GAIN, "GYR_GAIN");
this.GYR_GAIN.Name = "GYR_GAIN";
this.GYR_GAIN.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating);
resources.ApplyResources(this.H_GYR_GAIN, "H_GYR_GAIN");
this.H_GYR_GAIN.Name = "H_GYR_GAIN";
this.H_GYR_GAIN.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating);
//
// BUT_HS4save
//
@ -175,36 +175,36 @@
resources.ApplyResources(this.label21, "label21");
this.label21.Name = "label21";
//
// COL_MIN
// H_COL_MIN
//
resources.ApplyResources(this.COL_MIN, "COL_MIN");
this.COL_MIN.Name = "COL_MIN";
resources.ApplyResources(this.H_COL_MIN, "H_COL_MIN");
this.H_COL_MIN.Name = "H_COL_MIN";
//
// groupBox1
//
this.groupBox1.Controls.Add(this.label41);
this.groupBox1.Controls.Add(this.label21);
this.groupBox1.Controls.Add(this.COL_MIN);
this.groupBox1.Controls.Add(this.COL_MID);
this.groupBox1.Controls.Add(this.COL_MAX);
this.groupBox1.Controls.Add(this.H_COL_MIN);
this.groupBox1.Controls.Add(this.H_COL_MID);
this.groupBox1.Controls.Add(this.H_COL_MAX);
this.groupBox1.Controls.Add(this.BUT_0collective);
resources.ApplyResources(this.groupBox1, "groupBox1");
this.groupBox1.Name = "groupBox1";
this.groupBox1.TabStop = false;
//
// COL_MID
// H_COL_MID
//
resources.ApplyResources(this.COL_MID, "COL_MID");
this.COL_MID.Name = "COL_MID";
this.COL_MID.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
resources.ApplyResources(this.H_COL_MID, "H_COL_MID");
this.H_COL_MID.Name = "H_COL_MID";
this.H_COL_MID.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
//
// COL_MAX
// H_COL_MAX
//
resources.ApplyResources(this.COL_MAX, "COL_MAX");
this.COL_MAX.Name = "COL_MAX";
this.COL_MAX.Enter += new System.EventHandler(this.COL_MAX__Enter);
this.COL_MAX.Leave += new System.EventHandler(this.COL_MAX__Leave);
this.COL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
resources.ApplyResources(this.H_COL_MAX, "H_COL_MAX");
this.H_COL_MAX.Name = "H_COL_MAX";
this.H_COL_MAX.Enter += new System.EventHandler(this.COL_MAX__Enter);
this.H_COL_MAX.Leave += new System.EventHandler(this.COL_MAX__Leave);
this.H_COL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
//
// BUT_0collective
//
@ -334,22 +334,22 @@
resources.ApplyResources(this.label26, "label26");
this.label26.Name = "label26";
//
// PIT_MAX
// H_PIT_MAX
//
resources.ApplyResources(this.PIT_MAX, "PIT_MAX");
this.PIT_MAX.Name = "PIT_MAX";
this.PIT_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating);
resources.ApplyResources(this.H_PIT_MAX, "H_PIT_MAX");
this.H_PIT_MAX.Name = "H_PIT_MAX";
this.H_PIT_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating);
//
// label25
//
resources.ApplyResources(this.label25, "label25");
this.label25.Name = "label25";
//
// ROL_MAX
// H_ROL_MAX
//
resources.ApplyResources(this.ROL_MAX, "ROL_MAX");
this.ROL_MAX.Name = "ROL_MAX";
this.ROL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating);
resources.ApplyResources(this.H_ROL_MAX, "H_ROL_MAX");
this.H_ROL_MAX.Name = "H_ROL_MAX";
this.H_ROL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating);
//
// label23
//
@ -376,23 +376,23 @@
resources.ApplyResources(this.label18, "label18");
this.label18.Name = "label18";
//
// SV3_POS
// H_SV3_POS
//
resources.ApplyResources(this.SV3_POS, "SV3_POS");
this.SV3_POS.Name = "SV3_POS";
this.SV3_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos3_Validating);
resources.ApplyResources(this.H_SV3_POS, "H_SV3_POS");
this.H_SV3_POS.Name = "H_SV3_POS";
this.H_SV3_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos3_Validating);
//
// SV2_POS
// H_SV2_POS
//
resources.ApplyResources(this.SV2_POS, "SV2_POS");
this.SV2_POS.Name = "SV2_POS";
this.SV2_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos2_Validating);
resources.ApplyResources(this.H_SV2_POS, "H_SV2_POS");
this.H_SV2_POS.Name = "H_SV2_POS";
this.H_SV2_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos2_Validating);
//
// SV1_POS
// H_SV1_POS
//
resources.ApplyResources(this.SV1_POS, "SV1_POS");
this.SV1_POS.Name = "SV1_POS";
this.SV1_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos1_Validating);
resources.ApplyResources(this.H_SV1_POS, "H_SV1_POS");
this.H_SV1_POS.Name = "H_SV1_POS";
this.H_SV1_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos1_Validating);
//
// HS3_REV
//
@ -665,17 +665,17 @@
this.Controls.Add(this.label37);
this.Controls.Add(this.label36);
this.Controls.Add(this.label26);
this.Controls.Add(this.PIT_MAX);
this.Controls.Add(this.H_PIT_MAX);
this.Controls.Add(this.label25);
this.Controls.Add(this.ROL_MAX);
this.Controls.Add(this.H_ROL_MAX);
this.Controls.Add(this.label23);
this.Controls.Add(this.label22);
this.Controls.Add(this.label20);
this.Controls.Add(this.label19);
this.Controls.Add(this.label18);
this.Controls.Add(this.SV3_POS);
this.Controls.Add(this.SV2_POS);
this.Controls.Add(this.SV1_POS);
this.Controls.Add(this.H_SV3_POS);
this.Controls.Add(this.H_SV2_POS);
this.Controls.Add(this.H_SV1_POS);
this.Controls.Add(this.HS3_REV);
this.Controls.Add(this.HS2_REV);
this.Controls.Add(this.HS1_REV);
@ -707,21 +707,21 @@
#endregion
private System.Windows.Forms.GroupBox groupBox5;
private System.Windows.Forms.RadioButton H1_ENABLE;
private System.Windows.Forms.RadioButton H_SWASH_TYPE;
private System.Windows.Forms.RadioButton CCPM;
private MyButton BUT_swash_manual;
private System.Windows.Forms.Label label41;
private System.Windows.Forms.GroupBox groupBox3;
private System.Windows.Forms.Label label46;
private System.Windows.Forms.Label label45;
private System.Windows.Forms.CheckBox GYR_ENABLE;
private System.Windows.Forms.TextBox GYR_GAIN;
private System.Windows.Forms.CheckBox H_GYR_ENABLE;
private System.Windows.Forms.TextBox H_GYR_GAIN;
private MyButton BUT_HS4save;
private System.Windows.Forms.Label label21;
private System.Windows.Forms.TextBox COL_MIN;
private System.Windows.Forms.TextBox H_COL_MIN;
private System.Windows.Forms.GroupBox groupBox1;
private System.Windows.Forms.TextBox COL_MID;
private System.Windows.Forms.TextBox COL_MAX;
private System.Windows.Forms.TextBox H_COL_MID;
private System.Windows.Forms.TextBox H_COL_MAX;
private MyButton BUT_0collective;
private System.Windows.Forms.GroupBox groupBox2;
private System.Windows.Forms.Label label24;
@ -736,17 +736,17 @@
private System.Windows.Forms.Label label37;
private System.Windows.Forms.Label label36;
private System.Windows.Forms.Label label26;
private System.Windows.Forms.TextBox PIT_MAX;
private System.Windows.Forms.TextBox H_PIT_MAX;
private System.Windows.Forms.Label label25;
private System.Windows.Forms.TextBox ROL_MAX;
private System.Windows.Forms.TextBox H_ROL_MAX;
private System.Windows.Forms.Label label23;
private System.Windows.Forms.Label label22;
private System.Windows.Forms.Label label20;
private System.Windows.Forms.Label label19;
private System.Windows.Forms.Label label18;
private System.Windows.Forms.TextBox SV3_POS;
private System.Windows.Forms.TextBox SV2_POS;
private System.Windows.Forms.TextBox SV1_POS;
private System.Windows.Forms.TextBox H_SV3_POS;
private System.Windows.Forms.TextBox H_SV2_POS;
private System.Windows.Forms.TextBox H_SV1_POS;
private System.Windows.Forms.CheckBox HS3_REV;
private System.Windows.Forms.CheckBox HS2_REV;
private System.Windows.Forms.CheckBox HS1_REV;

View File

@ -22,65 +22,65 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
InitializeComponent();
}
private void H1_ENABLE_CheckedChanged(object sender, EventArgs e)
private void H_SWASH_TYPE_CheckedChanged(object sender, EventArgs e)
{
if (startup)
return;
try
{
if (MainV2.comPort.param["H1_ENABLE"] == null)
if (MainV2.comPort.param["H_SWASH_TYPE"] == null)
{
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
}
else
{
MainV2.comPort.setParam("H1_ENABLE", ((RadioButton)sender).Checked == true ? 1 : 0);
MainV2.comPort.setParam("H_SWASH_TYPE", ((RadioButton)sender).Checked == true ? 1 : 0);
}
}
catch { CustomMessageBox.Show("Set H1_ENABLE Failed"); }
catch { CustomMessageBox.Show("Set H_SWASH_TYPE Failed"); }
}
private void BUT_swash_manual_Click(object sender, EventArgs e)
{
try
{
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
if (MainV2.comPort.param["H_SV_MAN"].ToString() == "1")
{
MainV2.comPort.setParam("COL_MIN", int.Parse(COL_MIN.Text));
MainV2.comPort.setParam("COL_MAX", int.Parse(COL_MAX.Text));
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
MainV2.comPort.setParam("H_COL_MIN", int.Parse(H_COL_MIN.Text));
MainV2.comPort.setParam("H_COL_MAX", int.Parse(H_COL_MAX.Text));
MainV2.comPort.setParam("H_SV_MAN", 0); // randy request - last
BUT_swash_manual.Text = "Manual";
COL_MAX.Enabled = false;
COL_MID.Enabled = false;
COL_MIN.Enabled = false;
H_COL_MAX.Enabled = false;
H_COL_MID.Enabled = false;
H_COL_MIN.Enabled = false;
BUT_0collective.Enabled = false;
}
else
{
COL_MAX.Text = "1500";
COL_MIN.Text = "1500";
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
H_COL_MAX.Text = "1500";
H_COL_MIN.Text = "1500";
MainV2.comPort.setParam("H_SV_MAN", 1); // randy request
BUT_swash_manual.Text = "Save";
COL_MAX.Enabled = true;
COL_MID.Enabled = true;
COL_MIN.Enabled = true;
H_COL_MAX.Enabled = true;
H_COL_MID.Enabled = true;
H_COL_MIN.Enabled = true;
BUT_0collective.Enabled = true;
}
}
catch { CustomMessageBox.Show("Failed to set HSV_MAN"); }
catch { CustomMessageBox.Show("Failed to set H_SV_MAN"); }
}
private void BUT_HS4save_Click(object sender, EventArgs e)
{
try
{
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
if (MainV2.comPort.param["H_SV_MAN"].ToString() == "1")
{
MainV2.comPort.setParam("HS4_MIN", int.Parse(HS4_MIN.Text));
MainV2.comPort.setParam("HS4_MAX", int.Parse(HS4_MAX.Text));
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
MainV2.comPort.setParam("H_SV_MAN", 0); // randy request - last
BUT_HS4save.Text = "Manual";
HS4_MAX.Enabled = false;
@ -90,7 +90,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
HS4_MIN.Text = "1500";
HS4_MAX.Text = "1500";
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
MainV2.comPort.setParam("H_SV_MAN", 1); // randy request
BUT_HS4save.Text = "Save";
@ -98,7 +98,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
HS4_MIN.Enabled = true;
}
}
catch { CustomMessageBox.Show("Failed to set HSV_MAN"); }
catch { CustomMessageBox.Show("Failed to set H_SV_MAN"); }
}
private void tabHeli_Click(object sender, EventArgs e)
@ -122,10 +122,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
try
{
if (int.Parse(COL_MIN.Text) > HS3.minline)
COL_MIN.Text = HS3.minline.ToString();
if (int.Parse(COL_MAX.Text) < HS3.maxline)
COL_MAX.Text = HS3.maxline.ToString();
if (int.Parse(H_COL_MIN.Text) > HS3.minline)
H_COL_MIN.Text = HS3.minline.ToString();
if (int.Parse(H_COL_MAX.Text) < HS3.maxline)
H_COL_MAX.Text = HS3.maxline.ToString();
}
catch { }
}
@ -194,10 +194,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
try
{
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
MainV2.comPort.setParam("H_SV_MAN", 1); // randy request
MainV2.comPort.setParam(((TextBox)sender).Name, test);
System.Threading.Thread.Sleep(100);
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
MainV2.comPort.setParam("H_SV_MAN", 0); // randy request - last
}
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
@ -217,10 +217,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
try
{
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
MainV2.comPort.setParam("H_SV_MAN", 1); // randy request
MainV2.comPort.setParam(((TextBox)sender).Name, test);
System.Threading.Thread.Sleep(100);
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
MainV2.comPort.setParam("H_SV_MAN", 0); // randy request - last
}
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
}
@ -239,10 +239,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
try
{
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
MainV2.comPort.setParam("H_SV_MAN", 1); // randy request
MainV2.comPort.setParam(((TextBox)sender).Name, test);
System.Threading.Thread.Sleep(100);
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
MainV2.comPort.setParam("H_SV_MAN", 0); // randy request - last
}
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
}
@ -254,11 +254,11 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
try
{
MainV2.comPort.setParam("COL_MID", MainV2.cs.ch3in);
MainV2.comPort.setParam("H_COL_MID", MainV2.cs.ch3in);
COL_MID.Text = MainV2.comPort.param["COL_MID"].ToString();
H_COL_MID.Text = MainV2.comPort.param["H_COL_MID"].ToString();
}
catch { CustomMessageBox.Show("Set COL_MID_ failed"); }
catch { CustomMessageBox.Show("Set H_COL_MID failed"); }
}
private void HS1_REV_CheckedChanged(object sender, EventArgs e)
@ -379,7 +379,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.Enabled = true;
}
if (MainV2.comPort.param["GYR_ENABLE"] == null)
if (MainV2.comPort.param["H_GYR_ENABLE"] == null)
{
this.Enabled = false;
return;
@ -394,10 +394,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
startup = true;
try
{
if (MainV2.comPort.param.ContainsKey("H1_ENABLE"))
if (MainV2.comPort.param.ContainsKey("H_SWASH_TYPE"))
{
CCPM.Checked = MainV2.comPort.param["H1_ENABLE"].ToString() == "0" ? true : false;
H1_ENABLE.Checked = !CCPM.Checked;
CCPM.Checked = MainV2.comPort.param["H_SWASH_TYPE"].ToString() == "0" ? true : false;
H_SWASH_TYPE.Checked = !CCPM.Checked;
}
foreach (string value in MainV2.comPort.param.Keys)
@ -453,7 +453,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
}
catch { }
if (MainV2.comPort.param["HSV_MAN"] == null || MainV2.comPort.param["HSV_MAN"].ToString() == "0")
if (MainV2.comPort.param["H_SV_MAN"] == null || MainV2.comPort.param["H_SV_MAN"].ToString() == "0")
return;
if (HS3.minline == 0)
@ -477,8 +477,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
try
{
HS3.minline = int.Parse(COL_MIN.Text);
HS3.maxline = int.Parse(COL_MAX.Text);
HS3.minline = int.Parse(H_COL_MIN.Text);
HS3.maxline = int.Parse(H_COL_MAX.Text);
HS4.maxline = int.Parse(HS4_MIN.Text);
HS4.minline = int.Parse(HS4_MAX.Text);
}

View File

@ -117,42 +117,36 @@
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="H1_ENABLE.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="H1_ENABLE.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="H1_ENABLE.Location" type="System.Drawing.Point, System.Drawing">
<value>67, 19</value>
<data name="H_SWASH_TYPE.Location" type="System.Drawing.Point, System.Drawing">
<value>67, 15</value>
</data>
<data name="H1_ENABLE.Size" type="System.Drawing.Size, System.Drawing">
<value>39, 17</value>
<data name="H_SWASH_TYPE.Size" type="System.Drawing.Size, System.Drawing">
<value>42, 24</value>
</data>
<data name="H1_ENABLE.TabIndex" type="System.Int32, mscorlib">
<value>137</value>
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="H_SWASH_TYPE.TabIndex" type="System.Int32, mscorlib">
<value>0</value>
</data>
<data name="H1_ENABLE.Text" xml:space="preserve">
<data name="H_SWASH_TYPE.Text" xml:space="preserve">
<value>H1</value>
</data>
<data name="&gt;&gt;H1_ENABLE.Name" xml:space="preserve">
<value>H1_ENABLE</value>
<data name="&gt;&gt;H_SWASH_TYPE.Name" xml:space="preserve">
<value>H_SWASH_TYPE</value>
</data>
<data name="&gt;&gt;H1_ENABLE.Type" xml:space="preserve">
<data name="&gt;&gt;H_SWASH_TYPE.Type" xml:space="preserve">
<value>System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;H1_ENABLE.Parent" xml:space="preserve">
<data name="&gt;&gt;H_SWASH_TYPE.Parent" xml:space="preserve">
<value>groupBox5</value>
</data>
<data name="&gt;&gt;H1_ENABLE.ZOrder" xml:space="preserve">
<data name="&gt;&gt;H_SWASH_TYPE.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="CCPM.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="CCPM.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
@ -223,7 +217,7 @@
<value>BUT_swash_manual</value>
</data>
<data name="&gt;&gt;BUT_swash_manual.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_swash_manual.Parent" xml:space="preserve">
<value>$this</value>
@ -321,55 +315,55 @@
<data name="&gt;&gt;label45.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="GYR_ENABLE.AutoSize" type="System.Boolean, mscorlib">
<data name="H_GYR_ENABLE.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="GYR_ENABLE.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<data name="H_GYR_ENABLE.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="GYR_ENABLE.Location" type="System.Drawing.Point, System.Drawing">
<data name="H_GYR_ENABLE.Location" type="System.Drawing.Point, System.Drawing">
<value>57, 19</value>
</data>
<data name="GYR_ENABLE.Size" type="System.Drawing.Size, System.Drawing">
<data name="H_GYR_ENABLE.Size" type="System.Drawing.Size, System.Drawing">
<value>15, 14</value>
</data>
<data name="GYR_ENABLE.TabIndex" type="System.Int32, mscorlib">
<data name="H_GYR_ENABLE.TabIndex" type="System.Int32, mscorlib">
<value>118</value>
</data>
<data name="&gt;&gt;GYR_ENABLE.Name" xml:space="preserve">
<value>GYR_ENABLE</value>
<data name="&gt;&gt;H_GYR_ENABLE.Name" xml:space="preserve">
<value>H_GYR_ENABLE</value>
</data>
<data name="&gt;&gt;GYR_ENABLE.Type" xml:space="preserve">
<data name="&gt;&gt;H_GYR_ENABLE.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;GYR_ENABLE.Parent" xml:space="preserve">
<data name="&gt;&gt;H_GYR_ENABLE.Parent" xml:space="preserve">
<value>groupBox3</value>
</data>
<data name="&gt;&gt;GYR_ENABLE.ZOrder" xml:space="preserve">
<data name="&gt;&gt;H_GYR_ENABLE.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="GYR_GAIN.Location" type="System.Drawing.Point, System.Drawing">
<data name="H_GYR_GAIN.Location" type="System.Drawing.Point, System.Drawing">
<value>41, 35</value>
</data>
<data name="GYR_GAIN.Size" type="System.Drawing.Size, System.Drawing">
<data name="H_GYR_GAIN.Size" type="System.Drawing.Size, System.Drawing">
<value>47, 20</value>
</data>
<data name="GYR_GAIN.TabIndex" type="System.Int32, mscorlib">
<data name="H_GYR_GAIN.TabIndex" type="System.Int32, mscorlib">
<value>119</value>
</data>
<data name="GYR_GAIN.Text" xml:space="preserve">
<data name="H_GYR_GAIN.Text" xml:space="preserve">
<value>1000</value>
</data>
<data name="&gt;&gt;GYR_GAIN.Name" xml:space="preserve">
<value>GYR_GAIN</value>
<data name="&gt;&gt;H_GYR_GAIN.Name" xml:space="preserve">
<value>H_GYR_GAIN</value>
</data>
<data name="&gt;&gt;GYR_GAIN.Type" xml:space="preserve">
<data name="&gt;&gt;H_GYR_GAIN.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;GYR_GAIN.Parent" xml:space="preserve">
<data name="&gt;&gt;H_GYR_GAIN.Parent" xml:space="preserve">
<value>groupBox3</value>
</data>
<data name="&gt;&gt;GYR_GAIN.ZOrder" xml:space="preserve">
<data name="&gt;&gt;H_GYR_GAIN.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="groupBox3.Location" type="System.Drawing.Point, System.Drawing">
@ -415,7 +409,7 @@
<value>BUT_HS4save</value>
</data>
<data name="&gt;&gt;BUT_HS4save.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_HS4save.Parent" xml:space="preserve">
<value>$this</value>
@ -453,85 +447,85 @@
<data name="&gt;&gt;label21.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="COL_MIN.Enabled" type="System.Boolean, mscorlib">
<data name="H_COL_MIN.Enabled" type="System.Boolean, mscorlib">
<value>False</value>
</data>
<data name="COL_MIN.Location" type="System.Drawing.Point, System.Drawing">
<data name="H_COL_MIN.Location" type="System.Drawing.Point, System.Drawing">
<value>18, 173</value>
</data>
<data name="COL_MIN.Size" type="System.Drawing.Size, System.Drawing">
<data name="H_COL_MIN.Size" type="System.Drawing.Size, System.Drawing">
<value>43, 20</value>
</data>
<data name="COL_MIN.TabIndex" type="System.Int32, mscorlib">
<data name="H_COL_MIN.TabIndex" type="System.Int32, mscorlib">
<value>119</value>
</data>
<data name="COL_MIN.Text" xml:space="preserve">
<data name="H_COL_MIN.Text" xml:space="preserve">
<value>1500</value>
</data>
<data name="&gt;&gt;COL_MIN.Name" xml:space="preserve">
<value>COL_MIN</value>
<data name="&gt;&gt;H_COL_MIN.Name" xml:space="preserve">
<value>H_COL_MIN</value>
</data>
<data name="&gt;&gt;COL_MIN.Type" xml:space="preserve">
<data name="&gt;&gt;H_COL_MIN.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;COL_MIN.Parent" xml:space="preserve">
<data name="&gt;&gt;H_COL_MIN.Parent" xml:space="preserve">
<value>groupBox1</value>
</data>
<data name="&gt;&gt;COL_MIN.ZOrder" xml:space="preserve">
<data name="&gt;&gt;H_COL_MIN.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="COL_MID.Enabled" type="System.Boolean, mscorlib">
<data name="H_COL_MID.Enabled" type="System.Boolean, mscorlib">
<value>False</value>
</data>
<data name="COL_MID.Location" type="System.Drawing.Point, System.Drawing">
<data name="H_COL_MID.Location" type="System.Drawing.Point, System.Drawing">
<value>17, 117</value>
</data>
<data name="COL_MID.Size" type="System.Drawing.Size, System.Drawing">
<data name="H_COL_MID.Size" type="System.Drawing.Size, System.Drawing">
<value>44, 20</value>
</data>
<data name="COL_MID.TabIndex" type="System.Int32, mscorlib">
<data name="H_COL_MID.TabIndex" type="System.Int32, mscorlib">
<value>117</value>
</data>
<data name="COL_MID.Text" xml:space="preserve">
<data name="H_COL_MID.Text" xml:space="preserve">
<value>1500</value>
</data>
<data name="&gt;&gt;COL_MID.Name" xml:space="preserve">
<value>COL_MID</value>
<data name="&gt;&gt;H_COL_MID.Name" xml:space="preserve">
<value>H_COL_MID</value>
</data>
<data name="&gt;&gt;COL_MID.Type" xml:space="preserve">
<data name="&gt;&gt;H_COL_MID.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;COL_MID.Parent" xml:space="preserve">
<data name="&gt;&gt;H_COL_MID.Parent" xml:space="preserve">
<value>groupBox1</value>
</data>
<data name="&gt;&gt;COL_MID.ZOrder" xml:space="preserve">
<data name="&gt;&gt;H_COL_MID.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="COL_MAX.Enabled" type="System.Boolean, mscorlib">
<data name="H_COL_MAX.Enabled" type="System.Boolean, mscorlib">
<value>False</value>
</data>
<data name="COL_MAX.Location" type="System.Drawing.Point, System.Drawing">
<data name="H_COL_MAX.Location" type="System.Drawing.Point, System.Drawing">
<value>18, 45</value>
</data>
<data name="COL_MAX.Size" type="System.Drawing.Size, System.Drawing">
<data name="H_COL_MAX.Size" type="System.Drawing.Size, System.Drawing">
<value>43, 20</value>
</data>
<data name="COL_MAX.TabIndex" type="System.Int32, mscorlib">
<data name="H_COL_MAX.TabIndex" type="System.Int32, mscorlib">
<value>115</value>
</data>
<data name="COL_MAX.Text" xml:space="preserve">
<data name="H_COL_MAX.Text" xml:space="preserve">
<value>1500</value>
</data>
<data name="&gt;&gt;COL_MAX.Name" xml:space="preserve">
<value>COL_MAX</value>
<data name="&gt;&gt;H_COL_MAX.Name" xml:space="preserve">
<value>H_COL_MAX</value>
</data>
<data name="&gt;&gt;COL_MAX.Type" xml:space="preserve">
<data name="&gt;&gt;H_COL_MAX.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;COL_MAX.Parent" xml:space="preserve">
<data name="&gt;&gt;H_COL_MAX.Parent" xml:space="preserve">
<value>groupBox1</value>
</data>
<data name="&gt;&gt;COL_MAX.ZOrder" xml:space="preserve">
<data name="&gt;&gt;H_COL_MAX.ZOrder" xml:space="preserve">
<value>4</value>
</data>
<data name="BUT_0collective.Enabled" type="System.Boolean, mscorlib">
@ -556,7 +550,7 @@
<value>BUT_0collective</value>
</data>
<data name="&gt;&gt;BUT_0collective.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_0collective.Parent" xml:space="preserve">
<value>groupBox1</value>
@ -933,28 +927,28 @@
<data name="&gt;&gt;label26.ZOrder" xml:space="preserve">
<value>18</value>
</data>
<data name="PIT_MAX.Location" type="System.Drawing.Point, System.Drawing">
<data name="H_PIT_MAX.Location" type="System.Drawing.Point, System.Drawing">
<value>314, 362</value>
</data>
<data name="PIT_MAX.Size" type="System.Drawing.Size, System.Drawing">
<data name="H_PIT_MAX.Size" type="System.Drawing.Size, System.Drawing">
<value>47, 20</value>
</data>
<data name="PIT_MAX.TabIndex" type="System.Int32, mscorlib">
<data name="H_PIT_MAX.TabIndex" type="System.Int32, mscorlib">
<value>156</value>
</data>
<data name="PIT_MAX.Text" xml:space="preserve">
<data name="H_PIT_MAX.Text" xml:space="preserve">
<value>4500</value>
</data>
<data name="&gt;&gt;PIT_MAX.Name" xml:space="preserve">
<value>PIT_MAX</value>
<data name="&gt;&gt;H_PIT_MAX.Name" xml:space="preserve">
<value>H_PIT_MAX</value>
</data>
<data name="&gt;&gt;PIT_MAX.Type" xml:space="preserve">
<data name="&gt;&gt;H_PIT_MAX.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;PIT_MAX.Parent" xml:space="preserve">
<data name="&gt;&gt;H_PIT_MAX.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;PIT_MAX.ZOrder" xml:space="preserve">
<data name="&gt;&gt;H_PIT_MAX.ZOrder" xml:space="preserve">
<value>19</value>
</data>
<data name="label25.AutoSize" type="System.Boolean, mscorlib">
@ -987,28 +981,28 @@
<data name="&gt;&gt;label25.ZOrder" xml:space="preserve">
<value>20</value>
</data>
<data name="ROL_MAX.Location" type="System.Drawing.Point, System.Drawing">
<data name="H_ROL_MAX.Location" type="System.Drawing.Point, System.Drawing">
<value>314, 336</value>
</data>
<data name="ROL_MAX.Size" type="System.Drawing.Size, System.Drawing">
<data name="H_ROL_MAX.Size" type="System.Drawing.Size, System.Drawing">
<value>47, 20</value>
</data>
<data name="ROL_MAX.TabIndex" type="System.Int32, mscorlib">
<data name="H_ROL_MAX.TabIndex" type="System.Int32, mscorlib">
<value>154</value>
</data>
<data name="ROL_MAX.Text" xml:space="preserve">
<data name="H_ROL_MAX.Text" xml:space="preserve">
<value>4500</value>
</data>
<data name="&gt;&gt;ROL_MAX.Name" xml:space="preserve">
<value>ROL_MAX</value>
<data name="&gt;&gt;H_ROL_MAX.Name" xml:space="preserve">
<value>H_ROL_MAX</value>
</data>
<data name="&gt;&gt;ROL_MAX.Type" xml:space="preserve">
<data name="&gt;&gt;H_ROL_MAX.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;ROL_MAX.Parent" xml:space="preserve">
<data name="&gt;&gt;H_ROL_MAX.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;ROL_MAX.ZOrder" xml:space="preserve">
<data name="&gt;&gt;H_ROL_MAX.ZOrder" xml:space="preserve">
<value>21</value>
</data>
<data name="label23.AutoSize" type="System.Boolean, mscorlib">
@ -1161,76 +1155,76 @@
<data name="&gt;&gt;label18.ZOrder" xml:space="preserve">
<value>26</value>
</data>
<data name="SV3_POS.Location" type="System.Drawing.Point, System.Drawing">
<data name="H_SV3_POS.Location" type="System.Drawing.Point, System.Drawing">
<value>57, 314</value>
</data>
<data name="SV3_POS.Size" type="System.Drawing.Size, System.Drawing">
<data name="H_SV3_POS.Size" type="System.Drawing.Size, System.Drawing">
<value>39, 20</value>
</data>
<data name="SV3_POS.TabIndex" type="System.Int32, mscorlib">
<data name="H_SV3_POS.TabIndex" type="System.Int32, mscorlib">
<value>146</value>
</data>
<data name="SV3_POS.Text" xml:space="preserve">
<data name="H_SV3_POS.Text" xml:space="preserve">
<value>180</value>
</data>
<data name="&gt;&gt;SV3_POS.Name" xml:space="preserve">
<value>SV3_POS</value>
<data name="&gt;&gt;H_SV3_POS.Name" xml:space="preserve">
<value>H_SV3_POS</value>
</data>
<data name="&gt;&gt;SV3_POS.Type" xml:space="preserve">
<data name="&gt;&gt;H_SV3_POS.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;SV3_POS.Parent" xml:space="preserve">
<data name="&gt;&gt;H_SV3_POS.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;SV3_POS.ZOrder" xml:space="preserve">
<data name="&gt;&gt;H_SV3_POS.ZOrder" xml:space="preserve">
<value>27</value>
</data>
<data name="SV2_POS.Location" type="System.Drawing.Point, System.Drawing">
<data name="H_SV2_POS.Location" type="System.Drawing.Point, System.Drawing">
<value>57, 288</value>
</data>
<data name="SV2_POS.Size" type="System.Drawing.Size, System.Drawing">
<data name="H_SV2_POS.Size" type="System.Drawing.Size, System.Drawing">
<value>39, 20</value>
</data>
<data name="SV2_POS.TabIndex" type="System.Int32, mscorlib">
<data name="H_SV2_POS.TabIndex" type="System.Int32, mscorlib">
<value>145</value>
</data>
<data name="SV2_POS.Text" xml:space="preserve">
<data name="H_SV2_POS.Text" xml:space="preserve">
<value>60</value>
</data>
<data name="&gt;&gt;SV2_POS.Name" xml:space="preserve">
<value>SV2_POS</value>
<data name="&gt;&gt;H_SV2_POS.Name" xml:space="preserve">
<value>H_SV2_POS</value>
</data>
<data name="&gt;&gt;SV2_POS.Type" xml:space="preserve">
<data name="&gt;&gt;H_SV2_POS.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;SV2_POS.Parent" xml:space="preserve">
<data name="&gt;&gt;H_SV2_POS.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;SV2_POS.ZOrder" xml:space="preserve">
<data name="&gt;&gt;H_SV2_POS.ZOrder" xml:space="preserve">
<value>28</value>
</data>
<data name="SV1_POS.Location" type="System.Drawing.Point, System.Drawing">
<data name="H_SV1_POS.Location" type="System.Drawing.Point, System.Drawing">
<value>57, 262</value>
</data>
<data name="SV1_POS.Size" type="System.Drawing.Size, System.Drawing">
<data name="H_SV1_POS.Size" type="System.Drawing.Size, System.Drawing">
<value>39, 20</value>
</data>
<data name="SV1_POS.TabIndex" type="System.Int32, mscorlib">
<data name="H_SV1_POS.TabIndex" type="System.Int32, mscorlib">
<value>144</value>
</data>
<data name="SV1_POS.Text" xml:space="preserve">
<data name="H_SV1_POS.Text" xml:space="preserve">
<value>-60</value>
</data>
<data name="&gt;&gt;SV1_POS.Name" xml:space="preserve">
<value>SV1_POS</value>
<data name="&gt;&gt;H_SV1_POS.Name" xml:space="preserve">
<value>H_SV1_POS</value>
</data>
<data name="&gt;&gt;SV1_POS.Type" xml:space="preserve">
<data name="&gt;&gt;H_SV1_POS.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;SV1_POS.Parent" xml:space="preserve">
<data name="&gt;&gt;H_SV1_POS.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;SV1_POS.ZOrder" xml:space="preserve">
<data name="&gt;&gt;H_SV1_POS.ZOrder" xml:space="preserve">
<value>29</value>
</data>
<data name="HS3_REV.AutoSize" type="System.Boolean, mscorlib">
@ -1360,7 +1354,7 @@
<value>HS4</value>
</data>
<data name="&gt;&gt;HS4.Type" xml:space="preserve">
<value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;HS4.Parent" xml:space="preserve">
<value>$this</value>
@ -1381,7 +1375,7 @@
<value>HS3</value>
</data>
<data name="&gt;&gt;HS3.Type" xml:space="preserve">
<value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;HS3.Parent" xml:space="preserve">
<value>$this</value>
@ -1411,7 +1405,7 @@
<value>Gservoloc</value>
</data>
<data name="&gt;&gt;Gservoloc.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;Gservoloc.Parent" xml:space="preserve">
<value>$this</value>
@ -1576,6 +1570,6 @@
<value>ConfigTradHeli</value>
</data>
<data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
</data>
</root>

View File

@ -38,15 +38,15 @@
this.backstageView.Dock = System.Windows.Forms.DockStyle.Fill;
this.backstageView.Location = new System.Drawing.Point(0, 0);
this.backstageView.Name = "backstageView";
this.backstageView.Size = new System.Drawing.Size(823, 468);
this.backstageView.Size = new System.Drawing.Size(931, 468);
this.backstageView.TabIndex = 0;
//
// Setup
//
this.ClientSize = new System.Drawing.Size(823, 468);
this.ClientSize = new System.Drawing.Size(931, 468);
this.Controls.Add(this.backstageView);
this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
this.MinimumSize = new System.Drawing.Size(839, 506);
this.MinimumSize = new System.Drawing.Size(947, 506);
this.Name = "Setup";
this.Text = "Setup";
this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Setup_FormClosing);

View File

@ -267,7 +267,7 @@ namespace ArdupilotMega.GCSViews
continue;
}
if (!comPort.BaseStream.IsOpen)
lastdata = DateTime.MinValue;
lastdata = DateTime.Now;
// re-request servo data
if (!(lastdata.AddSeconds(8) > DateTime.Now) && comPort.BaseStream.IsOpen)
{
@ -479,7 +479,7 @@ namespace ArdupilotMega.GCSViews
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing));
routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing, gMapControl1));
}
else
{

View File

@ -550,7 +550,7 @@ namespace ArdupilotMega.GCSViews
{
reader.Read();
reader.ReadStartElement("CMD");
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
reader.ReadToFollowing("APM");
}
@ -3047,7 +3047,7 @@ namespace ArdupilotMega.GCSViews
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing) { ToolTipText = MainV2.cs.alt.ToString("0"), ToolTipMode = MarkerTooltipMode.Always });
routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing, MainMap) { ToolTipText = MainV2.cs.alt.ToString("0"), ToolTipMode = MarkerTooltipMode.Always });
}
else
{

View File

@ -157,7 +157,7 @@ namespace ArdupilotMega
{
reader.Read();
reader.ReadStartElement("LOGFORMAT");
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
reader.ReadToFollowing("APM");
}

View File

@ -1027,8 +1027,9 @@ namespace ArdupilotMega
public void requestDatastream(byte id, byte hzrate)
{
double pps = 0;
/*
switch (id)
{
case (byte)MAVLink.MAV_DATA_STREAM.ALL:
@ -1117,8 +1118,9 @@ namespace ArdupilotMega
{
return;
}
*/
log.InfoFormat("Request stream {0} at {1} hz : currently {2}", Enum.Parse(typeof(MAV_DATA_STREAM), id.ToString()), hzrate, pps);
log.InfoFormat("Request stream {0} at {1} hz", Enum.Parse(typeof(MAV_DATA_STREAM), id.ToString()), hzrate);
getDatastream(id, hzrate);
}

View File

@ -29,23 +29,56 @@
private void InitializeComponent()
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2));
this.MyView = new System.Windows.Forms.Panel();
this.MainMenu = new System.Windows.Forms.MenuStrip();
this.MenuFlightData = new System.Windows.Forms.ToolStripButton();
this.MenuFlightPlanner = new System.Windows.Forms.ToolStripButton();
this.MenuConfiguration = new System.Windows.Forms.ToolStripButton();
this.MenuSimulation = new System.Windows.Forms.ToolStripButton();
this.MenuFirmware = new System.Windows.Forms.ToolStripButton();
this.MenuConnect = new System.Windows.Forms.ToolStripButton();
this.CMB_serialport = new System.Windows.Forms.ToolStripComboBox();
this.MainMenu = new System.Windows.Forms.MenuStrip();
this.MenuTerminal = new System.Windows.Forms.ToolStripButton();
this.CMB_baudrate = new System.Windows.Forms.ToolStripComboBox();
this.TOOL_APMFirmware = new System.Windows.Forms.ToolStripComboBox();
this.MenuHelp = new System.Windows.Forms.ToolStripButton();
this.toolStripMenuItem1 = new System.Windows.Forms.ToolStripMenuItem();
this.MyView = new System.Windows.Forms.Panel();
this.MenuConnect = new System.Windows.Forms.ToolStripButton();
this.toolStripConnectionControl = new ArdupilotMega.Controls.ToolStripConnectionControl();
this.MainMenu.SuspendLayout();
this.SuspendLayout();
//
// MyView
//
this.MyView.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(38)))), ((int)(((byte)(39)))), ((int)(((byte)(40)))));
this.MyView.Dock = System.Windows.Forms.DockStyle.Fill;
this.MyView.ForeColor = System.Drawing.Color.White;
this.MyView.Location = new System.Drawing.Point(0, 76);
this.MyView.Margin = new System.Windows.Forms.Padding(0);
this.MyView.Name = "MyView";
this.MyView.Size = new System.Drawing.Size(1008, 461);
this.MyView.TabIndex = 3;
//
// MainMenu
//
this.MainMenu.BackColor = System.Drawing.SystemColors.Control;
this.MainMenu.BackgroundImage = ((System.Drawing.Image)(resources.GetObject("MainMenu.BackgroundImage")));
this.MainMenu.GripMargin = new System.Windows.Forms.Padding(0);
this.MainMenu.ImageScalingSize = new System.Drawing.Size(76, 76);
this.MainMenu.Items.AddRange(new System.Windows.Forms.ToolStripItem[] {
this.MenuFlightData,
this.MenuFlightPlanner,
this.MenuConfiguration,
this.MenuSimulation,
this.MenuFirmware,
this.MenuTerminal,
this.MenuHelp,
this.MenuConnect,
this.toolStripConnectionControl});
this.MainMenu.LayoutStyle = System.Windows.Forms.ToolStripLayoutStyle.HorizontalStackWithOverflow;
this.MainMenu.Location = new System.Drawing.Point(0, 0);
this.MainMenu.Name = "MainMenu";
this.MainMenu.Padding = new System.Windows.Forms.Padding(0);
this.MainMenu.RenderMode = System.Windows.Forms.ToolStripRenderMode.Professional;
this.MainMenu.Size = new System.Drawing.Size(1008, 76);
this.MainMenu.TabIndex = 5;
this.MainMenu.Text = "menuStrip1";
//
// MenuFlightData
//
this.MenuFlightData.AutoSize = false;
@ -114,57 +147,6 @@
this.MenuFirmware.ToolTipText = "Firmware";
this.MenuFirmware.Click += new System.EventHandler(this.MenuFirmware_Click);
//
// MenuConnect
//
this.MenuConnect.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
this.MenuConnect.AutoSize = false;
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
this.MenuConnect.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuConnect.ImageTransparentColor = System.Drawing.Color.Magenta;
this.MenuConnect.Margin = new System.Windows.Forms.Padding(0);
this.MenuConnect.Name = "MenuConnect";
this.MenuConnect.Padding = new System.Windows.Forms.Padding(0, 0, 72, 72);
this.MenuConnect.Size = new System.Drawing.Size(76, 76);
this.MenuConnect.Click += new System.EventHandler(this.MenuConnect_Click);
//
// CMB_serialport
//
this.CMB_serialport.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
this.CMB_serialport.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
this.CMB_serialport.Name = "CMB_serialport";
this.CMB_serialport.Size = new System.Drawing.Size(150, 76);
this.CMB_serialport.SelectedIndexChanged += new System.EventHandler(this.CMB_serialport_SelectedIndexChanged);
this.CMB_serialport.Enter += new System.EventHandler(this.CMB_serialport_Enter);
this.CMB_serialport.Click += new System.EventHandler(this.CMB_serialport_Click);
//
// MainMenu
//
this.MainMenu.AutoSize = false;
this.MainMenu.BackColor = System.Drawing.SystemColors.Control;
this.MainMenu.BackgroundImage = ((System.Drawing.Image)(resources.GetObject("MainMenu.BackgroundImage")));
this.MainMenu.GripMargin = new System.Windows.Forms.Padding(0);
this.MainMenu.ImageScalingSize = new System.Drawing.Size(76, 76);
this.MainMenu.Items.AddRange(new System.Windows.Forms.ToolStripItem[] {
this.MenuFlightData,
this.MenuFlightPlanner,
this.MenuConfiguration,
this.MenuSimulation,
this.MenuFirmware,
this.MenuTerminal,
this.MenuConnect,
this.CMB_baudrate,
this.CMB_serialport,
this.TOOL_APMFirmware,
this.MenuHelp});
this.MainMenu.LayoutStyle = System.Windows.Forms.ToolStripLayoutStyle.HorizontalStackWithOverflow;
this.MainMenu.Location = new System.Drawing.Point(0, 0);
this.MainMenu.Name = "MainMenu";
this.MainMenu.Padding = new System.Windows.Forms.Padding(0);
this.MainMenu.RenderMode = System.Windows.Forms.ToolStripRenderMode.Professional;
this.MainMenu.Size = new System.Drawing.Size(1008, 76);
this.MainMenu.TabIndex = 1;
this.MainMenu.Text = "menuStrip1";
//
// MenuTerminal
//
this.MenuTerminal.AutoSize = false;
@ -179,32 +161,6 @@
this.MenuTerminal.ToolTipText = "Terminal";
this.MenuTerminal.Click += new System.EventHandler(this.MenuTerminal_Click);
//
// CMB_baudrate
//
this.CMB_baudrate.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
this.CMB_baudrate.Items.AddRange(new object[] {
"4800",
"9600",
"14400",
"19200",
"28800",
"38400",
"57600",
"115200"});
this.CMB_baudrate.Name = "CMB_baudrate";
this.CMB_baudrate.Size = new System.Drawing.Size(76, 76);
this.CMB_baudrate.SelectedIndexChanged += new System.EventHandler(this.CMB_baudrate_SelectedIndexChanged);
this.CMB_baudrate.TextChanged += new System.EventHandler(this.CMB_baudrate_TextChanged);
//
// TOOL_APMFirmware
//
this.TOOL_APMFirmware.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
this.TOOL_APMFirmware.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
this.TOOL_APMFirmware.MaxDropDownItems = 2;
this.TOOL_APMFirmware.Name = "TOOL_APMFirmware";
this.TOOL_APMFirmware.Size = new System.Drawing.Size(121, 76);
this.TOOL_APMFirmware.SelectedIndexChanged += new System.EventHandler(this.TOOL_APMFirmware_SelectedIndexChanged);
//
// MenuHelp
//
this.MenuHelp.AutoSize = false;
@ -219,22 +175,25 @@
this.MenuHelp.ToolTipText = "Terminal";
this.MenuHelp.Click += new System.EventHandler(this.MenuHelp_Click);
//
// toolStripMenuItem1
// MenuConnect
//
this.toolStripMenuItem1.Name = "toolStripMenuItem1";
this.toolStripMenuItem1.Size = new System.Drawing.Size(141, 20);
this.toolStripMenuItem1.Text = "toolStripMenuItem1";
this.MenuConnect.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
this.MenuConnect.AutoSize = false;
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
this.MenuConnect.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuConnect.ImageTransparentColor = System.Drawing.Color.Magenta;
this.MenuConnect.Margin = new System.Windows.Forms.Padding(0);
this.MenuConnect.Name = "MenuConnect";
this.MenuConnect.Padding = new System.Windows.Forms.Padding(0, 0, 72, 72);
this.MenuConnect.Size = new System.Drawing.Size(76, 76);
this.MenuConnect.Click += new System.EventHandler(this.MenuConnect_Click);
//
// MyView
// toolStripConnectionControl
//
this.MyView.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(38)))), ((int)(((byte)(39)))), ((int)(((byte)(40)))));
this.MyView.Dock = System.Windows.Forms.DockStyle.Fill;
this.MyView.ForeColor = System.Drawing.Color.White;
this.MyView.Location = new System.Drawing.Point(0, 76);
this.MyView.Margin = new System.Windows.Forms.Padding(0);
this.MyView.Name = "MyView";
this.MyView.Size = new System.Drawing.Size(1008, 461);
this.MyView.TabIndex = 3;
this.toolStripConnectionControl.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
this.toolStripConnectionControl.BackColor = System.Drawing.Color.Transparent;
this.toolStripConnectionControl.Name = "toolStripConnectionControl";
this.toolStripConnectionControl.Size = new System.Drawing.Size(203, 73);
//
// MainV2
//
@ -257,26 +216,24 @@
this.MainMenu.ResumeLayout(false);
this.MainMenu.PerformLayout();
this.ResumeLayout(false);
this.PerformLayout();
}
#endregion
private System.Windows.Forms.Panel MyView;
private System.Windows.Forms.MenuStrip MainMenu;
private System.Windows.Forms.ToolStripButton MenuFlightData;
private System.Windows.Forms.ToolStripButton MenuFlightPlanner;
private System.Windows.Forms.ToolStripButton MenuConfiguration;
private System.Windows.Forms.ToolStripButton MenuSimulation;
private System.Windows.Forms.ToolStripButton MenuFirmware;
private System.Windows.Forms.ToolStripComboBox CMB_serialport;
private System.Windows.Forms.ToolStripButton MenuConnect;
private System.Windows.Forms.MenuStrip MainMenu;
private System.Windows.Forms.ToolStripMenuItem toolStripMenuItem1;
private System.Windows.Forms.ToolStripComboBox CMB_baudrate;
private System.Windows.Forms.Panel MyView;
private System.Windows.Forms.ToolStripButton MenuTerminal;
private System.Windows.Forms.ToolStripComboBox TOOL_APMFirmware;
private System.Windows.Forms.ToolStripButton MenuConnect;
private System.Windows.Forms.ToolStripButton MenuHelp;
//public static WebCam_Capture.WebCamCapture webCamCapture1;
private ArdupilotMega.Controls.ToolStripConnectionControl toolStripConnectionControl;
}
}

View File

@ -31,6 +31,8 @@ namespace ArdupilotMega
{
private static readonly ILog log =
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
// used to hide/show console window
[DllImport("user32.dll")]
public static extern int FindWindow(string szClass, string szTitle);
[DllImport("user32.dll")]
@ -39,41 +41,88 @@ namespace ArdupilotMega
const int SW_SHOWNORMAL = 1;
const int SW_HIDE = 0;
/// <summary>
/// Main Comport interface
/// </summary>
public static MAVLink comPort = new MAVLink();
/// <summary>
/// Comport name
/// </summary>
public static string comPortName = "";
/// <summary>
/// use to store all internal config
/// </summary>
public static Hashtable config = new Hashtable();
/// <summary>
/// used to prevent comport access for exclusive use
/// </summary>
public static bool giveComport = false;
public static Firmwares APMFirmware = Firmwares.ArduPlane;
/// <summary>
/// mono detection
/// </summary>
public static bool MONO = false;
/// <summary>
/// speech engein enable
/// </summary>
public static bool speechEnable = false;
/// <summary>
/// spech engine static class
/// </summary>
public static Speech speechEngine = null;
/// <summary>
/// joystick static class
/// </summary>
public static Joystick joystick = null;
/// <summary>
/// track last joystick packet sent. used to track timming
/// </summary>
DateTime lastjoystick = DateTime.Now;
/// <summary>
/// hud background image grabber from a video stream - not realy that efficent. ie no hardware overlays etc.
/// </summary>
public static WebCamService.Capture cam = null;
/// <summary>
/// the static global state of the currently connected MAV
/// </summary>
public static CurrentState cs = new CurrentState();
/// <summary>
/// controls the main serial reader thread
/// </summary>
bool serialThread = false;
/// <summary>
/// unused at this point - potential to move all forms to this single binding source. need to evalutate performance/exception issues
/// </summary>
static internal BindingSource bs;
TcpListener listener;
DateTime heatbeatSend = DateTime.Now;
/// <summary>
/// used for mini https server for websockets/mjpeg video stream, and network link kmls
/// </summary>
private TcpListener listener;
/// <summary>
/// track the last heartbeat sent
/// </summary>
private DateTime heatbeatSend = DateTime.Now;
/// <summary>
/// used to call anything as needed.
/// </summary>
public static MainV2 instance = null;
/// <summary>
/// used to feed in a network link kml to the http server
/// </summary>
public string georefkml = "";
/// <summary>
/// enum of firmwares
/// </summary>
public enum Firmwares
{
ArduPlane,
ArduCopter2,
}
/// <summary>
/// declared here if i want a "single" instance of the form
/// ie configuration gets reloaded on every click
/// </summary>
GCSViews.FlightData FlightData;
GCSViews.FlightPlanner FlightPlanner;
GCSViews.Configuration Configuration;
@ -82,13 +131,20 @@ namespace ArdupilotMega
GCSViews.Firmware Firmware;
GCSViews.Terminal Terminal;
/// <summary>
/// control for the serial port and firmware selector.
/// </summary>
private ConnectionControl _connectionControl;
public MainV2()
{
Form splash = new Splash();
splash.Show();
string strVersion = System.Reflection.Assembly.GetExecutingAssembly().GetName().Version.ToString();
strVersion = "";
strVersion = "mav " + MAVLink.MAVLINK_WIRE_PROTOCOL_VERSION;
splash.Text = "APM Planner " + Application.ProductVersion + " " + strVersion + " By Michael Oborne";
splash.Refresh();
@ -98,6 +154,14 @@ namespace ArdupilotMega
instance = this;
InitializeComponent();
_connectionControl = toolStripConnectionControl.ConnectionControl;
_connectionControl.CMB_baudrate.TextChanged += this.CMB_baudrate_TextChanged;
_connectionControl.CMB_baudrate.SelectedIndexChanged += this.CMB_baudrate_SelectedIndexChanged;
_connectionControl.CMB_serialport.SelectedIndexChanged += this.CMB_serialport_SelectedIndexChanged;
_connectionControl.CMB_serialport.Enter += this.CMB_serialport_Enter;
_connectionControl.CMB_serialport.Click += this.CMB_serialport_Click;
_connectionControl.TOOL_APMFirmware.SelectedIndexChanged += this.TOOL_APMFirmware_SelectedIndexChanged;
srtm.datadirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "srtm";
@ -113,24 +177,35 @@ namespace ArdupilotMega
List<object> list = new List<object>();
foreach (object obj in Enum.GetValues(typeof(Firmwares)))
{
TOOL_APMFirmware.Items.Add(obj);
_connectionControl.TOOL_APMFirmware.Items.Add(obj);
}
if (TOOL_APMFirmware.Items.Count > 0)
TOOL_APMFirmware.SelectedIndex = 0;
if (_connectionControl.TOOL_APMFirmware.Items.Count > 0)
_connectionControl.TOOL_APMFirmware.SelectedIndex = 0;
this.Text = splash.Text;
comPort.BaseStream.BaudRate = 115200;
CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
CMB_serialport.Items.Add("TCP");
CMB_serialport.Items.Add("UDP");
if (CMB_serialport.Items.Count > 0)
// ** Old
// CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
// CMB_serialport.Items.Add("TCP");
// CMB_serialport.Items.Add("UDP");
// if (CMB_serialport.Items.Count > 0)
// {
// CMB_baudrate.SelectedIndex = 7;
// CMB_serialport.SelectedIndex = 0;
// }
// ** new
_connectionControl.CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
_connectionControl.CMB_serialport.Items.Add("TCP");
_connectionControl.CMB_serialport.Items.Add("UDP");
if (_connectionControl.CMB_serialport.Items.Count > 0)
{
CMB_baudrate.SelectedIndex = 7;
CMB_serialport.SelectedIndex = 0;
_connectionControl.CMB_baudrate.SelectedIndex = 7;
_connectionControl.CMB_serialport.SelectedIndex = 0;
}
// ** Done
splash.Refresh();
Application.DoEvents();
@ -172,7 +247,7 @@ namespace ArdupilotMega
if (MainV2.config["CHK_GDIPlus"] != null)
GCSViews.FlightData.myhud.UseOpenGL = !bool.Parse(MainV2.config["CHK_GDIPlus"].ToString());
changeunits();
ChangeUnits();
try
{
@ -258,6 +333,9 @@ namespace ArdupilotMega
splash.Close();
}
/// <summary>
/// used to create planner screenshots - access by control-s
/// </summary>
internal void ScreenShot()
{
Rectangle bounds = Screen.GetBounds(Point.Empty);
@ -276,13 +354,13 @@ namespace ArdupilotMega
private void CMB_serialport_Click(object sender, EventArgs e)
{
string oldport = CMB_serialport.Text;
CMB_serialport.Items.Clear();
CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
CMB_serialport.Items.Add("TCP");
CMB_serialport.Items.Add("UDP");
if (CMB_serialport.Items.Contains(oldport))
CMB_serialport.Text = oldport;
string oldport = _connectionControl.CMB_serialport.Text;
_connectionControl.CMB_serialport.Items.Clear();
_connectionControl.CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
_connectionControl.CMB_serialport.Items.Add("TCP");
_connectionControl.CMB_serialport.Items.Add("UDP");
if (_connectionControl.CMB_serialport.Items.Contains(oldport))
_connectionControl.CMB_serialport.Text = oldport;
}
@ -474,11 +552,11 @@ namespace ArdupilotMega
}
else
{
if (CMB_serialport.Text == "TCP")
if (_connectionControl.CMB_serialport.Text == "TCP")
{
comPort.BaseStream = new TcpSerial();
}
else if (CMB_serialport.Text == "UDP")
if (_connectionControl.CMB_serialport.Text == "UDP")
{
comPort.BaseStream = new UdpSerial();
}
@ -490,31 +568,32 @@ namespace ArdupilotMega
try
{
// set port, then options
comPort.BaseStream.PortName = CMB_serialport.Text;
comPort.BaseStream.PortName = _connectionControl.CMB_serialport.Text;
comPort.BaseStream.DataBits = 8;
comPort.BaseStream.StopBits = (StopBits)Enum.Parse(typeof(StopBits), "1");
comPort.BaseStream.Parity = (Parity)Enum.Parse(typeof(Parity), "None");
try
{
comPort.BaseStream.BaudRate = int.Parse(CMB_baudrate.Text);
comPort.BaseStream.BaudRate = int.Parse(_connectionControl.CMB_baudrate.Text);
}
catch { }
if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true)
comPort.BaseStream.toggleDTR();
// false here
comPort.BaseStream.DtrEnable = false;
comPort.BaseStream.RtsEnable = false;
if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true)
comPort.BaseStream.toggleDTR();
// if reset on connect is on dtr will be true here
// cleanup from any previous sessions
if (comPort.logfile != null)
comPort.logfile.Close();
if (comPort.rawlogfile != null)
comPort.rawlogfile.Close();
// setup to record new logs
try
{
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
@ -524,39 +603,44 @@ namespace ArdupilotMega
}
catch { CustomMessageBox.Show("Failed to create log - wont log this session"); } // soft fail
// do the connect
comPort.Open(true);
// detect firmware we are conected to.
if (comPort.param["SYSID_SW_TYPE"] != null)
{
if (float.Parse(comPort.param["SYSID_SW_TYPE"].ToString()) == 10)
{
TOOL_APMFirmware.SelectedIndex = TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduCopter2);
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduCopter2);
}
else if (float.Parse(comPort.param["SYSID_SW_TYPE"].ToString()) == 0)
{
TOOL_APMFirmware.SelectedIndex = TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduPlane);
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduPlane);
}
}
cs.firmware = APMFirmware;
config[CMB_serialport.Text + "_BAUD"] = CMB_baudrate.Text;
// save the baudrate for this port
config[_connectionControl.CMB_serialport.Text + "_BAUD"] = _connectionControl.CMB_baudrate.Text;
// load wps on connect option.
if (config["loadwpsonconnect"] != null && bool.Parse(config["loadwpsonconnect"].ToString()) == true)
{
MenuFlightPlanner_Click(null, null);
FlightPlanner.BUT_read_Click(null, null);
}
// set connected icon
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.disconnect;
}
catch (Exception ex)
{
log.Warn(ex.ToString());
try
{
comPort.Close();
}
catch { }
// detect firmware -> scan eeprom contents -> error if no valid ap param/apvar header detected.
try
{
string version = ArduinoDetect.DetectVersion(comPort.BaseStream.PortName);
@ -601,10 +685,10 @@ namespace ArdupilotMega
private void CMB_serialport_SelectedIndexChanged(object sender, EventArgs e)
{
comPortName = CMB_serialport.Text;
comPortName = _connectionControl.CMB_serialport.Text;
if (comPortName == "UDP" || comPortName == "TCP")
{
CMB_baudrate.Enabled = false;
_connectionControl.CMB_baudrate.Enabled = false;
if (comPortName == "TCP")
MainV2.comPort.BaseStream = new TcpSerial();
if (comPortName == "UDP")
@ -612,35 +696,32 @@ namespace ArdupilotMega
}
else
{
CMB_baudrate.Enabled = true;
_connectionControl.CMB_baudrate.Enabled = true;
MainV2.comPort.BaseStream = new ArdupilotMega.SerialPort();
}
try
{
comPort.BaseStream.PortName = CMB_serialport.Text;
comPort.BaseStream.PortName = _connectionControl.CMB_serialport.Text;
MainV2.comPort.BaseStream.BaudRate = int.Parse(CMB_baudrate.Text);
MainV2.comPort.BaseStream.BaudRate = int.Parse(_connectionControl.CMB_baudrate.Text);
if (config[CMB_serialport.Text + "_BAUD"] != null)
// check for saved baud rate and restore
if (config[_connectionControl.CMB_serialport.Text + "_BAUD"] != null)
{
CMB_baudrate.Text = config[CMB_serialport.Text + "_BAUD"].ToString();
_connectionControl.CMB_baudrate.Text = config[_connectionControl.CMB_serialport.Text + "_BAUD"].ToString();
}
}
catch { }
}
private void toolStripMenuItem2_Click(object sender, EventArgs e)
{
//Form temp = new Main();
//temp.Show();
}
private void MainV2_FormClosed(object sender, FormClosedEventArgs e)
{
// shutdown threads
GCSViews.FlightData.threadrun = 0;
GCSViews.Simulation.threadrun = 0;
// shutdown local thread
serialThread = false;
try
@ -665,6 +746,8 @@ namespace ArdupilotMega
}
catch { }
// save config
xmlconfig(true);
}
@ -675,8 +758,6 @@ namespace ArdupilotMega
{
try
{
//System.Configuration.Configuration appconfig = System.Configuration.ConfigurationManager.OpenExeConfiguration(System.Configuration.ConfigurationUserLevel.None);
XmlTextWriter xmlwriter = new XmlTextWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"config.xml", Encoding.ASCII);
xmlwriter.Formatting = Formatting.Indented;
@ -686,13 +767,9 @@ namespace ArdupilotMega
xmlwriter.WriteElementString("comport", comPortName);
xmlwriter.WriteElementString("baudrate", CMB_baudrate.Text);
xmlwriter.WriteElementString("baudrate", _connectionControl.CMB_baudrate.Text);
xmlwriter.WriteElementString("APMFirmware", APMFirmware.ToString());
//appconfig.AppSettings.Settings.Add("comport", comportname);
//appconfig.AppSettings.Settings.Add("baudrate", CMB_baudrate.Text);
//appconfig.AppSettings.Settings.Add("APMFirmware", APMFirmware.ToString());
xmlwriter.WriteElementString("APMFirmware", MainV2.cs.firmware.ToString());
foreach (string key in config.Keys)
{
@ -701,8 +778,6 @@ namespace ArdupilotMega
if (key == "" || key.Contains("/")) // "/dev/blah"
continue;
xmlwriter.WriteElementString(key, config[key].ToString());
//appconfig.AppSettings.Settings.Add(key, config[key].ToString());
}
catch { }
}
@ -711,8 +786,6 @@ namespace ArdupilotMega
xmlwriter.WriteEndDocument();
xmlwriter.Close();
//appconfig.Save();
}
catch (Exception ex) { CustomMessageBox.Show(ex.ToString()); }
}
@ -732,10 +805,10 @@ namespace ArdupilotMega
case "comport":
string temp = xmlreader.ReadString();
CMB_serialport.SelectedIndex = CMB_serialport.FindString(temp);
if (CMB_serialport.SelectedIndex == -1)
_connectionControl.CMB_serialport.SelectedIndex = _connectionControl.CMB_serialport.FindString(temp);
if (_connectionControl.CMB_serialport.SelectedIndex == -1)
{
CMB_serialport.Text = temp; // allows ports that dont exist - yet
_connectionControl.CMB_serialport.Text = temp; // allows ports that dont exist - yet
}
comPort.BaseStream.PortName = temp;
comPortName = temp;
@ -743,20 +816,20 @@ namespace ArdupilotMega
case "baudrate":
string temp2 = xmlreader.ReadString();
CMB_baudrate.SelectedIndex = CMB_baudrate.FindString(temp2);
if (CMB_baudrate.SelectedIndex == -1)
_connectionControl.CMB_baudrate.SelectedIndex = _connectionControl.CMB_baudrate.FindString(temp2);
if (_connectionControl.CMB_baudrate.SelectedIndex == -1)
{
CMB_baudrate.Text = temp2;
_connectionControl.CMB_baudrate.Text = temp2;
//CMB_baudrate.SelectedIndex = CMB_baudrate.FindString("57600"); ; // must exist
}
//bau = int.Parse(CMB_baudrate.Text);
break;
case "APMFirmware":
string temp3 = xmlreader.ReadString();
TOOL_APMFirmware.SelectedIndex = TOOL_APMFirmware.FindStringExact(temp3);
if (TOOL_APMFirmware.SelectedIndex == -1)
TOOL_APMFirmware.SelectedIndex = 0;
APMFirmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), TOOL_APMFirmware.Text);
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.FindStringExact(temp3);
if (_connectionControl.TOOL_APMFirmware.SelectedIndex == -1)
_connectionControl.TOOL_APMFirmware.SelectedIndex = 0;
MainV2.cs.firmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), _connectionControl.TOOL_APMFirmware.Text);
break;
case "Config":
break;
@ -781,11 +854,16 @@ namespace ArdupilotMega
{
try
{
comPort.BaseStream.BaudRate = int.Parse(CMB_baudrate.Text);
comPort.BaseStream.BaudRate = int.Parse(_connectionControl.CMB_baudrate.Text);
}
catch
{
}
catch { }
}
/// <summary>
/// thread used to send joystick packets to the MAV
/// </summary>
private void joysticksend()
{
@ -870,10 +948,11 @@ namespace ArdupilotMega
DateTime connectButtonUpdate = DateTime.Now;
/// <summary>
/// Used to fix the icon status for unexpected unplugs etc...
/// </summary>
private void updateConnectIcon()
{
if ((DateTime.Now - connectButtonUpdate).Milliseconds > 500)
{
// Console.WriteLine(DateTime.Now.Millisecond);
@ -885,8 +964,8 @@ namespace ArdupilotMega
{
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.disconnect;
this.MenuConnect.BackgroundImage.Tag = "Disconnect";
CMB_baudrate.Enabled = false;
CMB_serialport.Enabled = false;
_connectionControl.CMB_baudrate.Enabled = false;
_connectionControl.CMB_serialport.Enabled = false;
});
}
}
@ -898,8 +977,8 @@ namespace ArdupilotMega
{
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
this.MenuConnect.BackgroundImage.Tag = "Connect";
CMB_baudrate.Enabled = true;
CMB_serialport.Enabled = true;
_connectionControl.CMB_baudrate.Enabled = true;
_connectionControl.CMB_serialport.Enabled = true;
});
}
}
@ -907,7 +986,16 @@ namespace ArdupilotMega
}
}
/// <summary>
/// main serial reader thread
/// controls
/// serial reading
/// link quality stats
/// speech voltage - custom - alt warning - data lost
/// heartbeat packet sending
///
/// and cant fall out
/// </summary>
private void SerialReader()
{
if (serialThread == true)
@ -1089,6 +1177,7 @@ namespace ArdupilotMega
// for long running tasks using own threads.
// for short use threadpool
// setup http server
try
{
listener = new TcpListener(IPAddress.Any, 56781);
@ -1104,6 +1193,7 @@ namespace ArdupilotMega
CustomMessageBox.Show(ex.ToString());
}
/// setup joystick packet sender
new Thread(new ThreadStart(joysticksend))
{
IsBackground = true,
@ -1111,12 +1201,14 @@ namespace ArdupilotMega
Name = "Main joystick sender"
}.Start();
// setup main serial reader
new Thread(SerialReader)
{
IsBackground = true,
Name = "Main Serial reader"
}.Start();
// check for updates
if (Debugger.IsAttached)
{
log.Info("Skipping update test as it appears we are debugging");
@ -1134,6 +1226,7 @@ namespace ArdupilotMega
}
}
public static String ComputeWebSocketHandshakeSecurityHash09(String secWebSocketKey)
{
const String MagicKEY = "258EAFA5-E914-47DA-95CA-C5AB0DC85B11";
@ -1155,7 +1248,6 @@ namespace ArdupilotMega
/// <summary>
/// little web server for sending network link kml's
/// </summary>
void listernforclients()
{
try
@ -1440,8 +1532,7 @@ namespace ArdupilotMega
private void TOOL_APMFirmware_SelectedIndexChanged(object sender, EventArgs e)
{
APMFirmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), TOOL_APMFirmware.Text);
MainV2.cs.firmware = APMFirmware;
MainV2.cs.firmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), _connectionControl.TOOL_APMFirmware.Text);
}
private void MainV2_Resize(object sender, EventArgs e)
@ -1858,7 +1949,12 @@ namespace ArdupilotMega
}
/// <summary>
/// trying to replicate google code etags....... this doesnt work.
/// </summary>
/// <param name="fileName"></param>
/// <param name="modifyDate"></param>
/// <returns></returns>
private string GetFileETag(string fileName, DateTime modifyDate)
{
@ -1892,29 +1988,34 @@ namespace ArdupilotMega
}
/// <summary>
/// keyboard shortcuts override
/// </summary>
/// <param name="msg"></param>
/// <param name="keyData"></param>
/// <returns></returns>
protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
{
if (keyData == (Keys.Control | Keys.F))
if (keyData == (Keys.Control | Keys.F)) // temp
{
Form frm = new temp();
ThemeManager.ApplyThemeTo(frm);
frm.Show();
return true;
}
if (keyData == (Keys.Control | Keys.S))
if (keyData == (Keys.Control | Keys.S)) // screenshot
{
ScreenShot();
return true;
}
if (keyData == (Keys.Control | Keys.G)) // test
if (keyData == (Keys.Control | Keys.G)) // nmea out
{
Form frm = new SerialOutput();
ThemeManager.ApplyThemeTo(frm);
frm.Show();
return true;
}
if (keyData == (Keys.Control | Keys.A)) // test
if (keyData == (Keys.Control | Keys.A)) // 3dr radio
{
Form temp = new Form();
Control frm = new _3DRradio();
@ -1925,7 +2026,7 @@ namespace ArdupilotMega
temp.Show();
return true;
}
if (keyData == (Keys.Control | Keys.W)) // test
if (keyData == (Keys.Control | Keys.W)) // test ac config
{
Controls.ConfigPanel cfg = new Controls.ConfigPanel();
@ -2026,7 +2127,7 @@ namespace ArdupilotMega
return "";
}
public void changeunits()
public void ChangeUnits()
{
try
{
@ -2070,24 +2171,29 @@ namespace ArdupilotMega
catch { }
}
private void CMB_baudrate_TextChanged(object sender, EventArgs e)
{
StringBuilder sb = new StringBuilder();
int baud = 0;
for (int i = 0; i < CMB_baudrate.Text.Length; i++)
if (char.IsDigit(CMB_baudrate.Text[i]))
for (int i = 0; i < _connectionControl.CMB_baudrate.Text.Length; i++)
if (char.IsDigit(_connectionControl.CMB_baudrate.Text[i]))
{
sb.Append(CMB_baudrate.Text[i]);
baud = baud * 10 + CMB_baudrate.Text[i] - '0';
sb.Append(_connectionControl.CMB_baudrate.Text[i]);
baud = baud * 10 + _connectionControl.CMB_baudrate.Text[i] - '0';
}
if (CMB_baudrate.Text != sb.ToString())
CMB_baudrate.Text = sb.ToString();
if (_connectionControl.CMB_baudrate.Text != sb.ToString())
{
_connectionControl.CMB_baudrate.Text = sb.ToString();
}
try
{
if (baud > 0 && comPort.BaseStream.BaudRate != baud)
comPort.BaseStream.BaudRate = baud;
}
catch (Exception) { }
catch (Exception)
{
}
}
private void CMB_serialport_Enter(object sender, EventArgs e)

View File

@ -118,7 +118,7 @@
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<metadata name="MainMenu.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>127, 17</value>
<value>17, 17</value>
</metadata>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="MainMenu.BackgroundImage" type="System.Drawing.Bitmap, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">

View File

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

View File

@ -56,6 +56,16 @@
this.RS2 = new System.Windows.Forms.ComboBox();
this.RS1 = new System.Windows.Forms.ComboBox();
this.RSSI = new System.Windows.Forms.TextBox();
this.S10 = new System.Windows.Forms.ComboBox();
this.S11 = new System.Windows.Forms.ComboBox();
this.S12 = new System.Windows.Forms.ComboBox();
this.RS12 = new System.Windows.Forms.ComboBox();
this.RS11 = new System.Windows.Forms.ComboBox();
this.RS10 = new System.Windows.Forms.ComboBox();
this.S9 = new System.Windows.Forms.ComboBox();
this.S8 = new System.Windows.Forms.ComboBox();
this.RS8 = new System.Windows.Forms.ComboBox();
this.RS9 = new System.Windows.Forms.ComboBox();
this.RS0 = new System.Windows.Forms.TextBox();
this.label9 = new System.Windows.Forms.Label();
this.label10 = new System.Windows.Forms.Label();
@ -70,6 +80,27 @@
this.BUT_syncS2 = new ArdupilotMega.MyButton();
this.BUT_syncS3 = new ArdupilotMega.MyButton();
this.BUT_syncS5 = new ArdupilotMega.MyButton();
this.label13 = new System.Windows.Forms.Label();
this.label14 = new System.Windows.Forms.Label();
this.label15 = new System.Windows.Forms.Label();
this.label16 = new System.Windows.Forms.Label();
this.label17 = new System.Windows.Forms.Label();
this.label20 = new System.Windows.Forms.Label();
this.label21 = new System.Windows.Forms.Label();
this.label22 = new System.Windows.Forms.Label();
this.label23 = new System.Windows.Forms.Label();
this.label24 = new System.Windows.Forms.Label();
this.label25 = new System.Windows.Forms.Label();
this.label26 = new System.Windows.Forms.Label();
this.label27 = new System.Windows.Forms.Label();
this.label28 = new System.Windows.Forms.Label();
this.label29 = new System.Windows.Forms.Label();
this.label30 = new System.Windows.Forms.Label();
this.label31 = new System.Windows.Forms.Label();
this.label32 = new System.Windows.Forms.Label();
this.BUT_syncS8 = new ArdupilotMega.MyButton();
this.BUT_syncS9 = new ArdupilotMega.MyButton();
this.BUT_syncS10 = new ArdupilotMega.MyButton();
this.SuspendLayout();
//
// Progressbar
@ -263,6 +294,7 @@
//
// RS4
//
resources.ApplyResources(this.RS4, "RS4");
this.RS4.FormattingEnabled = true;
this.RS4.Items.AddRange(new object[] {
resources.GetString("RS4.Items"),
@ -286,12 +318,12 @@
resources.GetString("RS4.Items18"),
resources.GetString("RS4.Items19"),
resources.GetString("RS4.Items20")});
resources.ApplyResources(this.RS4, "RS4");
this.RS4.Name = "RS4";
this.toolTip1.SetToolTip(this.RS4, resources.GetString("RS4.ToolTip"));
//
// RS3
//
resources.ApplyResources(this.RS3, "RS3");
this.RS3.FormattingEnabled = true;
this.RS3.Items.AddRange(new object[] {
resources.GetString("RS3.Items"),
@ -324,12 +356,12 @@
resources.GetString("RS3.Items27"),
resources.GetString("RS3.Items28"),
resources.GetString("RS3.Items29")});
resources.ApplyResources(this.RS3, "RS3");
this.RS3.Name = "RS3";
this.toolTip1.SetToolTip(this.RS3, resources.GetString("RS3.ToolTip"));
//
// RS2
//
resources.ApplyResources(this.RS2, "RS2");
this.RS2.FormattingEnabled = true;
this.RS2.Items.AddRange(new object[] {
resources.GetString("RS2.Items"),
@ -342,12 +374,12 @@
resources.GetString("RS2.Items7"),
resources.GetString("RS2.Items8"),
resources.GetString("RS2.Items9")});
resources.ApplyResources(this.RS2, "RS2");
this.RS2.Name = "RS2";
this.toolTip1.SetToolTip(this.RS2, resources.GetString("RS2.ToolTip"));
//
// RS1
//
resources.ApplyResources(this.RS1, "RS1");
this.RS1.FormattingEnabled = true;
this.RS1.Items.AddRange(new object[] {
resources.GetString("RS1.Items"),
@ -359,7 +391,6 @@
resources.GetString("RS1.Items6"),
resources.GetString("RS1.Items7"),
resources.GetString("RS1.Items8")});
resources.ApplyResources(this.RS1, "RS1");
this.RS1.Name = "RS1";
this.toolTip1.SetToolTip(this.RS1, resources.GetString("RS1.ToolTip"));
//
@ -370,6 +401,183 @@
this.RSSI.ReadOnly = true;
this.toolTip1.SetToolTip(this.RSSI, resources.GetString("RSSI.ToolTip"));
//
// S10
//
this.S10.FormattingEnabled = true;
this.S10.Items.AddRange(new object[] {
resources.GetString("S10.Items"),
resources.GetString("S10.Items1"),
resources.GetString("S10.Items2"),
resources.GetString("S10.Items3"),
resources.GetString("S10.Items4"),
resources.GetString("S10.Items5"),
resources.GetString("S10.Items6"),
resources.GetString("S10.Items7"),
resources.GetString("S10.Items8"),
resources.GetString("S10.Items9"),
resources.GetString("S10.Items10"),
resources.GetString("S10.Items11"),
resources.GetString("S10.Items12"),
resources.GetString("S10.Items13"),
resources.GetString("S10.Items14"),
resources.GetString("S10.Items15"),
resources.GetString("S10.Items16"),
resources.GetString("S10.Items17"),
resources.GetString("S10.Items18")});
resources.ApplyResources(this.S10, "S10");
this.S10.Name = "S10";
this.toolTip1.SetToolTip(this.S10, resources.GetString("S10.ToolTip"));
//
// S11
//
this.S11.FormattingEnabled = true;
this.S11.Items.AddRange(new object[] {
resources.GetString("S11.Items"),
resources.GetString("S11.Items1"),
resources.GetString("S11.Items2"),
resources.GetString("S11.Items3"),
resources.GetString("S11.Items4"),
resources.GetString("S11.Items5"),
resources.GetString("S11.Items6"),
resources.GetString("S11.Items7"),
resources.GetString("S11.Items8"),
resources.GetString("S11.Items9")});
resources.ApplyResources(this.S11, "S11");
this.S11.Name = "S11";
this.toolTip1.SetToolTip(this.S11, resources.GetString("S11.ToolTip"));
//
// S12
//
this.S12.FormattingEnabled = true;
this.S12.Items.AddRange(new object[] {
resources.GetString("S12.Items"),
resources.GetString("S12.Items1")});
resources.ApplyResources(this.S12, "S12");
this.S12.Name = "S12";
this.toolTip1.SetToolTip(this.S12, resources.GetString("S12.ToolTip"));
//
// RS12
//
resources.ApplyResources(this.RS12, "RS12");
this.RS12.FormattingEnabled = true;
this.RS12.Items.AddRange(new object[] {
resources.GetString("RS12.Items"),
resources.GetString("RS12.Items1")});
this.RS12.Name = "RS12";
this.toolTip1.SetToolTip(this.RS12, resources.GetString("RS12.ToolTip"));
//
// RS11
//
resources.ApplyResources(this.RS11, "RS11");
this.RS11.FormattingEnabled = true;
this.RS11.Items.AddRange(new object[] {
resources.GetString("RS11.Items"),
resources.GetString("RS11.Items1"),
resources.GetString("RS11.Items2"),
resources.GetString("RS11.Items3"),
resources.GetString("RS11.Items4"),
resources.GetString("RS11.Items5"),
resources.GetString("RS11.Items6"),
resources.GetString("RS11.Items7"),
resources.GetString("RS11.Items8"),
resources.GetString("RS11.Items9")});
this.RS11.Name = "RS11";
this.toolTip1.SetToolTip(this.RS11, resources.GetString("RS11.ToolTip"));
//
// RS10
//
resources.ApplyResources(this.RS10, "RS10");
this.RS10.FormattingEnabled = true;
this.RS10.Items.AddRange(new object[] {
resources.GetString("RS10.Items"),
resources.GetString("RS10.Items1"),
resources.GetString("RS10.Items2"),
resources.GetString("RS10.Items3"),
resources.GetString("RS10.Items4"),
resources.GetString("RS10.Items5"),
resources.GetString("RS10.Items6"),
resources.GetString("RS10.Items7"),
resources.GetString("RS10.Items8"),
resources.GetString("RS10.Items9"),
resources.GetString("RS10.Items10"),
resources.GetString("RS10.Items11"),
resources.GetString("RS10.Items12"),
resources.GetString("RS10.Items13"),
resources.GetString("RS10.Items14"),
resources.GetString("RS10.Items15"),
resources.GetString("RS10.Items16"),
resources.GetString("RS10.Items17"),
resources.GetString("RS10.Items18")});
this.RS10.Name = "RS10";
this.toolTip1.SetToolTip(this.RS10, resources.GetString("RS10.ToolTip"));
//
// S9
//
this.S9.FormattingEnabled = true;
this.S9.Items.AddRange(new object[] {
resources.GetString("S9.Items"),
resources.GetString("S9.Items1"),
resources.GetString("S9.Items2"),
resources.GetString("S9.Items3"),
resources.GetString("S9.Items4"),
resources.GetString("S9.Items5"),
resources.GetString("S9.Items6"),
resources.GetString("S9.Items7"),
resources.GetString("S9.Items8")});
resources.ApplyResources(this.S9, "S9");
this.S9.Name = "S9";
//
// S8
//
this.S8.FormattingEnabled = true;
this.S8.Items.AddRange(new object[] {
resources.GetString("S8.Items"),
resources.GetString("S8.Items1"),
resources.GetString("S8.Items2"),
resources.GetString("S8.Items3"),
resources.GetString("S8.Items4"),
resources.GetString("S8.Items5"),
resources.GetString("S8.Items6"),
resources.GetString("S8.Items7"),
resources.GetString("S8.Items8"),
resources.GetString("S8.Items9"),
resources.GetString("S8.Items10"),
resources.GetString("S8.Items11")});
resources.ApplyResources(this.S8, "S8");
this.S8.Name = "S8";
//
// RS8
//
resources.ApplyResources(this.RS8, "RS8");
this.RS8.FormattingEnabled = true;
this.RS8.Items.AddRange(new object[] {
resources.GetString("RS8.Items"),
resources.GetString("RS8.Items1"),
resources.GetString("RS8.Items2"),
resources.GetString("RS8.Items3"),
resources.GetString("RS8.Items4"),
resources.GetString("RS8.Items5"),
resources.GetString("RS8.Items6"),
resources.GetString("RS8.Items7"),
resources.GetString("RS8.Items8")});
this.RS8.Name = "RS8";
//
// RS9
//
resources.ApplyResources(this.RS9, "RS9");
this.RS9.FormattingEnabled = true;
this.RS9.Items.AddRange(new object[] {
resources.GetString("RS9.Items"),
resources.GetString("RS9.Items1"),
resources.GetString("RS9.Items2"),
resources.GetString("RS9.Items3"),
resources.GetString("RS9.Items4"),
resources.GetString("RS9.Items5"),
resources.GetString("RS9.Items6"),
resources.GetString("RS9.Items7"),
resources.GetString("RS9.Items8")});
this.RS9.Name = "RS9";
//
// RS0
//
resources.ApplyResources(this.RS0, "RS0");
@ -456,10 +664,152 @@
this.BUT_syncS5.UseVisualStyleBackColor = true;
this.BUT_syncS5.Click += new System.EventHandler(this.BUT_syncS5_Click);
//
// label13
//
resources.ApplyResources(this.label13, "label13");
this.label13.Name = "label13";
//
// label14
//
resources.ApplyResources(this.label14, "label14");
this.label14.Name = "label14";
//
// label15
//
resources.ApplyResources(this.label15, "label15");
this.label15.Name = "label15";
//
// label16
//
resources.ApplyResources(this.label16, "label16");
this.label16.Name = "label16";
//
// label17
//
resources.ApplyResources(this.label17, "label17");
this.label17.Name = "label17";
//
// label20
//
resources.ApplyResources(this.label20, "label20");
this.label20.Name = "label20";
//
// label21
//
resources.ApplyResources(this.label21, "label21");
this.label21.Name = "label21";
//
// label22
//
resources.ApplyResources(this.label22, "label22");
this.label22.Name = "label22";
//
// label23
//
resources.ApplyResources(this.label23, "label23");
this.label23.Name = "label23";
//
// label24
//
resources.ApplyResources(this.label24, "label24");
this.label24.Name = "label24";
//
// label25
//
resources.ApplyResources(this.label25, "label25");
this.label25.Name = "label25";
//
// label26
//
resources.ApplyResources(this.label26, "label26");
this.label26.Name = "label26";
//
// label27
//
resources.ApplyResources(this.label27, "label27");
this.label27.Name = "label27";
//
// label28
//
resources.ApplyResources(this.label28, "label28");
this.label28.Name = "label28";
//
// label29
//
resources.ApplyResources(this.label29, "label29");
this.label29.Name = "label29";
//
// label30
//
resources.ApplyResources(this.label30, "label30");
this.label30.Name = "label30";
//
// label31
//
resources.ApplyResources(this.label31, "label31");
this.label31.Name = "label31";
//
// label32
//
resources.ApplyResources(this.label32, "label32");
this.label32.Name = "label32";
//
// BUT_syncS8
//
resources.ApplyResources(this.BUT_syncS8, "BUT_syncS8");
this.BUT_syncS8.Name = "BUT_syncS8";
this.BUT_syncS8.UseVisualStyleBackColor = true;
this.BUT_syncS8.Click += new System.EventHandler(this.BUT_syncS8_Click);
//
// BUT_syncS9
//
resources.ApplyResources(this.BUT_syncS9, "BUT_syncS9");
this.BUT_syncS9.Name = "BUT_syncS9";
this.BUT_syncS9.UseVisualStyleBackColor = true;
this.BUT_syncS9.Click += new System.EventHandler(this.BUT_syncS9_Click);
//
// BUT_syncS10
//
resources.ApplyResources(this.BUT_syncS10, "BUT_syncS10");
this.BUT_syncS10.Name = "BUT_syncS10";
this.BUT_syncS10.UseVisualStyleBackColor = true;
this.BUT_syncS10.Click += new System.EventHandler(this.BUT_syncS10_Click);
//
// _3DRradio
//
resources.ApplyResources(this, "$this");
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.Controls.Add(this.BUT_syncS10);
this.Controls.Add(this.BUT_syncS9);
this.Controls.Add(this.BUT_syncS8);
this.Controls.Add(this.label25);
this.Controls.Add(this.label26);
this.Controls.Add(this.label27);
this.Controls.Add(this.label28);
this.Controls.Add(this.label29);
this.Controls.Add(this.label30);
this.Controls.Add(this.label31);
this.Controls.Add(this.label32);
this.Controls.Add(this.label20);
this.Controls.Add(this.label21);
this.Controls.Add(this.label22);
this.Controls.Add(this.label23);
this.Controls.Add(this.label24);
this.Controls.Add(this.RS8);
this.Controls.Add(this.RS12);
this.Controls.Add(this.RS11);
this.Controls.Add(this.RS10);
this.Controls.Add(this.RS9);
this.Controls.Add(this.label17);
this.Controls.Add(this.label16);
this.Controls.Add(this.label15);
this.Controls.Add(this.label14);
this.Controls.Add(this.label13);
this.Controls.Add(this.S8);
this.Controls.Add(this.S12);
this.Controls.Add(this.S11);
this.Controls.Add(this.S10);
this.Controls.Add(this.S9);
this.Controls.Add(this.BUT_syncS5);
this.Controls.Add(this.BUT_syncS3);
this.Controls.Add(this.BUT_syncS2);
@ -499,7 +849,7 @@
this.Controls.Add(this.lbl_status);
this.Controls.Add(this.Progressbar);
this.Controls.Add(this.BUT_upload);
this.MinimumSize = new System.Drawing.Size(334, 482);
this.MinimumSize = new System.Drawing.Size(781, 433);
this.Name = "_3DRradio";
this.ResumeLayout(false);
this.PerformLayout();
@ -548,5 +898,36 @@
private MyButton BUT_syncS2;
private MyButton BUT_syncS3;
private MyButton BUT_syncS5;
private System.Windows.Forms.ComboBox S9;
private System.Windows.Forms.ComboBox S10;
private System.Windows.Forms.ComboBox S11;
private System.Windows.Forms.ComboBox S12;
private System.Windows.Forms.ComboBox S8;
private System.Windows.Forms.Label label13;
private System.Windows.Forms.Label label14;
private System.Windows.Forms.Label label15;
private System.Windows.Forms.Label label16;
private System.Windows.Forms.Label label17;
private System.Windows.Forms.Label label20;
private System.Windows.Forms.Label label21;
private System.Windows.Forms.Label label22;
private System.Windows.Forms.Label label23;
private System.Windows.Forms.Label label24;
private System.Windows.Forms.ComboBox RS8;
private System.Windows.Forms.ComboBox RS12;
private System.Windows.Forms.ComboBox RS11;
private System.Windows.Forms.ComboBox RS10;
private System.Windows.Forms.ComboBox RS9;
private System.Windows.Forms.Label label25;
private System.Windows.Forms.Label label26;
private System.Windows.Forms.Label label27;
private System.Windows.Forms.Label label28;
private System.Windows.Forms.Label label29;
private System.Windows.Forms.Label label30;
private System.Windows.Forms.Label label31;
private System.Windows.Forms.Label label32;
private MyButton BUT_syncS8;
private MyButton BUT_syncS9;
private MyButton BUT_syncS10;
}
}

View File

@ -14,6 +14,37 @@ namespace ArdupilotMega
{
public partial class _3DRradio : BackStageViewContentPanel
{
/*
responce 0 S0: FORMAT=25
S1: SERIAL_SPEED=57
S2: AIR_SPEED=64
S3: NETID=25
S4: TXPOWER=20
S5: ECC=1
S6: MAVLINK=1
S7: OPPRESEND=1
S8: MIN_FREQ=915000
S9: MAX_FREQ=928000
S10: NUM_CHANNELS=50
S11: DUTY_CYCLE=100
S12: LBT_RSSI=0
S13: MANCHESTER=0
*/
public delegate void LogEventHandler(string message, int level = 0);
public delegate void ProgressEventHandler(double completed);
@ -65,8 +96,7 @@ namespace ArdupilotMega
bool bootloadermode = false;
uploader.ProgressEvent += new ProgressEventHandler(uploader_ProgressEvent);
uploader.LogEvent += new LogEventHandler(uploader_LogEvent);
try
{
@ -74,6 +104,10 @@ namespace ArdupilotMega
uploader_LogEvent("Trying Bootloader Mode");
uploader.port = comPort;
uploader.connect_and_sync();
uploader.ProgressEvent += new ProgressEventHandler(uploader_ProgressEvent);
uploader.LogEvent += new LogEventHandler(uploader_LogEvent);
uploader_LogEvent("In Bootloader Mode");
bootloadermode = true;
}
@ -82,12 +116,15 @@ namespace ArdupilotMega
comPort.Close();
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
comPort.Open();
uploader.ProgressEvent += new ProgressEventHandler(uploader_ProgressEvent);
uploader.LogEvent += new LogEventHandler(uploader_LogEvent);
uploader_LogEvent("Trying Firmware Mode");
bootloadermode = false;
}
if (bootloadermode || doConnect(comPort))
{
if (getFirmware())
@ -617,5 +654,20 @@ namespace ArdupilotMega
{
RS5.Checked = S5.Checked;
}
private void BUT_syncS8_Click(object sender, EventArgs e)
{
RS8.Text = S8.Text;
}
private void BUT_syncS9_Click(object sender, EventArgs e)
{
RS9.Text = S9.Text;
}
private void BUT_syncS10_Click(object sender, EventArgs e)
{
RS10.Text = S10.Text;
}
}
}

File diff suppressed because it is too large Load Diff

View File

@ -1 +1 @@
1.1.4493.14496
1.1.4494.25525