Browse Source

Mission Planner 1.2.27

add extra decimal place on arducopter config screens
update ch6_list
fix quickview double click error
fix terminal/logview comport problem
add AC thr accel pids
modify driver (line ending issue) and resign
fix config view doubleclick popout
master
Michael Oborne 12 years ago
parent
commit
dda74afa21
  1. 50
      Tools/ArdupilotMegaPlanner/ArduCopterConfig.xml
  2. 11
      Tools/ArdupilotMegaPlanner/ChangeLog.txt
  3. 75
      Tools/ArdupilotMegaPlanner/Common.cs
  4. 32
      Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs
  5. 3
      Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs
  6. 2
      Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs
  7. 2
      Tools/ArdupilotMegaPlanner/Controls/RangeControl.Designer.cs
  8. BIN
      Tools/ArdupilotMegaPlanner/Driver/arduino.cat
  9. 2
      Tools/ArdupilotMegaPlanner/Driver/arduino.inf
  10. BIN
      Tools/ArdupilotMegaPlanner/Driver/px4fmu.cat
  11. 110
      Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
  12. 53
      Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs
  13. 2065
      Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx
  14. 68
      Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs
  15. 3
      Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
  16. 86
      Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
  17. 21
      Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs
  18. 50
      Tools/ArdupilotMegaPlanner/Msi/installer.wxs
  19. 2
      Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
  20. 4
      Tools/ArdupilotMegaPlanner/wix/wix.csproj

50
Tools/ArdupilotMegaPlanner/ArduCopterConfig.xml

@ -16,7 +16,7 @@ Large: P = 0.090</DESC>
<PARAMNAME>RATE_PIT_P</PARAMNAME> <PARAMNAME>RATE_PIT_P</PARAMNAME>
<RANGEMIN>0.001</RANGEMIN> <RANGEMIN>0.001</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>I</NAME> <NAME>I</NAME>
@ -24,7 +24,7 @@ Large: P = 0.090</DESC>
<PARAMNAME>RATE_PIT_I</PARAMNAME> <PARAMNAME>RATE_PIT_I</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>D</NAME> <NAME>D</NAME>
@ -32,7 +32,7 @@ Large: P = 0.090</DESC>
<PARAMNAME>RATE_PIT_D</PARAMNAME> <PARAMNAME>RATE_PIT_D</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>IMAX</NAME> <NAME>IMAX</NAME>
@ -58,14 +58,14 @@ When the sticks are fully deflected:
<PARAMNAME>STAB_D</PARAMNAME> <PARAMNAME>STAB_D</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>Dynamic</NAME> <NAME>Dynamic</NAME>
<PARAMNAME>STAB_D_S</PARAMNAME> <PARAMNAME>STAB_D_S</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>1</RANGEMAX> <RANGEMAX>1</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
</FIELDS> </FIELDS>
@ -82,7 +82,7 @@ Too high = slow wobbles
<PARAMNAME>STB_PIT_P</PARAMNAME> <PARAMNAME>STB_PIT_P</PARAMNAME>
<RANGEMIN>0.001</RANGEMIN> <RANGEMIN>0.001</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>I</NAME> <NAME>I</NAME>
@ -90,7 +90,7 @@ Too high = slow wobbles
<PARAMNAME>STB_PIT_I</PARAMNAME> <PARAMNAME>STB_PIT_I</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>IMAX</NAME> <NAME>IMAX</NAME>
@ -98,7 +98,7 @@ Too high = slow wobbles
<PARAMNAME>STB_PIT_IMAX</PARAMNAME> <PARAMNAME>STB_PIT_IMAX</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>50</RANGEMAX> <RANGEMAX>50</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
</FIELDS> </FIELDS>
@ -111,21 +111,21 @@ Too high = slow wobbles
<PARAMNAME>RATE_YAW_P</PARAMNAME> <PARAMNAME>RATE_YAW_P</PARAMNAME>
<RANGEMIN>0.001</RANGEMIN> <RANGEMIN>0.001</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>I</NAME> <NAME>I</NAME>
<PARAMNAME>RATE_YAW_I</PARAMNAME> <PARAMNAME>RATE_YAW_I</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>D</NAME> <NAME>D</NAME>
<PARAMNAME>RATE_YAW_D</PARAMNAME> <PARAMNAME>RATE_YAW_D</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>IMAX</NAME> <NAME>IMAX</NAME>
@ -148,14 +148,14 @@ Too high = slow wobbles
<PARAMNAME>STB_YAW_P</PARAMNAME> <PARAMNAME>STB_YAW_P</PARAMNAME>
<RANGEMIN>0.001</RANGEMIN> <RANGEMIN>0.001</RANGEMIN>
<RANGEMAX>10</RANGEMAX> <RANGEMAX>10</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>I</NAME> <NAME>I</NAME>
<PARAMNAME>STB_YAW_I</PARAMNAME> <PARAMNAME>STB_YAW_I</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>IMAX</NAME> <NAME>IMAX</NAME>
@ -180,7 +180,7 @@ How much angle is applied to make the copter accelerate to the desired speed.
<PARAMNAME>LOITER_LON_P</PARAMNAME> <PARAMNAME>LOITER_LON_P</PARAMNAME>
<RANGEMIN>0.001</RANGEMIN> <RANGEMIN>0.001</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>I</NAME> <NAME>I</NAME>
@ -188,7 +188,7 @@ How much angle is applied to make the copter accelerate to the desired speed.
<PARAMNAME>LOITER_LON_I</PARAMNAME> <PARAMNAME>LOITER_LON_I</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>D</NAME> <NAME>D</NAME>
@ -196,7 +196,7 @@ How much angle is applied to make the copter accelerate to the desired speed.
<PARAMNAME>LOITER_LON_D</PARAMNAME> <PARAMNAME>LOITER_LON_D</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>IMAX</NAME> <NAME>IMAX</NAME>
@ -220,7 +220,7 @@ A distance error of 100cm * P of .25 = 25 cm/s
<PARAMNAME>HLD_LON_P</PARAMNAME> <PARAMNAME>HLD_LON_P</PARAMNAME>
<RANGEMIN>0.001</RANGEMIN> <RANGEMIN>0.001</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
</FIELDS> </FIELDS>
</Item> </Item>
@ -238,7 +238,7 @@ A distance error of 100cm * P of .25 = 25 cm/s
<PARAMNAME>NAV_LON_P</PARAMNAME> <PARAMNAME>NAV_LON_P</PARAMNAME>
<RANGEMIN>0.001</RANGEMIN> <RANGEMIN>0.001</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>I</NAME> <NAME>I</NAME>
@ -246,7 +246,7 @@ A distance error of 100cm * P of .25 = 25 cm/s
<PARAMNAME>NAV_LON_I</PARAMNAME> <PARAMNAME>NAV_LON_I</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>D</NAME> <NAME>D</NAME>
@ -254,7 +254,7 @@ A distance error of 100cm * P of .25 = 25 cm/s
<PARAMNAME>NAV_LON_D</PARAMNAME> <PARAMNAME>NAV_LON_D</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>IMAX</NAME> <NAME>IMAX</NAME>
@ -294,14 +294,14 @@ A distance error of 100cm * P of .25 = 25 cm/s
<PARAMNAME>THR_ALT_P</PARAMNAME> <PARAMNAME>THR_ALT_P</PARAMNAME>
<RANGEMIN>0.001</RANGEMIN> <RANGEMIN>0.001</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>I</NAME> <NAME>I</NAME>
<PARAMNAME>THR_ALT_I</PARAMNAME> <PARAMNAME>THR_ALT_I</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>IMAX</NAME> <NAME>IMAX</NAME>
@ -323,21 +323,21 @@ A distance error of 100cm * P of .25 = 25 cm/s
<PARAMNAME>THR_RATE_P</PARAMNAME> <PARAMNAME>THR_RATE_P</PARAMNAME>
<RANGEMIN>0.001</RANGEMIN> <RANGEMIN>0.001</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>I</NAME> <NAME>I</NAME>
<PARAMNAME>THR_RATE_I</PARAMNAME> <PARAMNAME>THR_RATE_I</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>D</NAME> <NAME>D</NAME>
<PARAMNAME>THR_RATE_D</PARAMNAME> <PARAMNAME>THR_RATE_D</PARAMNAME>
<RANGEMIN>0</RANGEMIN> <RANGEMIN>0</RANGEMIN>
<RANGEMAX>5</RANGEMAX> <RANGEMAX>5</RANGEMAX>
<STEP>0.001</STEP> <STEP>0.0001</STEP>
</FIELD> </FIELD>
<FIELD> <FIELD>
<NAME>IMAX</NAME> <NAME>IMAX</NAME>

11
Tools/ArdupilotMegaPlanner/ChangeLog.txt

@ -1,4 +1,13 @@
* Mission Planner 1.2.26 * Mission Planner 1.2.27
add extra decimal place on arducopter config screens
update ch6_list
fix quickview double click error
fix terminal/logview comport problem
add AC thr accel pids
modify driver (line ending issue) and resign
fix config view doubleclick popout
* Mission Planner 1.2.26
move mavlink structure/currentstate around for future mods move mavlink structure/currentstate around for future mods
update old firmware git hashs update old firmware git hashs
mod some error descriptions mod some error descriptions

