This commit is contained in:
Jason Short 2011-09-22 17:45:01 -07:00
commit 3444b7fdca
11 changed files with 205 additions and 103 deletions

View File

@ -79,17 +79,16 @@ namespace System.IO.Ports
client = new UdpClient(int.Parse(Port));
int timeout = 5;
while (timeout > 0)
{
if (BytesToRead > 0)
break;
System.Threading.Thread.Sleep(1000);
timeout--;
}
if (BytesToRead == 0)
return;
int timeout = 5;
while (timeout > 0)
{
if (BytesToRead > 0)
break;
System.Threading.Thread.Sleep(1000);
timeout--;
}
if (BytesToRead == 0)
return;
try
{

View File

@ -136,7 +136,11 @@ namespace ArdupilotMega
public int hilch1 { get; set; }
public int hilch2 { get; set; }
public int hilch3 { get; set; }
public int hilch4 { get; set; }
public int hilch4 { get; set; }
public int hilch5;
public int hilch6;
public int hilch7;
public int hilch8;
// rc override
public ushort rcoverridech1 { get; set; }
@ -230,6 +234,10 @@ namespace ArdupilotMega
hilch2 = hil.chan2_scaled;
hilch3 = hil.chan3_scaled;
hilch4 = hil.chan4_scaled;
hilch5 = hil.chan5_scaled;
hilch6 = hil.chan6_scaled;
hilch7 = hil.chan7_scaled;
hilch8 = hil.chan8_scaled;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] = null;
}

View File

@ -622,7 +622,11 @@ namespace ArdupilotMega.GCSViews
case MAVLink.MAV_CMD.LAND:
Commands.Columns[1].HeaderText = "N/A";
if (MainV2.APMFirmware != MainV2.Firmwares.ArduPlane)
{
Commands.Columns[2].HeaderText = "N/A";
Commands.Columns[3].HeaderText = "N/A";
Commands.Columns[4].HeaderText = "N/A";
}
break;
case MAVLink.MAV_CMD.TAKEOFF:
if (MainV2.APMFirmware != MainV2.Firmwares.ArduPlane)
@ -2430,7 +2434,7 @@ namespace ArdupilotMega.GCSViews
polygons.Markers.Add(new GMapMarkerGoogleRed(start));
MainMap.Invalidate();
MessageBox.Show("Distance: " + FormatDistance(MainMap.Manager.GetDistance(startmeasure, start), true));
MessageBox.Show("Distance: " + FormatDistance(MainMap.Manager.GetDistance(startmeasure, start),true) + " AZ: " + (MainMap.Manager.GetBearing(startmeasure, start).ToString("0")));
polygons.Polygons.Remove(line);
polygons.Markers.Clear();
startmeasure = new PointLatLng();

View File

@ -109,6 +109,7 @@
this.BUT_startfgquad = new ArdupilotMega.MyButton();
this.BUT_startfgplane = new ArdupilotMega.MyButton();
this.BUT_startxplane = new ArdupilotMega.MyButton();
this.CHK_heli = new System.Windows.Forms.CheckBox();
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
this.panel1.SuspendLayout();
this.panel2.SuspendLayout();
@ -673,10 +674,17 @@
this.BUT_startxplane.UseVisualStyleBackColor = true;
this.BUT_startxplane.Click += new System.EventHandler(this.BUT_startxplane_Click);
//
// CHK_heli
//
resources.ApplyResources(this.CHK_heli, "CHK_heli");
this.CHK_heli.Name = "CHK_heli";
this.CHK_heli.UseVisualStyleBackColor = true;
//
// Simulation
//
resources.ApplyResources(this, "$this");
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.Controls.Add(this.CHK_heli);
this.Controls.Add(this.BUT_startxplane);
this.Controls.Add(this.BUT_startfgplane);
this.Controls.Add(this.BUT_startfgquad);
@ -801,5 +809,6 @@
private MyButton BUT_startfgquad;
private MyButton BUT_startfgplane;
private MyButton BUT_startxplane;
private System.Windows.Forms.CheckBox CHK_heli;
}
}

View File