75
Tools/ArdupilotMegaPlanner/Common.cs

@ -561,46 +561,41 @@ namespace ArdupilotMega
{ {
// CH_6 Tuning // CH_6 Tuning
// ----------- // -----------
CH6_NONE = 0, CH6_0NONE = 0, // no tuning performed
// Attitude CH6_STABILIZE_KP = 1, // stabilize roll/pitch angle controller's P term
CH6_STABILIZE_KP = 1, CH6_STABILIZE_KI = 2, // stabilize roll/pitch angle controller's I term
CH6_STABILIZE_KI = 2, CH6_STABILIZE_KD = 29, // stabilize roll/pitch angle controller's D term
CH6_YAW_KP = 3, CH6_YAW_KP = 3, // stabilize yaw heading controller's P term
// Rate CH6_YAW_KI = 24, // stabilize yaw heading controller's P term
CH6_RATE_KP = 4, CH6_ACRO_KP = 25, // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate
CH6_RATE_KI = 5, CH6_RATE_KP = 4, // body frame roll/pitch rate controller's P term
CH6_RATE_KD = 21, CH6_RATE_KI = 5, // body frame roll/pitch rate controller's I term
CH6_YAW_RATE_KP = 6, CH6_RATE_KD = 21, // body frame roll/pitch rate controller's D term
// Altitude rate controller CH6_YAW_RATE_KP = 6, // body frame yaw rate controller's P term
CH6_THROTTLE_KP = 7, CH6_YAW_RATE_KD = 26, // body frame yaw rate controller's D term
// Extras CH6_THR_HOLD_KP = 14, // altitude hold controller's P term (alt error to desired rate)
CH6_TOP_BOTTOM_RATIO = 8, CH6_THROTTLE_KP = 7, // throttle rate controller's P term (desired rate to acceleration or motor output)
CH6_RELAY = 9, CH6_THROTTLE_KI = 33, // throttle rate controller's I term (desired rate to acceleration or motor output)
CH6_TRAVERSE_SPEED = 10, CH6_THR_ACCEL_KP = 34, // accel based throttle controller's P term
CH6_THR_ACCEL_KI = 35, // accel based throttle controller's I term
CH6_NAV_P = 11, CH6_THR_ACCEL_KD = 36, // accel based throttle controller's D term
CH6_LOITER_P = 12, CH6_TOP_BOTTOM_RATIO = 8, // upper/lower motor ratio (not used)
CH6_HELI_EXTERNAL_GYRO = 13, CH6_RELAY = 9, // switch relay on if ch6 high, off if low
CH6_TRAVERSE_SPEED = 10, // maximum speed to next way point (0 to 10m/s)
// altitude controller CH6_NAV_KP = 11, // navigation rate controller's P term (speed error to tilt angle)
CH6_THR_HOLD_KP = 14, CH6_NAV_KI = 20, // navigation rate controller's I term (speed error to tilt angle)
CH6_Z_GAIN = 15, CH6_LOITER_KP = 12, // loiter distance controller's P term (position error to speed)
//CH6_DAMP = 16, CH6_LOITER_KI = 27, // loiter distance controller's I term (position error to speed)
CH6_HELI_EXTERNAL_GYRO = 13, // TradHeli specific external tail gyro gain
// optical flow controller CH6_OPTFLOW_KP = 17, // optical flow loiter controller's P term (position error to tilt angle)
CH6_OPTFLOW_KP = 17, CH6_OPTFLOW_KI = 18, // optical flow loiter controller's I term (position error to tilt angle)
CH6_OPTFLOW_KI = 18, CH6_OPTFLOW_KD = 19, // optical flow loiter controller's D term (position error to tilt angle)
CH6_OPTFLOW_KD = 19, CH6_LOITER_RATE_KP = 22, // loiter rate controller's P term (speed error to tilt angle)
CH6_LOITER_RATE_KI = 28, // loiter rate controller's I term (speed error to tilt angle)
CH6_NAV_I = 20, CH6_LOITER_RATE_KD = 23, // loiter rate controller's D term (speed error to tilt angle)
CH6_LOITER_RATE_P = 22, CH6_AHRS_YAW_KP = 30, // ahrs's compass effect on yaw angle (0 = very low, 1 = very high)
CH6_LOITER_RATE_D = 23, CH6_AHRS_KP = 31, // accelerometer effect on roll/pitch angle (0=low)
CH6_YAW_KI = 24, CH6_INAV_TC = 32 // inertial navigation baro/accel and gps/accel time
CH6_ACRO_KP = 25,
CH6_YAW_RATE_KD = 26,
CH6_LOITER_KI = 27,
CH6_LOITER_RATE_KI = 28,
CH6_STABILIZE_KD = 29
} }
public static void linearRegression() public static void linearRegression()

32
Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs

@ -49,23 +49,33 @@ namespace ArdupilotMega.Comms
public void toggleDTR() public void toggleDTR()
{ {
bool open = this.IsOpen; bool open = this.IsOpen;
Console.WriteLine("toggleDTR " + this.IsOpen);
try
{
if (!open)
this.Open();
}
catch { }
if (!open)
this.Open();
base.DtrEnable = false; base.DtrEnable = false;
base.RtsEnable = false; base.RtsEnable = false;
System.Threading.Thread.Sleep(50); System.Threading.Thread.Sleep(50);
base.DtrEnable = true; base.DtrEnable = true;
base.RtsEnable = true; base.RtsEnable = true;
System.Threading.Thread.Sleep(50); System.Threading.Thread.Sleep(50);
if (!open) try
this.Close(); {
if (!open)
this.Close();
}
catch { }
Console.WriteLine("toggleDTR done " + this.IsOpen);
} }
public new static string[] GetPortNames() public new static string[] GetPortNames()

3
Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs

@ -226,6 +226,9 @@ namespace ArdupilotMega.Controls.BackstageView
private void DrawMenu(BackstageViewPage CurrentPage) private void DrawMenu(BackstageViewPage CurrentPage)
{ {
if (_activePage == CurrentPage)
return;
pnlMenu.Visible = false; pnlMenu.Visible = false;
pnlMenu.SuspendLayout(); pnlMenu.SuspendLayout();

2
Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs

@ -216,7 +216,7 @@ namespace ArdupilotMega.Controls
nud.Maximum = (decimal)rangemax; nud.Maximum = (decimal)rangemax;
nud.Minimum = (decimal)rangemin; nud.Minimum = (decimal)rangemin;
nud.Increment = (decimal)step; nud.Increment = (decimal)step;
nud.DecimalPlaces = (int)(step.ToString().Length - step.ToString(new System.Globalization.CultureInfo("en-US")).IndexOf('.') - 1); nud.DecimalPlaces = (int)(step.ToString().Length - step.ToString(new System.Globalization.CultureInfo("en-US")).IndexOf('.') -1);
nud.Name = paramname[0]; nud.Name = paramname[0];
this.Controls.Add(nud); this.Controls.Add(nud);

2
Tools/ArdupilotMegaPlanner/Controls/RangeControl.Designer.cs generated

@ -90,7 +90,7 @@
// //
this.numericUpDown1.Location = new System.Drawing.Point(3, 3); this.numericUpDown1.Location = new System.Drawing.Point(3, 3);
this.numericUpDown1.Name = "numericUpDown1"; this.numericUpDown1.Name = "numericUpDown1";
this.numericUpDown1.Size = new System.Drawing.Size(47, 20); this.numericUpDown1.Size = new System.Drawing.Size(57, 20);
this.numericUpDown1.TabIndex = 4; this.numericUpDown1.TabIndex = 4;
// //
// myLabel1 // myLabel1

BIN
Tools/ArdupilotMegaPlanner/Driver/arduino.cat

Binary file not shown.

2
Tools/ArdupilotMegaPlanner/Driver/arduino.inf

@ -8,7 +8,7 @@ Signature="$Windows NT$"
Class=Ports Class=Ports
ClassGuid={4D36E978-E325-11CE-BFC1-08002BE10318} ClassGuid={4D36E978-E325-11CE-BFC1-08002BE10318}
Provider=%MFGNAME% Provider=%MFGNAME%
DriverVer=01/01/2012,1.0.0.0 DriverVer=01/01/2012,1.0.0.1
CatalogFile=arduino.cat CatalogFile=arduino.cat
[Manufacturer] [Manufacturer]

BIN
Tools/ArdupilotMegaPlanner/Driver/px4fmu.cat

Binary file not shown.

110
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs generated

@ -137,6 +137,16 @@
this.myLabel3 = new ArdupilotMega.Controls.MyLabel(); this.myLabel3 = new ArdupilotMega.Controls.MyLabel();
this.myLabel2 = new ArdupilotMega.Controls.MyLabel(); this.myLabel2 = new ArdupilotMega.Controls.MyLabel();
this.myLabel1 = new ArdupilotMega.Controls.MyLabel(); this.myLabel1 = new ArdupilotMega.Controls.MyLabel();
this.groupBox2 = new System.Windows.Forms.GroupBox();
this.THR_ACCEL_D = new System.Windows.Forms.NumericUpDown();
this.label5 = new System.Windows.Forms.Label();
this.label6 = new System.Windows.Forms.Label();
this.THR_ACCEL_IMAX = new System.Windows.Forms.NumericUpDown();
this.THR_ACCEL_I = new System.Windows.Forms.NumericUpDown();
this.label7 = new System.Windows.Forms.Label();
this.THR_ACCEL_P = new System.Windows.Forms.NumericUpDown();
this.label8 = new System.Windows.Forms.Label();
this.MVCHK_thr_Acc_enable = new ArdupilotMega.Controls.MavlinkCheckBox();
((System.ComponentModel.ISupportInitialize)(this.TUNE_LOW)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.TUNE_LOW)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.TUNE_HIGH)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.TUNE_HIGH)).BeginInit();
this.groupBox5.SuspendLayout(); this.groupBox5.SuspendLayout();
@ -193,6 +203,11 @@
((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_IMAX)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_I)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_P)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_P)).BeginInit();
this.groupBox2.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.THR_ACCEL_D)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.THR_ACCEL_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.THR_ACCEL_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.THR_ACCEL_P)).BeginInit();
this.SuspendLayout(); this.SuspendLayout();
// //
// TUNE_LOW // TUNE_LOW
@ -303,6 +318,7 @@
resources.ApplyResources(this.groupBox4, "groupBox4"); resources.ApplyResources(this.groupBox4, "groupBox4");
this.groupBox4.Name = "groupBox4"; this.groupBox4.Name = "groupBox4";
this.groupBox4.TabStop = false; this.groupBox4.TabStop = false;
this.groupBox4.Enter += new System.EventHandler(this.groupBox4_Enter);
// //
// NAV_LAT_D // NAV_LAT_D
// //
@ -361,6 +377,7 @@
resources.ApplyResources(this.groupBox6, "groupBox6"); resources.ApplyResources(this.groupBox6, "groupBox6");
this.groupBox6.Name = "groupBox6"; this.groupBox6.Name = "groupBox6";
this.groupBox6.TabStop = false; this.groupBox6.TabStop = false;
this.groupBox6.Enter += new System.EventHandler(this.groupBox6_Enter);
// //
// XTRK_GAIN_SC // XTRK_GAIN_SC
// //
@ -383,6 +400,7 @@
resources.ApplyResources(this.groupBox7, "groupBox7"); resources.ApplyResources(this.groupBox7, "groupBox7");
this.groupBox7.Name = "groupBox7"; this.groupBox7.Name = "groupBox7";
this.groupBox7.TabStop = false; this.groupBox7.TabStop = false;
this.groupBox7.Enter += new System.EventHandler(this.groupBox7_Enter);
// //
// THR_ALT_IMAX // THR_ALT_IMAX
// //
@ -425,6 +443,7 @@
resources.ApplyResources(this.groupBox19, "groupBox19"); resources.ApplyResources(this.groupBox19, "groupBox19");
this.groupBox19.Name = "groupBox19"; this.groupBox19.Name = "groupBox19";
this.groupBox19.TabStop = false; this.groupBox19.TabStop = false;
this.groupBox19.Enter += new System.EventHandler(this.groupBox19_Enter);
// //
// HLD_LAT_IMAX // HLD_LAT_IMAX
// //
@ -467,6 +486,7 @@
resources.ApplyResources(this.groupBox20, "groupBox20"); resources.ApplyResources(this.groupBox20, "groupBox20");
this.groupBox20.Name = "groupBox20"; this.groupBox20.Name = "groupBox20";
this.groupBox20.TabStop = false; this.groupBox20.TabStop = false;
this.groupBox20.Enter += new System.EventHandler(this.groupBox20_Enter);
// //
// STB_YAW_IMAX // STB_YAW_IMAX
// //
@ -511,6 +531,7 @@
resources.ApplyResources(this.groupBox21, "groupBox21"); resources.ApplyResources(this.groupBox21, "groupBox21");
this.groupBox21.Name = "groupBox21"; this.groupBox21.Name = "groupBox21";
this.groupBox21.TabStop = false; this.groupBox21.TabStop = false;
this.groupBox21.Enter += new System.EventHandler(this.groupBox21_Enter);
// //
// STAB_D // STAB_D
// //
@ -607,6 +628,7 @@
resources.ApplyResources(this.groupBox23, "groupBox23"); resources.ApplyResources(this.groupBox23, "groupBox23");
this.groupBox23.Name = "groupBox23"; this.groupBox23.Name = "groupBox23";
this.groupBox23.TabStop = false; this.groupBox23.TabStop = false;
this.groupBox23.Enter += new System.EventHandler(this.groupBox23_Enter);
// //
// RATE_YAW_D // RATE_YAW_D
// //
@ -661,6 +683,7 @@
resources.ApplyResources(this.groupBox24, "groupBox24"); resources.ApplyResources(this.groupBox24, "groupBox24");
this.groupBox24.Name = "groupBox24"; this.groupBox24.Name = "groupBox24";
this.groupBox24.TabStop = false; this.groupBox24.TabStop = false;
this.groupBox24.Enter += new System.EventHandler(this.groupBox24_Enter);
// //
// RATE_PIT_D // RATE_PIT_D
// //
@ -775,6 +798,7 @@
resources.ApplyResources(this.groupBox1, "groupBox1"); resources.ApplyResources(this.groupBox1, "groupBox1");
this.groupBox1.Name = "groupBox1"; this.groupBox1.Name = "groupBox1";
this.groupBox1.TabStop = false; this.groupBox1.TabStop = false;
this.groupBox1.Enter += new System.EventHandler(this.groupBox1_Enter);
// //
// LOITER_LAT_D // LOITER_LAT_D
// //
@ -848,10 +872,81 @@
this.myLabel1.Name = "myLabel1"; this.myLabel1.Name = "myLabel1";
this.myLabel1.resize = false; this.myLabel1.resize = false;
// //
// groupBox2
//
this.groupBox2.Controls.Add(this.THR_ACCEL_D);
this.groupBox2.Controls.Add(this.label5);
this.groupBox2.Controls.Add(this.label6);
this.groupBox2.Controls.Add(this.THR_ACCEL_IMAX);
this.groupBox2.Controls.Add(this.THR_ACCEL_I);
this.groupBox2.Controls.Add(this.label7);
this.groupBox2.Controls.Add(this.THR_ACCEL_P);
this.groupBox2.Controls.Add(this.label8);
resources.ApplyResources(this.groupBox2, "groupBox2");
this.groupBox2.Name = "groupBox2";
this.groupBox2.TabStop = false;
//
// THR_ACCEL_D
//
resources.ApplyResources(this.THR_ACCEL_D, "THR_ACCEL_D");
this.THR_ACCEL_D.Name = "THR_ACCEL_D";
//
// label5
//
resources.ApplyResources(this.label5, "label5");
this.label5.Name = "label5";
//
// label6
//
resources.ApplyResources(this.label6, "label6");
this.label6.Name = "label6";
//
// THR_ACCEL_IMAX
//
resources.ApplyResources(this.THR_ACCEL_IMAX, "THR_ACCEL_IMAX");
this.THR_ACCEL_IMAX.Maximum = new decimal(new int[] {
1000,
0,
0,
0});
this.THR_ACCEL_IMAX.Name = "THR_ACCEL_IMAX";
//
// THR_ACCEL_I
//
resources.ApplyResources(this.THR_ACCEL_I, "THR_ACCEL_I");
this.THR_ACCEL_I.Name = "THR_ACCEL_I";
//
// label7
//
resources.ApplyResources(this.label7, "label7");
this.label7.Name = "label7";
//
// THR_ACCEL_P
//
resources.ApplyResources(this.THR_ACCEL_P, "THR_ACCEL_P");
this.THR_ACCEL_P.Name = "THR_ACCEL_P";
//
// label8
//
resources.ApplyResources(this.label8, "label8");
this.label8.Name = "label8";
//
// MVCHK_thr_Acc_enable
//
resources.ApplyResources(this.MVCHK_thr_Acc_enable, "MVCHK_thr_Acc_enable");
this.MVCHK_thr_Acc_enable.Name = "MVCHK_thr_Acc_enable";
this.MVCHK_thr_Acc_enable.OffValue = 0F;
this.MVCHK_thr_Acc_enable.OnValue = 1F;
this.MVCHK_thr_Acc_enable.param = null;
this.MVCHK_thr_Acc_enable.ParamName = null;
this.MVCHK_thr_Acc_enable.UseVisualStyleBackColor = true;
//
// ConfigArducopter // ConfigArducopter
// //
resources.ApplyResources(this, "$this"); resources.ApplyResources(this, "$this");
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.Controls.Add(this.MVCHK_thr_Acc_enable);
this.Controls.Add(this.groupBox2);
this.Controls.Add(this.groupBox1); this.Controls.Add(this.groupBox1);
this.Controls.Add(this.BUT_rerequestparams); this.Controls.Add(this.BUT_rerequestparams);
this.Controls.Add(this.BUT_writePIDS); this.Controls.Add(this.BUT_writePIDS);
@ -931,6 +1026,11 @@
((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_IMAX)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_I)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_P)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_P)).EndInit();
this.groupBox2.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.THR_ACCEL_D)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.THR_ACCEL_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.THR_ACCEL_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.THR_ACCEL_P)).EndInit();
this.ResumeLayout(false); this.ResumeLayout(false);
this.PerformLayout(); this.PerformLayout();
@ -1045,5 +1145,15 @@
private System.Windows.Forms.Label label3; private System.Windows.Forms.Label label3;
private System.Windows.Forms.NumericUpDown LOITER_LAT_P; private System.Windows.Forms.NumericUpDown LOITER_LAT_P;
private System.Windows.Forms.Label label4; private System.Windows.Forms.Label label4;
private System.Windows.Forms.GroupBox groupBox2;
private System.Windows.Forms.NumericUpDown THR_ACCEL_D;
private System.Windows.Forms.Label label5;
private System.Windows.Forms.Label label6;
private System.Windows.Forms.NumericUpDown THR_ACCEL_IMAX;
private System.Windows.Forms.NumericUpDown THR_ACCEL_I;
private System.Windows.Forms.Label label7;
private System.Windows.Forms.NumericUpDown THR_ACCEL_P;
private System.Windows.Forms.Label label8;
private Controls.MavlinkCheckBox MVCHK_thr_Acc_enable;
} }
} }

53
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs

@ -74,6 +74,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
// prefill all fields // prefill all fields
processToScreen(); processToScreen();
MVCHK_thr_Acc_enable.setup(1, 0, "THR_ACC_ENABLE", MainV2.comPort.MAV.param, groupBox2);
startup = false; startup = false;
} }
@ -188,12 +190,12 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
thisctl.Maximum = 9000; thisctl.Maximum = 9000;
thisctl.Minimum = -9000; thisctl.Minimum = -9000;
thisctl.Value = (decimal)numbervalue; thisctl.Value = (decimal)numbervalue;
thisctl.Increment = (decimal)0.001; thisctl.Increment = (decimal)0.0001;
if (thisctl.Name.EndsWith("_P") || thisctl.Name.EndsWith("_I") || thisctl.Name.EndsWith("_D") if (thisctl.Name.EndsWith("_P") || thisctl.Name.EndsWith("_I") || thisctl.Name.EndsWith("_D")
|| thisctl.Name.EndsWith("_LOW") || thisctl.Name.EndsWith("_HIGH") || thisctl.Value == 0 || thisctl.Name.EndsWith("_LOW") || thisctl.Name.EndsWith("_HIGH") || thisctl.Value == 0
|| thisctl.Value.ToString("0.###", new System.Globalization.CultureInfo("en-US")).Contains(".")) || thisctl.Value.ToString("0.####", new System.Globalization.CultureInfo("en-US")).Contains("."))
{ {
thisctl.DecimalPlaces = 3; thisctl.DecimalPlaces = 4;
} }
else else
{ {
@ -424,6 +426,51 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.Activate(); this.Activate();
} }
private void groupBox1_Enter(object sender, EventArgs e)
{
}
private void groupBox4_Enter(object sender, EventArgs e)
{
}
private void groupBox6_Enter(object sender, EventArgs e)
{
}
private void groupBox7_Enter(object sender, EventArgs e)
{
}
private void groupBox19_Enter(object sender, EventArgs e)
{
}
private void groupBox20_Enter(object sender, EventArgs e)
{
}
private void groupBox21_Enter(object sender, EventArgs e)
{
}
private void groupBox23_Enter(object sender, EventArgs e)
{
}
private void groupBox24_Enter(object sender, EventArgs e)
{
}
} }

2065
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx

File diff suppressed because it is too large Load Diff

68
Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs generated

@ -70,12 +70,12 @@
this.tableMap = new System.Windows.Forms.TableLayoutPanel(); this.tableMap = new System.Windows.Forms.TableLayoutPanel();
this.splitContainer1 = new System.Windows.Forms.SplitContainer(); this.splitContainer1 = new System.Windows.Forms.SplitContainer();
this.zg1 = new ZedGraph.ZedGraphControl(); this.zg1 = new ZedGraph.ZedGraphControl();
this.gMapControl1 = new ArdupilotMega.Controls.myGMAP();
this.TRK_zoom = new ArdupilotMega.Controls.MyTrackBar();
this.lbl_winddir = new ArdupilotMega.Controls.MyLabel(); this.lbl_winddir = new ArdupilotMega.Controls.MyLabel();
this.lbl_windvel = new ArdupilotMega.Controls.MyLabel(); this.lbl_windvel = new ArdupilotMega.Controls.MyLabel();
this.lbl_hdop = new ArdupilotMega.Controls.MyLabel(); this.lbl_hdop = new ArdupilotMega.Controls.MyLabel();
this.lbl_sats = new ArdupilotMega.Controls.MyLabel(); this.lbl_sats = new ArdupilotMega.Controls.MyLabel();
this.gMapControl1 = new ArdupilotMega.Controls.myGMAP();
this.TRK_zoom = new ArdupilotMega.Controls.MyTrackBar();
this.panel1 = new System.Windows.Forms.Panel(); this.panel1 = new System.Windows.Forms.Panel();
this.TXT_lat = new ArdupilotMega.Controls.MyLabel(); this.TXT_lat = new ArdupilotMega.Controls.MyLabel();
this.Zoomlevel = new System.Windows.Forms.NumericUpDown(); this.Zoomlevel = new System.Windows.Forms.NumericUpDown();
@ -1136,6 +1136,38 @@
this.zg1.ScrollMinY2 = 0D; this.zg1.ScrollMinY2 = 0D;
this.zg1.DoubleClick += new System.EventHandler(this.zg1_DoubleClick); this.zg1.DoubleClick += new System.EventHandler(this.zg1_DoubleClick);
// //
// lbl_winddir
//
this.lbl_winddir.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_dir", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Dir: 0"));
resources.ApplyResources(this.lbl_winddir, "lbl_winddir");
this.lbl_winddir.Name = "lbl_winddir";
this.lbl_winddir.resize = true;
this.toolTip1.SetToolTip(this.lbl_winddir, resources.GetString("lbl_winddir.ToolTip"));
//
// lbl_windvel
//
this.lbl_windvel.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_vel", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Vel: 0"));
resources.ApplyResources(this.lbl_windvel, "lbl_windvel");
this.lbl_windvel.Name = "lbl_windvel";
this.lbl_windvel.resize = true;
this.toolTip1.SetToolTip(this.lbl_windvel, resources.GetString("lbl_windvel.ToolTip"));
//
// lbl_hdop
//
resources.ApplyResources(this.lbl_hdop, "lbl_hdop");
this.lbl_hdop.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "gpshdop", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "hdop: 0.0"));
this.lbl_hdop.Name = "lbl_hdop";
this.lbl_hdop.resize = true;
this.toolTip1.SetToolTip(this.lbl_hdop, resources.GetString("lbl_hdop.ToolTip"));
//
// lbl_sats
//
resources.ApplyResources(this.lbl_sats, "lbl_sats");
this.lbl_sats.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "satcount", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Sats: 0"));
this.lbl_sats.Name = "lbl_sats";
this.lbl_sats.resize = true;
this.toolTip1.SetToolTip(this.lbl_sats, resources.GetString("lbl_sats.ToolTip"));
//
// gMapControl1 // gMapControl1
// //
this.gMapControl1.Bearing = 0F; this.gMapControl1.Bearing = 0F;
@ -1174,38 +1206,6 @@
this.TRK_zoom.Value = 10D; this.TRK_zoom.Value = 10D;
this.TRK_zoom.Scroll += new System.EventHandler(this.TRK_zoom_Scroll); this.TRK_zoom.Scroll += new System.EventHandler(this.TRK_zoom_Scroll);
// //
// lbl_winddir
//
this.lbl_winddir.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_dir", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Dir: 0"));
resources.ApplyResources(this.lbl_winddir, "lbl_winddir");
this.lbl_winddir.Name = "lbl_winddir";
this.lbl_winddir.resize = true;
this.toolTip1.SetToolTip(this.lbl_winddir, resources.GetString("lbl_winddir.ToolTip"));
//
// lbl_windvel
//
this.lbl_windvel.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_vel", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Vel: 0"));
resources.ApplyResources(this.lbl_windvel, "lbl_windvel");
this.lbl_windvel.Name = "lbl_windvel";
this.lbl_windvel.resize = true;
this.toolTip1.SetToolTip(this.lbl_windvel, resources.GetString("lbl_windvel.ToolTip"));
//
// lbl_hdop
//
resources.ApplyResources(this.lbl_hdop, "lbl_hdop");
this.lbl_hdop.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "gpshdop", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "hdop: 0.0"));
this.lbl_hdop.Name = "lbl_hdop";
this.lbl_hdop.resize = true;
this.toolTip1.SetToolTip(this.lbl_hdop, resources.GetString("lbl_hdop.ToolTip"));
//
// lbl_sats
//
resources.ApplyResources(this.lbl_sats, "lbl_sats");
this.lbl_sats.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "satcount", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Sats: 0"));
this.lbl_sats.Name = "lbl_sats";
this.lbl_sats.resize = true;
this.toolTip1.SetToolTip(this.lbl_sats, resources.GetString("lbl_sats.ToolTip"));
//
// panel1 // panel1
// //
this.panel1.Controls.Add(this.TXT_lat); this.panel1.Controls.Add(this.TXT_lat);