@ -124,6 +124,8 @@ namespace ArdupilotMega.GCSViews
try
{
quad = new HIL.QuadCopter();
SetupUDPRecv();
if (RAD_softXplanes.Checked)
@ -149,6 +151,7 @@ namespace ArdupilotMega.GCSViews
};
t11.Start();
MainV2.threads.Add(t11);
timer1.Start();
}
else
{
@ -618,6 +621,9 @@ namespace ArdupilotMega.GCSViews
att.pitch = (DATA[18][0] * deg2rad);
att.roll = (DATA[18][1] * deg2rad);
att.yaw = (DATA[18][2] * deg2rad);
att.pitchspeed = (DATA[17][0]);
att.rollspeed = (DATA[17][1]);
att.yawspeed = (DATA[17][2]);
TimeSpan timediff = DateTime.Now - oldtime;
@ -679,7 +685,7 @@ namespace ArdupilotMega.GCSViews
object imudata = new fgIMUData();
MAVLink.ByteArrayToStructure(data, ref imudata, 0);
MAVLink.ByteArrayToStructureEndian(data, ref imudata, 0);
imudata = (fgIMUData)(imudata);
@ -725,7 +731,7 @@ namespace ArdupilotMega.GCSViews
object temp = fdm;
MAVLink.ByteArrayToStructure(data, ref temp, 0);
MAVLink.ByteArrayToStructureEndian(data, ref temp, 0);
fdm = (FGNetFDM)(temp);
@ -904,12 +910,9 @@ namespace ArdupilotMega.GCSViews
private void processArduPilot()
{
// Console.WriteLine("sim "+DateTime.Now.Millisecond);
bool heli = CHK_heli.Checked;
float roll_out = (float)MainV2.cs.hilch1 / rollgain;
float pitch_out = (float)MainV2.cs.hilch2 / pitchgain;
float throttle_out = ((float)MainV2.cs.hilch3 + 5000) / throttlegain;
float rudder_out = (float)MainV2.cs.hilch4 / ruddergain;
// Console.WriteLine("sim "+DateTime.Now.Millisecond);
if (CHK_quad.Checked)
{
@ -931,6 +934,9 @@ namespace ArdupilotMega.GCSViews
try
{
if (lastfdmdata.version == 0)
return;
quad.update(ref m, lastfdmdata);
}
catch (Exception e) { Console.WriteLine("Quad hill error " + e.ToString()); }
@ -1010,12 +1016,37 @@ namespace ArdupilotMega.GCSViews
}
float roll_out, pitch_out, throttle_out, rudder_out, collective_out;
collective_out = 0;
if (heli)
{
roll_out = (float)MainV2.cs.hilch1 / rollgain;
pitch_out = (float)MainV2.cs.hilch2 / pitchgain;
throttle_out = 1;
rudder_out = (float)MainV2.cs.hilch4 / -ruddergain;
collective_out = (float)(MainV2.cs.hilch3 - 1000) / throttlegain;
}
else
{
roll_out = (float)MainV2.cs.hilch1 / rollgain;
pitch_out = (float)MainV2.cs.hilch2 / pitchgain;
throttle_out = ((float)MainV2.cs.hilch3 + 5000) / throttlegain;
rudder_out = (float)MainV2.cs.hilch4 / ruddergain;
}
if ((roll_out == -1 || roll_out == 1) && (pitch_out == -1 || pitch_out == 1))
{
this.Invoke((MethodInvoker)delegate
{
//OutputLog.AppendText("Please check your radio setup - CLI -> setup -> radio!!!\n");
try
{
OutputLog.AppendText("Please check your radio setup - CLI -> setup -> radio!!!\n");
}
catch { }
});
}
@ -1158,15 +1189,9 @@ namespace ArdupilotMega.GCSViews
{
// sending only 1 packet instead of many.
bool helicopter = false;
#if !DEBUG
helicopter = false;
#endif
byte[] Xplane = new byte[5 + 36 + 36];
if (helicopter)
if (heli)
{
Xplane = new byte[5 + 36 + 36 + 36];
}
@ -1184,14 +1209,6 @@ namespace ArdupilotMega.GCSViews
Array.Copy(BitConverter.GetBytes((float)throttle_out), 0, Xplane, 17, 4);
Array.Copy(BitConverter.GetBytes((float)throttle_out), 0, Xplane, 21, 4);
if (helicopter)
{
Array.Copy(BitConverter.GetBytes((float)1), 0, Xplane, 9, 4); // start data
Array.Copy(BitConverter.GetBytes((float)1), 0, Xplane, 13, 4);
Array.Copy(BitConverter.GetBytes((float)1), 0, Xplane, 17, 4);
Array.Copy(BitConverter.GetBytes((float)1), 0, Xplane, 21, 4);
}
Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 25, 4);
Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 29, 4);
Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 33, 4);
@ -1211,12 +1228,15 @@ namespace ArdupilotMega.GCSViews
Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 69, 4);
Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 73, 4);
if (helicopter)
if (heli)
{
Array.Copy(BitConverter.GetBytes((float)(0)), 0, Xplane, 53, 4);
int a = 73 + 4;
Array.Copy(BitConverter.GetBytes((int)39), 0, Xplane, a, 4); // packet index
a += 4;
Array.Copy(BitConverter.GetBytes((float)(12 * throttle_out - 2)), 0, Xplane, a, 4); // main rotor 0 - 12
Array.Copy(BitConverter.GetBytes((float)(12 * collective_out)), 0, Xplane, a, 4); // main rotor 0 - 12
a += 4;
Array.Copy(BitConverter.GetBytes((float)(12 * rudder_out)), 0, Xplane, a, 4); // tail rotor -12 - 12
a += 4;

View File

@ -144,7 +144,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKREV_roll.ZOrder" xml:space="preserve">
<value>27</value>
<value>28</value>
</data>
<data name="CHKREV_pitch.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -171,7 +171,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKREV_pitch.ZOrder" xml:space="preserve">
<value>26</value>
<value>27</value>
</data>
<data name="CHKREV_rudder.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -198,7 +198,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKREV_rudder.ZOrder" xml:space="preserve">
<value>25</value>
<value>26</value>
</data>
<data name="GPSrate.Items" xml:space="preserve">
<value>100</value>
@ -243,7 +243,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;GPSrate.ZOrder" xml:space="preserve">
<value>24</value>
<value>25</value>
</data>
<data name="ConnectComPort.Location" type="System.Drawing.Point, System.Drawing">
<value>26, 13</value>
@ -294,7 +294,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;OutputLog.ZOrder" xml:space="preserve">
<value>23</value>
<value>24</value>
</data>
<data name="TXT_roll.Location" type="System.Drawing.Point, System.Drawing">
<value>67, 22</value>
@ -510,7 +510,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;SaveSettings.ZOrder" xml:space="preserve">
<value>22</value>
<value>23</value>
</data>
<data name="RAD_softXplanes.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -537,7 +537,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;RAD_softXplanes.ZOrder" xml:space="preserve">
<value>21</value>
<value>22</value>
</data>
<data name="RAD_softFlightGear.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -564,7 +564,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;RAD_softFlightGear.ZOrder" xml:space="preserve">
<value>20</value>
<value>21</value>
</data>
<data name="TXT_servoroll.Location" type="System.Drawing.Point, System.Drawing">
<value>67, 24</value>
@ -765,7 +765,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel1.ZOrder" xml:space="preserve">
<value>19</value>
<value>20</value>
</data>
<data name="label30.Location" type="System.Drawing.Point, System.Drawing">
<value>7, 100</value>
@ -927,7 +927,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel2.ZOrder" xml:space="preserve">
<value>18</value>
<value>19</value>
</data>
<data name="label8.Location" type="System.Drawing.Point, System.Drawing">
<value>7, 27</value>
@ -1140,7 +1140,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel3.ZOrder" xml:space="preserve">
<value>17</value>
<value>18</value>
</data>
<data name="label20.Location" type="System.Drawing.Point, System.Drawing">
<value>72, 104</value>
@ -1275,7 +1275,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel4.ZOrder" xml:space="preserve">
<value>16</value>
<value>17</value>
</data>
<data name="label17.Location" type="System.Drawing.Point, System.Drawing">
<value>535, 9</value>
@ -1299,7 +1299,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label17.ZOrder" xml:space="preserve">
<value>15</value>
<value>16</value>
</data>
<data name="panel5.Location" type="System.Drawing.Point, System.Drawing">
<value>13, 5</value>
@ -1320,7 +1320,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel5.ZOrder" xml:space="preserve">
<value>14</value>
<value>15</value>
</data>
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="zg1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
@ -1345,7 +1345,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;zg1.ZOrder" xml:space="preserve">
<value>13</value>
<value>14</value>
</data>
<metadata name="timer1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>17, 17</value>
@ -1657,7 +1657,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel6.ZOrder" xml:space="preserve">
<value>12</value>
<value>13</value>
</data>
<data name="label26.Location" type="System.Drawing.Point, System.Drawing">
<value>508, 330</value>
@ -1681,7 +1681,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label26.ZOrder" xml:space="preserve">
<value>11</value>
<value>12</value>
</data>
<data name="CHKdisplayall.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -1708,7 +1708,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKdisplayall.ZOrder" xml:space="preserve">
<value>10</value>
<value>11</value>
</data>
<data name="CHKgraphroll.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
@ -1738,7 +1738,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKgraphroll.ZOrder" xml:space="preserve">
<value>9</value>
<value>10</value>
</data>
<data name="CHKgraphpitch.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
@ -1768,7 +1768,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKgraphpitch.ZOrder" xml:space="preserve">
<value>8</value>
<value>9</value>
</data>
<data name="CHKgraphrudder.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
@ -1798,7 +1798,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKgraphrudder.ZOrder" xml:space="preserve">
<value>7</value>
<value>8</value>
</data>
<data name="CHKgraphthrottle.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
@ -1828,7 +1828,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKgraphthrottle.ZOrder" xml:space="preserve">
<value>6</value>
<value>7</value>
</data>
<data name="but_advsettings.Location" type="System.Drawing.Point, System.Drawing">
<value>566, 368</value>
@ -1852,13 +1852,13 @@
<value>$this</value>
</data>
<data name="&gt;&gt;but_advsettings.ZOrder" xml:space="preserve">
<value>5</value>
<value>6</value>
</data>
<data name="chkSensor.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="chkSensor.Location" type="System.Drawing.Point, System.Drawing">
<value>567, 324</value>
<value>566, 317</value>
</data>
<data name="chkSensor.Size" type="System.Drawing.Size, System.Drawing">
<value>59, 17</value>
@ -1879,7 +1879,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;chkSensor.ZOrder" xml:space="preserve">
<value>4</value>
<value>5</value>
</data>
<data name="CHK_quad.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -1888,7 +1888,7 @@
<value>NoControl</value>
</data>
<data name="CHK_quad.Location" type="System.Drawing.Point, System.Drawing">
<value>567, 346</value>
<value>566, 334</value>
</data>
<data name="CHK_quad.Size" type="System.Drawing.Size, System.Drawing">
<value>52, 17</value>
@ -1909,7 +1909,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHK_quad.ZOrder" xml:space="preserve">
<value>3</value>
<value>4</value>
</data>
<data name="BUT_startfgquad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -1936,7 +1936,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_startfgquad.ZOrder" xml:space="preserve">
<value>2</value>
<value>3</value>
</data>
<data name="BUT_startfgplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -1963,7 +1963,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_startfgplane.ZOrder" xml:space="preserve">
<value>1</value>
<value>2</value>
</data>
<data name="BUT_startxplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -1990,6 +1990,36 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_startxplane.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="CHK_heli.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CHK_heli.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CHK_heli.Location" type="System.Drawing.Point, System.Drawing">
<value>566, 350</value>
</data>
<data name="CHK_heli.Size" type="System.Drawing.Size, System.Drawing">
<value>44, 17</value>
</data>
<data name="CHK_heli.TabIndex" type="System.Int32, mscorlib">
<value>47</value>
</data>
<data name="CHK_heli.Text" xml:space="preserve">
<value>Heli</value>
</data>
<data name="&gt;&gt;CHK_heli.Name" xml:space="preserve">
<value>CHK_heli</value>
</data>
<data name="&gt;&gt;CHK_heli.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;CHK_heli.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CHK_heli.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">

View File

@ -159,7 +159,7 @@ namespace ArdupilotMega.HIL
//Console.WriteLine("Z {0} halt {1} < gl {2} fh {3}" ,position.Z , home_altitude , ground_level , frame_height);
if (home_latitude == 0)
if (home_latitude == 0 || home_latitude > 90 || home_latitude < -90 || home_longitude == 0)
{
this.home_latitude = fdm.latitude * rad2deg;
this.home_longitude = fdm.longitude * rad2deg;
@ -187,7 +187,7 @@ namespace ArdupilotMega.HIL
position = new Vector3d(position.X, position.Y,
ground_level + frame_height - home_altitude + 0);
// Console.WriteLine("here " + position.Z);
}
}
//# update lat/lon/altitude
update_position();