3
Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs

@ -2326,7 +2326,8 @@ print 'Roll complete'
CheckBox chk_box = new CheckBox(); CheckBox chk_box = new CheckBox();
if (((QuickView)sender).Tag.ToString() == field.Name) // dont change to ToString() = null exception
if (((QuickView)sender).Tag == field.Name)
chk_box.Checked = true; chk_box.Checked = true;
chk_box.Text = field.Name; chk_box.Text = field.Name;

86
Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx

@ -244,7 +244,7 @@
<value>hud1</value> <value>hud1</value>
</data> </data>
<data name="&gt;&gt;hud1.Type" xml:space="preserve"> <data name="&gt;&gt;hud1.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.HUD, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.HUD, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;hud1.Parent" xml:space="preserve"> <data name="&gt;&gt;hud1.Parent" xml:space="preserve">
<value>SubMainLeft.Panel1</value> <value>SubMainLeft.Panel1</value>
@ -283,7 +283,7 @@
<value>quickView6</value> <value>quickView6</value>
</data> </data>
<data name="&gt;&gt;quickView6.Type" xml:space="preserve"> <data name="&gt;&gt;quickView6.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;quickView6.Parent" xml:space="preserve"> <data name="&gt;&gt;quickView6.Parent" xml:space="preserve">
<value>tabQuick</value> <value>tabQuick</value>
@ -307,7 +307,7 @@
<value>quickView5</value> <value>quickView5</value>
</data> </data>
<data name="&gt;&gt;quickView5.Type" xml:space="preserve"> <data name="&gt;&gt;quickView5.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;quickView5.Parent" xml:space="preserve"> <data name="&gt;&gt;quickView5.Parent" xml:space="preserve">
<value>tabQuick</value> <value>tabQuick</value>
@ -331,7 +331,7 @@
<value>quickView4</value> <value>quickView4</value>
</data> </data>
<data name="&gt;&gt;quickView4.Type" xml:space="preserve"> <data name="&gt;&gt;quickView4.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;quickView4.Parent" xml:space="preserve"> <data name="&gt;&gt;quickView4.Parent" xml:space="preserve">
<value>tabQuick</value> <value>tabQuick</value>
@ -355,7 +355,7 @@
<value>quickView3</value> <value>quickView3</value>
</data> </data>
<data name="&gt;&gt;quickView3.Type" xml:space="preserve"> <data name="&gt;&gt;quickView3.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;quickView3.Parent" xml:space="preserve"> <data name="&gt;&gt;quickView3.Parent" xml:space="preserve">
<value>tabQuick</value> <value>tabQuick</value>
@ -379,7 +379,7 @@
<value>quickView2</value> <value>quickView2</value>
</data> </data>
<data name="&gt;&gt;quickView2.Type" xml:space="preserve"> <data name="&gt;&gt;quickView2.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;quickView2.Parent" xml:space="preserve"> <data name="&gt;&gt;quickView2.Parent" xml:space="preserve">
<value>tabQuick</value> <value>tabQuick</value>
@ -409,7 +409,7 @@
<value>quickView1</value> <value>quickView1</value>
</data> </data>
<data name="&gt;&gt;quickView1.Type" xml:space="preserve"> <data name="&gt;&gt;quickView1.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;quickView1.Parent" xml:space="preserve"> <data name="&gt;&gt;quickView1.Parent" xml:space="preserve">
<value>tabQuick</value> <value>tabQuick</value>
@ -457,7 +457,7 @@
<value>modifyandSetSpeed</value> <value>modifyandSetSpeed</value>
</data> </data>
<data name="&gt;&gt;modifyandSetSpeed.Type" xml:space="preserve"> <data name="&gt;&gt;modifyandSetSpeed.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;modifyandSetSpeed.Parent" xml:space="preserve"> <data name="&gt;&gt;modifyandSetSpeed.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -478,7 +478,7 @@
<value>modifyandSetAlt</value> <value>modifyandSetAlt</value>
</data> </data>
<data name="&gt;&gt;modifyandSetAlt.Type" xml:space="preserve"> <data name="&gt;&gt;modifyandSetAlt.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;modifyandSetAlt.Parent" xml:space="preserve"> <data name="&gt;&gt;modifyandSetAlt.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -511,7 +511,7 @@
<value>BUT_ARM</value> <value>BUT_ARM</value>
</data> </data>
<data name="&gt;&gt;BUT_ARM.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_ARM.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_ARM.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_ARM.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -538,7 +538,7 @@
<value>BUT_script</value> <value>BUT_script</value>
</data> </data>
<data name="&gt;&gt;BUT_script.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_script.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_script.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_script.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -568,7 +568,7 @@
<value>BUT_joystick</value> <value>BUT_joystick</value>
</data> </data>
<data name="&gt;&gt;BUT_joystick.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_joystick.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_joystick.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_joystick.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -598,7 +598,7 @@
<value>BUT_quickmanual</value> <value>BUT_quickmanual</value>
</data> </data>
<data name="&gt;&gt;BUT_quickmanual.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_quickmanual.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_quickmanual.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_quickmanual.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -628,7 +628,7 @@
<value>BUT_quickrtl</value> <value>BUT_quickrtl</value>
</data> </data>
<data name="&gt;&gt;BUT_quickrtl.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_quickrtl.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_quickrtl.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_quickrtl.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -658,7 +658,7 @@
<value>BUT_quickauto</value> <value>BUT_quickauto</value>
</data> </data>
<data name="&gt;&gt;BUT_quickauto.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_quickauto.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_quickauto.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_quickauto.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -712,7 +712,7 @@
<value>BUT_setwp</value> <value>BUT_setwp</value>
</data> </data>
<data name="&gt;&gt;BUT_setwp.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_setwp.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_setwp.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_setwp.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -763,7 +763,7 @@
<value>BUT_setmode</value> <value>BUT_setmode</value>
</data> </data>
<data name="&gt;&gt;BUT_setmode.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_setmode.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_setmode.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_setmode.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -793,7 +793,7 @@
<value>BUT_clear_track</value> <value>BUT_clear_track</value>
</data> </data>
<data name="&gt;&gt;BUT_clear_track.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_clear_track.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_clear_track.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_clear_track.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -844,7 +844,7 @@
<value>BUT_Homealt</value> <value>BUT_Homealt</value>
</data> </data>
<data name="&gt;&gt;BUT_Homealt.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_Homealt.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_Homealt.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_Homealt.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -874,7 +874,7 @@
<value>BUT_RAWSensor</value> <value>BUT_RAWSensor</value>
</data> </data>
<data name="&gt;&gt;BUT_RAWSensor.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_RAWSensor.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_RAWSensor.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_RAWSensor.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -904,7 +904,7 @@
<value>BUTrestartmission</value> <value>BUTrestartmission</value>
</data> </data>
<data name="&gt;&gt;BUTrestartmission.Type" xml:space="preserve"> <data name="&gt;&gt;BUTrestartmission.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUTrestartmission.Parent" xml:space="preserve"> <data name="&gt;&gt;BUTrestartmission.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -934,7 +934,7 @@
<value>BUTactiondo</value> <value>BUTactiondo</value>
</data> </data>
<data name="&gt;&gt;BUTactiondo.Type" xml:space="preserve"> <data name="&gt;&gt;BUTactiondo.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUTactiondo.Parent" xml:space="preserve"> <data name="&gt;&gt;BUTactiondo.Parent" xml:space="preserve">
<value>tabActions</value> <value>tabActions</value>
@ -988,7 +988,7 @@
<value>Gvspeed</value> <value>Gvspeed</value>
</data> </data>
<data name="&gt;&gt;Gvspeed.Type" xml:space="preserve"> <data name="&gt;&gt;Gvspeed.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;Gvspeed.Parent" xml:space="preserve"> <data name="&gt;&gt;Gvspeed.Parent" xml:space="preserve">
<value>tabGauges</value> <value>tabGauges</value>
@ -1018,7 +1018,7 @@
<value>Gheading</value> <value>Gheading</value>
</data> </data>
<data name="&gt;&gt;Gheading.Type" xml:space="preserve"> <data name="&gt;&gt;Gheading.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;Gheading.Parent" xml:space="preserve"> <data name="&gt;&gt;Gheading.Parent" xml:space="preserve">
<value>tabGauges</value> <value>tabGauges</value>
@ -1048,7 +1048,7 @@
<value>Galt</value> <value>Galt</value>
</data> </data>
<data name="&gt;&gt;Galt.Type" xml:space="preserve"> <data name="&gt;&gt;Galt.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;Galt.Parent" xml:space="preserve"> <data name="&gt;&gt;Galt.Parent" xml:space="preserve">
<value>tabGauges</value> <value>tabGauges</value>
@ -1081,7 +1081,7 @@
<value>Gspeed</value> <value>Gspeed</value>
</data> </data>
<data name="&gt;&gt;Gspeed.Type" xml:space="preserve"> <data name="&gt;&gt;Gspeed.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;Gspeed.Parent" xml:space="preserve"> <data name="&gt;&gt;Gspeed.Parent" xml:space="preserve">
<value>tabGauges</value> <value>tabGauges</value>
@ -1165,7 +1165,7 @@
<value>lbl_playbackspeed</value> <value>lbl_playbackspeed</value>
</data> </data>
<data name="&gt;&gt;lbl_playbackspeed.Type" xml:space="preserve"> <data name="&gt;&gt;lbl_playbackspeed.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;lbl_playbackspeed.Parent" xml:space="preserve"> <data name="&gt;&gt;lbl_playbackspeed.Parent" xml:space="preserve">
<value>tabTLogs</value> <value>tabTLogs</value>
@ -1192,7 +1192,7 @@
<value>lbl_logpercent</value> <value>lbl_logpercent</value>
</data> </data>
<data name="&gt;&gt;lbl_logpercent.Type" xml:space="preserve"> <data name="&gt;&gt;lbl_logpercent.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;lbl_logpercent.Parent" xml:space="preserve"> <data name="&gt;&gt;lbl_logpercent.Parent" xml:space="preserve">
<value>tabTLogs</value> <value>tabTLogs</value>
@ -1219,7 +1219,7 @@
<value>NUM_playbackspeed</value> <value>NUM_playbackspeed</value>
</data> </data>
<data name="&gt;&gt;NUM_playbackspeed.Type" xml:space="preserve"> <data name="&gt;&gt;NUM_playbackspeed.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;NUM_playbackspeed.Parent" xml:space="preserve"> <data name="&gt;&gt;NUM_playbackspeed.Parent" xml:space="preserve">
<value>tabTLogs</value> <value>tabTLogs</value>
@ -1246,7 +1246,7 @@
<value>BUT_log2kml</value> <value>BUT_log2kml</value>
</data> </data>
<data name="&gt;&gt;BUT_log2kml.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_log2kml.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_log2kml.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_log2kml.Parent" xml:space="preserve">
<value>tabTLogs</value> <value>tabTLogs</value>
@ -1300,7 +1300,7 @@
<value>BUT_playlog</value> <value>BUT_playlog</value>
</data> </data>
<data name="&gt;&gt;BUT_playlog.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_playlog.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_playlog.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_playlog.Parent" xml:space="preserve">
<value>tabTLogs</value> <value>tabTLogs</value>
@ -1327,7 +1327,7 @@
<value>BUT_loadtelem</value> <value>BUT_loadtelem</value>
</data> </data>
<data name="&gt;&gt;BUT_loadtelem.Type" xml:space="preserve"> <data name="&gt;&gt;BUT_loadtelem.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;BUT_loadtelem.Parent" xml:space="preserve"> <data name="&gt;&gt;BUT_loadtelem.Parent" xml:space="preserve">
<value>tabTLogs</value> <value>tabTLogs</value>
@ -1513,7 +1513,7 @@
<value>lbl_winddir</value> <value>lbl_winddir</value>
</data> </data>
<data name="&gt;&gt;lbl_winddir.Type" xml:space="preserve"> <data name="&gt;&gt;lbl_winddir.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;lbl_winddir.Parent" xml:space="preserve"> <data name="&gt;&gt;lbl_winddir.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value> <value>splitContainer1.Panel2</value>
@ -1543,7 +1543,7 @@
<value>lbl_windvel</value> <value>lbl_windvel</value>
</data> </data>
<data name="&gt;&gt;lbl_windvel.Type" xml:space="preserve"> <data name="&gt;&gt;lbl_windvel.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;lbl_windvel.Parent" xml:space="preserve"> <data name="&gt;&gt;lbl_windvel.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value> <value>splitContainer1.Panel2</value>
@ -1576,7 +1576,7 @@
<value>lbl_hdop</value> <value>lbl_hdop</value>
</data> </data>
<data name="&gt;&gt;lbl_hdop.Type" xml:space="preserve"> <data name="&gt;&gt;lbl_hdop.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;lbl_hdop.Parent" xml:space="preserve"> <data name="&gt;&gt;lbl_hdop.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value> <value>splitContainer1.Panel2</value>
@ -1609,7 +1609,7 @@
<value>lbl_sats</value> <value>lbl_sats</value>
</data> </data>
<data name="&gt;&gt;lbl_sats.Type" xml:space="preserve"> <data name="&gt;&gt;lbl_sats.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;lbl_sats.Parent" xml:space="preserve"> <data name="&gt;&gt;lbl_sats.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value> <value>splitContainer1.Panel2</value>
@ -1781,7 +1781,7 @@
<value>gMapControl1</value> <value>gMapControl1</value>
</data> </data>
<data name="&gt;&gt;gMapControl1.Type" xml:space="preserve"> <data name="&gt;&gt;gMapControl1.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;gMapControl1.Parent" xml:space="preserve"> <data name="&gt;&gt;gMapControl1.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value> <value>splitContainer1.Panel2</value>
@ -1808,7 +1808,7 @@
<value>TRK_zoom</value> <value>TRK_zoom</value>
</data> </data>
<data name="&gt;&gt;TRK_zoom.Type" xml:space="preserve"> <data name="&gt;&gt;TRK_zoom.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;TRK_zoom.Parent" xml:space="preserve"> <data name="&gt;&gt;TRK_zoom.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value> <value>splitContainer1.Panel2</value>
@ -1871,7 +1871,7 @@
<value>TXT_lat</value> <value>TXT_lat</value>
</data> </data>
<data name="&gt;&gt;TXT_lat.Type" xml:space="preserve"> <data name="&gt;&gt;TXT_lat.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;TXT_lat.Parent" xml:space="preserve"> <data name="&gt;&gt;TXT_lat.Parent" xml:space="preserve">
<value>panel1</value> <value>panel1</value>
@ -1928,7 +1928,7 @@
<value>label1</value> <value>label1</value>
</data> </data>
<data name="&gt;&gt;label1.Type" xml:space="preserve"> <data name="&gt;&gt;label1.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;label1.Parent" xml:space="preserve"> <data name="&gt;&gt;label1.Parent" xml:space="preserve">
<value>panel1</value> <value>panel1</value>
@ -1958,7 +1958,7 @@
<value>TXT_long</value> <value>TXT_long</value>
</data> </data>
<data name="&gt;&gt;TXT_long.Type" xml:space="preserve"> <data name="&gt;&gt;TXT_long.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;TXT_long.Parent" xml:space="preserve"> <data name="&gt;&gt;TXT_long.Parent" xml:space="preserve">
<value>panel1</value> <value>panel1</value>
@ -1988,7 +1988,7 @@
<value>TXT_alt</value> <value>TXT_alt</value>
</data> </data>
<data name="&gt;&gt;TXT_alt.Type" xml:space="preserve"> <data name="&gt;&gt;TXT_alt.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
<data name="&gt;&gt;TXT_alt.Parent" xml:space="preserve"> <data name="&gt;&gt;TXT_alt.Parent" xml:space="preserve">
<value>panel1</value> <value>panel1</value>
@ -2279,6 +2279,6 @@
<value>FlightData</value> <value>FlightData</value>
</data> </data>
<data name="&gt;&gt;$this.Type" xml:space="preserve"> <data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null</value> <value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4725.11331, Culture=neutral, PublicKeyToken=null</value>
</data> </data>
</root> </root>