View File

@ -222,12 +222,12 @@ namespace ArdupilotMega
private void CMB_serialport_Click(object sender, EventArgs e)
{
String old_port = CMB_serialport.Text;
string oldport = CMB_serialport.Text;
CMB_serialport.Items.Clear();
CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
CMB_serialport.Items.Add("UDP");
if (CMB_serialport.Items.Contains(old_port))
CMB_serialport.Text = old_port;
if (CMB_serialport.Items.Contains(oldport))
CMB_serialport.Text = oldport;
}
public static void fixtheme(Control temp)
@ -679,6 +679,7 @@ namespace ArdupilotMega
CMB_baudrate.Enabled = false;
else
CMB_baudrate.Enabled = true;
try
{
comPort.BaseStream.PortName = CMB_serialport.Text;

View File

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

View File

@ -456,7 +456,8 @@ namespace ArdupilotMega.Setup
float value = (float)(CB_simple1.Checked ? 1 : 0) + (CB_simple2.Checked ? 1 << 1 : 0) + (CB_simple3.Checked ? 1 <<2 : 0)
+ (CB_simple4.Checked ? 1 << 3 : 0) + (CB_simple5.Checked ? 1 << 4 : 0) + (CB_simple6.Checked ? 1 << 5 : 0);
MainV2.comPort.setParam("SIMPLE", value);
if (MainV2.comPort.param.ContainsKey("SIMPLE"))
MainV2.comPort.setParam("SIMPLE", value);
}
}
catch { MessageBox.Show("Failed to set Flight modes"); }

View File

@ -144,7 +144,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKREV_roll.ZOrder" xml:space="preserve">
<value>27</value>
<value>28</value>
</data>
<data name="CHKREV_pitch.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -171,7 +171,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKREV_pitch.ZOrder" xml:space="preserve">
<value>26</value>
<value>27</value>
</data>
<data name="CHKREV_rudder.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -198,7 +198,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKREV_rudder.ZOrder" xml:space="preserve">
<value>25</value>
<value>26</value>
</data>
<data name="GPSrate.Items" xml:space="preserve">
<value>100</value>
@ -243,7 +243,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;GPSrate.ZOrder" xml:space="preserve">
<value>24</value>
<value>25</value>
</data>
<data name="ConnectComPort.Location" type="System.Drawing.Point, System.Drawing">
<value>26, 13</value>
@ -294,7 +294,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;OutputLog.ZOrder" xml:space="preserve">
<value>23</value>
<value>24</value>
</data>
<data name="TXT_roll.Location" type="System.Drawing.Point, System.Drawing">
<value>67, 22</value>
@ -510,7 +510,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;SaveSettings.ZOrder" xml:space="preserve">
<value>22</value>
<value>23</value>
</data>
<data name="RAD_softXplanes.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -537,7 +537,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;RAD_softXplanes.ZOrder" xml:space="preserve">
<value>21</value>
<value>22</value>
</data>
<data name="RAD_softFlightGear.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -564,7 +564,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;RAD_softFlightGear.ZOrder" xml:space="preserve">
<value>20</value>
<value>21</value>
</data>
<data name="TXT_servoroll.Location" type="System.Drawing.Point, System.Drawing">
<value>67, 24</value>
@ -765,7 +765,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel1.ZOrder" xml:space="preserve">
<value>19</value>
<value>20</value>
</data>
<data name="label30.Location" type="System.Drawing.Point, System.Drawing">
<value>7, 100</value>
@ -927,7 +927,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel2.ZOrder" xml:space="preserve">
<value>18</value>
<value>19</value>
</data>
<data name="label8.Location" type="System.Drawing.Point, System.Drawing">
<value>7, 27</value>
@ -1140,7 +1140,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel3.ZOrder" xml:space="preserve">
<value>17</value>
<value>18</value>
</data>
<data name="label20.Location" type="System.Drawing.Point, System.Drawing">
<value>72, 104</value>
@ -1275,7 +1275,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel4.ZOrder" xml:space="preserve">
<value>16</value>
<value>17</value>
</data>
<data name="label17.Location" type="System.Drawing.Point, System.Drawing">
<value>535, 9</value>
@ -1299,7 +1299,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label17.ZOrder" xml:space="preserve">
<value>15</value>
<value>16</value>
</data>
<data name="panel5.Location" type="System.Drawing.Point, System.Drawing">
<value>13, 5</value>
@ -1320,7 +1320,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel5.ZOrder" xml:space="preserve">
<value>14</value>
<value>15</value>
</data>
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="zg1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
@ -1345,7 +1345,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;zg1.ZOrder" xml:space="preserve">
<value>13</value>
<value>14</value>
</data>
<metadata name="timer1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>17, 17</value>
@ -1657,7 +1657,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;panel6.ZOrder" xml:space="preserve">
<value>12</value>
<value>13</value>
</data>
<data name="label26.Location" type="System.Drawing.Point, System.Drawing">
<value>508, 330</value>
@ -1681,7 +1681,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label26.ZOrder" xml:space="preserve">
<value>11</value>
<value>12</value>
</data>
<data name="CHKdisplayall.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -1708,7 +1708,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKdisplayall.ZOrder" xml:space="preserve">
<value>10</value>
<value>11</value>
</data>
<data name="CHKgraphroll.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
@ -1738,7 +1738,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKgraphroll.ZOrder" xml:space="preserve">
<value>9</value>
<value>10</value>
</data>
<data name="CHKgraphpitch.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
@ -1768,7 +1768,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKgraphpitch.ZOrder" xml:space="preserve">
<value>8</value>
<value>9</value>
</data>
<data name="CHKgraphrudder.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
@ -1798,7 +1798,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKgraphrudder.ZOrder" xml:space="preserve">
<value>7</value>
<value>8</value>
</data>
<data name="CHKgraphthrottle.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
@ -1828,7 +1828,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHKgraphthrottle.ZOrder" xml:space="preserve">
<value>6</value>
<value>7</value>
</data>
<data name="but_advsettings.Location" type="System.Drawing.Point, System.Drawing">
<value>566, 368</value>
@ -1852,13 +1852,13 @@
<value>$this</value>
</data>
<data name="&gt;&gt;but_advsettings.ZOrder" xml:space="preserve">
<value>5</value>
<value>6</value>
</data>
<data name="chkSensor.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="chkSensor.Location" type="System.Drawing.Point, System.Drawing">
<value>567, 324</value>
<value>566, 317</value>
</data>
<data name="chkSensor.Size" type="System.Drawing.Size, System.Drawing">
<value>59, 17</value>
@ -1879,7 +1879,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;chkSensor.ZOrder" xml:space="preserve">
<value>4</value>
<value>5</value>
</data>
<data name="CHK_quad.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -1888,7 +1888,7 @@
<value>NoControl</value>
</data>
<data name="CHK_quad.Location" type="System.Drawing.Point, System.Drawing">
<value>567, 346</value>
<value>566, 334</value>
</data>
<data name="CHK_quad.Size" type="System.Drawing.Size, System.Drawing">
<value>52, 17</value>
@ -1909,7 +1909,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CHK_quad.ZOrder" xml:space="preserve">
<value>3</value>
<value>4</value>
</data>
<data name="BUT_startfgquad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -1936,7 +1936,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_startfgquad.ZOrder" xml:space="preserve">
<value>2</value>
<value>3</value>
</data>
<data name="BUT_startfgplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -1963,7 +1963,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_startfgplane.ZOrder" xml:space="preserve">
<value>1</value>
<value>2</value>
</data>
<data name="BUT_startxplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -1990,6 +1990,36 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_startxplane.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="CHK_heli.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CHK_heli.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CHK_heli.Location" type="System.Drawing.Point, System.Drawing">
<value>566, 350</value>
</data>
<data name="CHK_heli.Size" type="System.Drawing.Size, System.Drawing">
<value>44, 17</value>
</data>
<data name="CHK_heli.TabIndex" type="System.Int32, mscorlib">
<value>47</value>
</data>
<data name="CHK_heli.Text" xml:space="preserve">
<value>Heli</value>
</data>
<data name="&gt;&gt;CHK_heli.Name" xml:space="preserve">
<value>CHK_heli</value>
</data>
<data name="&gt;&gt;CHK_heli.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;CHK_heli.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CHK_heli.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">