21
Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs

@ -217,7 +217,7 @@ namespace ArdupilotMega.GCSViews
{ {
DateTime start = DateTime.Now; DateTime start = DateTime.Now;
while ((DateTime.Now - start).TotalMilliseconds < time) while ((DateTime.Now - start).TotalMilliseconds < time && !inlogview)
{ {
try try
{ {
@ -234,7 +234,7 @@ namespace ArdupilotMega.GCSViews
{ {
DateTime start = DateTime.Now; DateTime start = DateTime.Now;
while ((DateTime.Now - start).TotalMilliseconds < time) while ((DateTime.Now - start).TotalMilliseconds < time && !inlogview)
{ {
try try
{ {
@ -273,20 +273,25 @@ namespace ArdupilotMega.GCSViews
threadrun = true; threadrun = true;
// 10 sec // 10 sec
waitandsleep(10000); if (!inlogview)
waitandsleep(10000);
// 100 ms // 100 ms
readandsleep(100); if (!inlogview)
readandsleep(100);
try try
{ {
comPort.Write("\n\n\n"); if (!inlogview)
comPort.Write("\n\n\n");
// 1 secs // 1 secs
readandsleep(1000); if (!inlogview)
readandsleep(1000);
comPort.Write("\r\r\r?\r"); if (!inlogview)
comPort.Write("\r\r\r?\r");
} }
catch { threadrun = false; return; } catch { threadrun = false; return; }
while (threadrun) while (threadrun)
{ {

50
Tools/ArdupilotMegaPlanner/Msi/installer.wxs

@ -2,14 +2,14 @@
<Wix xmlns="http://schemas.microsoft.com/wix/2006/wi" xmlns:netfx="http://schemas.microsoft.com/wix/NetFxExtension" xmlns:difx="http://schemas.microsoft.com/wix/DifxAppExtension" xmlns:iis='http://schemas.microsoft.com/wix/IIsExtension' > <Wix xmlns="http://schemas.microsoft.com/wix/2006/wi" xmlns:netfx="http://schemas.microsoft.com/wix/NetFxExtension" xmlns:difx="http://schemas.microsoft.com/wix/DifxAppExtension" xmlns:iis='http://schemas.microsoft.com/wix/IIsExtension' >
<Product Id="*" Name="Mission Planner" Language="1033" Version="1.2.25" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}"> <Product Id="*" Name="Mission Planner" Language="1033" Version="1.2.26" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
<Package Description="Mission Planner Installer" Comments="Mission Planner Installer" Manufacturer="Michael Oborne" InstallerVersion="200" Compressed="yes" /> <Package Description="Mission Planner Installer" Comments="Mission Planner Installer" Manufacturer="Michael Oborne" InstallerVersion="200" Compressed="yes" />
<Upgrade Id="{625389D7-EB3C-4d77-A5F6-A285CF99437D}"> <Upgrade Id="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
<UpgradeVersion OnlyDetect="yes" Minimum="1.2.25" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" /> <UpgradeVersion OnlyDetect="yes" Minimum="1.2.26" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" />
<UpgradeVersion OnlyDetect="no" Maximum="1.2.25" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" /> <UpgradeVersion OnlyDetect="no" Maximum="1.2.26" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" />
</Upgrade> </Upgrade>
<InstallExecuteSequence> <InstallExecuteSequence>
@ -31,7 +31,7 @@
<Permission User="Everyone" GenericAll="yes" /> <Permission User="Everyone" GenericAll="yes" />
</CreateFolder> </CreateFolder>
</Component> </Component>
<Component Id="_comp1" Guid="8eda8864-af82-496a-aa0f-abec8aa5cf38"> <Component Id="_comp1" Guid="19e3bd54-2962-4428-b0c0-d6714c4db4b2">
<File Id="_2" Source="..\bin\release\.gdbinit" /> <File Id="_2" Source="..\bin\release\.gdbinit" />
<File Id="_3" Source="..\bin\release\.gitignore" /> <File Id="_3" Source="..\bin\release\.gitignore" />
<File Id="_4" Source="..\bin\release\aerosim3.91.txt" /> <File Id="_4" Source="..\bin\release\aerosim3.91.txt" />
@ -106,11 +106,11 @@
<File Id="_73" Source="..\bin\release\ZedGraph.dll" /> <File Id="_73" Source="..\bin\release\ZedGraph.dll" />
</Component> </Component>
<Directory Id="aircraft73" Name="aircraft"> <Directory Id="aircraft73" Name="aircraft">
<Component Id="_comp74" Guid="ef20ba3d-39a7-4477-9233-f3909045a2c9"> <Component Id="_comp74" Guid="2e206c50-a59e-4cac-9f72-c671d21fa499">
<File Id="_75" Source="..\bin\release\aircraft\placeholder.txt" /> <File Id="_75" Source="..\bin\release\aircraft\placeholder.txt" />
</Component> </Component>
<Directory Id="arducopter75" Name="arducopter"> <Directory Id="arducopter75" Name="arducopter">
<Component Id="_comp76" Guid="ed499a14-18e1-40ed-9453-87f0d5fccbe5"> <Component Id="_comp76" Guid="83d68a79-9cb9-405e-87a6-6c398348b905">
<File Id="_77" Source="..\bin\release\aircraft\arducopter\arducopter-set.xml" /> <File Id="_77" Source="..\bin\release\aircraft\arducopter\arducopter-set.xml" />
<File Id="_78" Source="..\bin\release\aircraft\arducopter\arducopter.jpg" /> <File Id="_78" Source="..\bin\release\aircraft\arducopter\arducopter.jpg" />
<File Id="_79" Source="..\bin\release\aircraft\arducopter\arducopter.xml" /> <File Id="_79" Source="..\bin\release\aircraft\arducopter\arducopter.xml" />
@ -121,20 +121,20 @@
<File Id="_84" Source="..\bin\release\aircraft\arducopter\README" /> <File Id="_84" Source="..\bin\release\aircraft\arducopter\README" />
</Component> </Component>
<Directory Id="data84" Name="data"> <Directory Id="data84" Name="data">
<Component Id="_comp85" Guid="3bd5e16c-ac2d-402b-b263-fa7f698d328f"> <Component Id="_comp85" Guid="5e7d27cb-61b2-4779-81e0-c79b1c7c1bb5">
<File Id="_86" Source="..\bin\release\aircraft\arducopter\data\arducopter_half_step.txt" /> <File Id="_86" Source="..\bin\release\aircraft\arducopter\data\arducopter_half_step.txt" />
<File Id="_87" Source="..\bin\release\aircraft\arducopter\data\arducopter_step.txt" /> <File Id="_87" Source="..\bin\release\aircraft\arducopter\data\arducopter_step.txt" />
<File Id="_88" Source="..\bin\release\aircraft\arducopter\data\rw_generic_pylon.ac" /> <File Id="_88" Source="..\bin\release\aircraft\arducopter\data\rw_generic_pylon.ac" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="Engines88" Name="Engines"> <Directory Id="Engines88" Name="Engines">
<Component Id="_comp89" Guid="ff2beef6-2c12-430c-9e08-cc92a434d312"> <Component Id="_comp89" Guid="3f5f845d-1c08-4edf-989a-02415f201f8d">
<File Id="_90" Source="..\bin\release\aircraft\arducopter\Engines\a2830-12.xml" /> <File Id="_90" Source="..\bin\release\aircraft\arducopter\Engines\a2830-12.xml" />
<File Id="_91" Source="..\bin\release\aircraft\arducopter\Engines\prop10x4.5.xml" /> <File Id="_91" Source="..\bin\release\aircraft\arducopter\Engines\prop10x4.5.xml" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="Models91" Name="Models"> <Directory Id="Models91" Name="Models">
<Component Id="_comp92" Guid="dd1c4dbe-13f3-49d7-8ad4-9d791154b616"> <Component Id="_comp92" Guid="08960001-11f3-47a9-a03b-dc14082cc646">
<File Id="_93" Source="..\bin\release\aircraft\arducopter\Models\arducopter.ac" /> <File Id="_93" Source="..\bin\release\aircraft\arducopter\Models\arducopter.ac" />
<File Id="_94" Source="..\bin\release\aircraft\arducopter\Models\arducopter.xml" /> <File Id="_94" Source="..\bin\release\aircraft\arducopter\Models\arducopter.xml" />
<File Id="_95" Source="..\bin\release\aircraft\arducopter\Models\plus_quad.ac" /> <File Id="_95" Source="..\bin\release\aircraft\arducopter\Models\plus_quad.ac" />
@ -148,7 +148,7 @@
</Directory> </Directory>
</Directory> </Directory>
<Directory Id="Rascal101" Name="Rascal"> <Directory Id="Rascal101" Name="Rascal">
<Component Id="_comp102" Guid="8e12a66c-496f-4061-b983-39dd323a02d8"> <Component Id="_comp102" Guid="0af0c3ab-6412-4397-9f43-31bddad578e8">
<File Id="_103" Source="..\bin\release\aircraft\Rascal\Rascal-keyboard.xml" /> <File Id="_103" Source="..\bin\release\aircraft\Rascal\Rascal-keyboard.xml" />
<File Id="_104" Source="..\bin\release\aircraft\Rascal\Rascal-submodels.xml" /> <File Id="_104" Source="..\bin\release\aircraft\Rascal\Rascal-submodels.xml" />
<File Id="_105" Source="..\bin\release\aircraft\Rascal\Rascal.xml" /> <File Id="_105" Source="..\bin\release\aircraft\Rascal\Rascal.xml" />
@ -160,13 +160,13 @@
<File Id="_111" Source="..\bin\release\aircraft\Rascal\thumbnail.jpg" /> <File Id="_111" Source="..\bin\release\aircraft\Rascal\thumbnail.jpg" />
</Component> </Component>
<Directory Id="Engines111" Name="Engines"> <Directory Id="Engines111" Name="Engines">
<Component Id="_comp112" Guid="29c6a326-4b22-4bea-86c5-45acb89ad1b3"> <Component Id="_comp112" Guid="85547752-4ae1-4952-934b-35de595351dd">
<File Id="_113" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml" /> <File Id="_113" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml" />
<File Id="_114" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml" /> <File Id="_114" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="Models114" Name="Models"> <Directory Id="Models114" Name="Models">
<Component Id="_comp115" Guid="2bf62e16-131d-4044-9f9e-85f46165e864"> <Component Id="_comp115" Guid="1097d010-daae-474e-9563-3f00273e1e55">
<File Id="_116" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb" /> <File Id="_116" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb" />
<File Id="_117" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac" /> <File Id="_117" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac" />
<File Id="_118" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml" /> <File Id="_118" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml" />
@ -177,7 +177,7 @@
</Component> </Component>
</Directory> </Directory>
<Directory Id="Systems122" Name="Systems"> <Directory Id="Systems122" Name="Systems">
<Component Id="_comp123" Guid="7d4cce5e-cc7f-4e7b-bdae-39b4b819b990"> <Component Id="_comp123" Guid="ee0e2198-9811-4979-a5e2-636225c01719">
<File Id="_124" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml" /> <File Id="_124" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml" />
<File Id="_125" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas" /> <File Id="_125" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas" />
<File Id="_126" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml" /> <File Id="_126" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml" />
@ -188,12 +188,12 @@
</Directory> </Directory>
</Directory> </Directory>
<Directory Id="de_DE128" Name="de-DE"> <Directory Id="de_DE128" Name="de-DE">
<Component Id="_comp129" Guid="b32fc040-351e-4047-8a03-898c091df6b8"> <Component Id="_comp129" Guid="eb3dff79-795a-403d-a486-d446217dae0f">
<File Id="_130" Source="..\bin\release\de-DE\ArdupilotMegaPlanner10.resources.dll" /> <File Id="_130" Source="..\bin\release\de-DE\ArdupilotMegaPlanner10.resources.dll" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="Driver130" Name="Driver"> <Directory Id="Driver130" Name="Driver">
<Component Id="_comp131" Guid="6fea680e-3d6a-4760-a602-db0c16e5c837"> <Component Id="_comp131" Guid="884a1413-d231-4187-ae9b-320820669ab9">
<File Id="_132" Source="..\bin\release\Driver\arduino.cat" /> <File Id="_132" Source="..\bin\release\Driver\arduino.cat" />
<File Id="_133" Source="..\bin\release\Driver\arduino.inf" /> <File Id="_133" Source="..\bin\release\Driver\arduino.inf" />
<File Id="_134" Source="..\bin\release\Driver\px4fmu.cat" /> <File Id="_134" Source="..\bin\release\Driver\px4fmu.cat" />
@ -202,31 +202,31 @@
</Component> </Component>
</Directory> </Directory>
<Directory Id="es_ES136" Name="es-ES"> <Directory Id="es_ES136" Name="es-ES">
<Component Id="_comp137" Guid="8e85f491-bbc4-447f-bbd7-8e9fd5ec70b1"> <Component Id="_comp137" Guid="03ad39f7-9702-45c4-9d27-c6170fd0a8f0">
<File Id="_138" Source="..\bin\release\es-ES\ArdupilotMegaPlanner.resources.dll" /> <File Id="_138" Source="..\bin\release\es-ES\ArdupilotMegaPlanner.resources.dll" />
<File Id="_139" Source="..\bin\release\es-ES\ArdupilotMegaPlanner10.resources.dll" /> <File Id="_139" Source="..\bin\release\es-ES\ArdupilotMegaPlanner10.resources.dll" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="fr139" Name="fr"> <Directory Id="fr139" Name="fr">
<Component Id="_comp140" Guid="f81019ad-871c-4b7c-a529-1e0c295e873c"> <Component Id="_comp140" Guid="333b1a46-9313-4a20-8e0a-d746e01b699c">
<File Id="_141" Source="..\bin\release\fr\ArdupilotMegaPlanner.resources.dll" /> <File Id="_141" Source="..\bin\release\fr\ArdupilotMegaPlanner.resources.dll" />
<File Id="_142" Source="..\bin\release\fr\ArdupilotMegaPlanner10.resources.dll" /> <File Id="_142" Source="..\bin\release\fr\ArdupilotMegaPlanner10.resources.dll" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="it_IT142" Name="it-IT"> <Directory Id="it_IT142" Name="it-IT">
<Component Id="_comp143" Guid="f9fa8a36-27cb-4b57-ab47-99edbca336b0"> <Component Id="_comp143" Guid="8dbc5657-aa34-4e9f-b29b-98fe52d57cf8">
<File Id="_144" Source="..\bin\release\it-IT\ArdupilotMegaPlanner.resources.dll" /> <File Id="_144" Source="..\bin\release\it-IT\ArdupilotMegaPlanner.resources.dll" />
<File Id="_145" Source="..\bin\release\it-IT\ArdupilotMegaPlanner10.resources.dll" /> <File Id="_145" Source="..\bin\release\it-IT\ArdupilotMegaPlanner10.resources.dll" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="jsbsim145" Name="jsbsim"> <Directory Id="jsbsim145" Name="jsbsim">
<Component Id="_comp146" Guid="f59985bc-8f32-41ca-aada-ab9f06a26583"> <Component Id="_comp146" Guid="55946077-e708-4073-bd39-ecd855171b4b">
<File Id="_147" Source="..\bin\release\jsbsim\fgout.xml" /> <File Id="_147" Source="..\bin\release\jsbsim\fgout.xml" />
<File Id="_148" Source="..\bin\release\jsbsim\rascal_test.xml" /> <File Id="_148" Source="..\bin\release\jsbsim\rascal_test.xml" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="m3u148" Name="m3u"> <Directory Id="m3u148" Name="m3u">
<Component Id="_comp149" Guid="0e17a3c8-d9f4-4fb4-a782-48cda02b4a83"> <Component Id="_comp149" Guid="cf004c8f-916d-4d2a-b273-c2538c72ff3f">
<File Id="_150" Source="..\bin\release\m3u\both.m3u" /> <File Id="_150" Source="..\bin\release\m3u\both.m3u" />
<File Id="_151" Source="..\bin\release\m3u\GeoRefnetworklink.kml" /> <File Id="_151" Source="..\bin\release\m3u\GeoRefnetworklink.kml" />
<File Id="_152" Source="..\bin\release\m3u\hud.m3u" /> <File Id="_152" Source="..\bin\release\m3u\hud.m3u" />
@ -235,31 +235,31 @@
</Component> </Component>
</Directory> </Directory>
<Directory Id="pl154" Name="pl"> <Directory Id="pl154" Name="pl">
<Component Id="_comp155" Guid="b3f2efc0-2fff-44bf-a776-9e37a74ed100"> <Component Id="_comp155" Guid="40c37938-743d-492f-bc2e-200be62b2c7e">
<File Id="_156" Source="..\bin\release\pl\ArdupilotMegaPlanner.resources.dll" /> <File Id="_156" Source="..\bin\release\pl\ArdupilotMegaPlanner.resources.dll" />
<File Id="_157" Source="..\bin\release\pl\ArdupilotMegaPlanner10.resources.dll" /> <File Id="_157" Source="..\bin\release\pl\ArdupilotMegaPlanner10.resources.dll" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="Resources157" Name="Resources"> <Directory Id="Resources157" Name="Resources">
<Component Id="_comp158" Guid="c2f7719c-1373-4cda-a476-426c417a72b5"> <Component Id="_comp158" Guid="68103b73-338b-4ba7-8dac-bda2aa37f207">
<File Id="_159" Source="..\bin\release\Resources\MAVCmd.txt" /> <File Id="_159" Source="..\bin\release\Resources\MAVCmd.txt" />
<File Id="_160" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf" /> <File Id="_160" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="ru_RU160" Name="ru-RU"> <Directory Id="ru_RU160" Name="ru-RU">
<Component Id="_comp161" Guid="a4bf1286-c4fc-471d-bf53-cb370acdc205"> <Component Id="_comp161" Guid="3337d605-e25b-475b-8720-ac1d11c1b73f">
<File Id="_162" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner.resources.dll" /> <File Id="_162" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner.resources.dll" />
<File Id="_163" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner10.resources.dll" /> <File Id="_163" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner10.resources.dll" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="zh_Hans163" Name="zh-Hans"> <Directory Id="zh_Hans163" Name="zh-Hans">
<Component Id="_comp164" Guid="3052fa6a-f05f-4d91-aedd-2a12785684d7"> <Component Id="_comp164" Guid="0dad1edc-301a-422d-93bf-8aa310f9124a">
<File Id="_165" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner.resources.dll" /> <File Id="_165" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner.resources.dll" />
<File Id="_166" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner10.resources.dll" /> <File Id="_166" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner10.resources.dll" />
</Component> </Component>
</Directory> </Directory>
<Directory Id="zh_TW166" Name="zh-TW"> <Directory Id="zh_TW166" Name="zh-TW">
<Component Id="_comp167" Guid="d6efa64a-9952-446a-afd5-b40fbad8c877"> <Component Id="_comp167" Guid="46b9504b-7921-4dbd-82dc-d6a64548b0ed">
<File Id="_168" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner.resources.dll" /> <File Id="_168" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner.resources.dll" />
<File Id="_169" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner10.resources.dll" /> <File Id="_169" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner10.resources.dll" />
</Component> </Component>

2
Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs

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

4
Tools/ArdupilotMegaPlanner/wix/wix.csproj

@ -81,7 +81,9 @@
</ItemGroup> </ItemGroup>
<ItemGroup> <ItemGroup>
<None Include="app.config" /> <None Include="app.config" />
<None Include="Properties\app.manifest" /> <None Include="Properties\app.manifest">
<SubType>Designer</SubType>
</None>
<None Include="Properties\Settings.settings"> <None Include="Properties\Settings.settings">
<Generator>SettingsSingleFileGenerator</Generator> <Generator>SettingsSingleFileGenerator</Generator>
<LastGenOutput>Settings.Designer.cs</LastGenOutput> <LastGenOutput>Settings.Designer.cs</LastGenOutput>

Loading…
Cancel
Save