From 03dfcc7089c54a2ec3cdfc7f36806d7799e6ad9f Mon Sep 17 00:00:00 2001
From: Michael Oborne <mich146@hotmail.com>
Date: Tue, 24 Apr 2012 21:49:27 +0800
Subject: [PATCH] planner cleanup fixup mode names in joystick and flight data
 add mavlink 0.9/1.0 error message

---
 .../Antenna/ArduTracker.cs                    |    2 +-
 .../Antenna/ITrackerOutput.cs                 |    2 +-
 Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs |    2 +-
 .../Antenna/Tracker.Designer.cs               |    4 +-
 Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs |    1 +
 .../ArdupilotMegaPlanner/Antenna/Tracker.resx |    2 +-
 .../{ => Arduino}/ArduinoComms.cs             |   76 +-
 .../{ => Arduino}/ArduinoDetect.cs            |  919 ++---
 .../{ => Arduino}/ArduinoSTK.cs               |  669 ++--
 .../{ => Arduino}/ArduinoSTKv2.cs             |  776 ++--
 .../ArdupilotMegaPlanner/ArdupilotMega.csproj |   32 +-
 Tools/ArdupilotMegaPlanner/Camera.Designer.cs |    4 +-
 Tools/ArdupilotMegaPlanner/Camera.resx        |    2 +-
 Tools/ArdupilotMegaPlanner/Common.cs          |   24 +-
 .../{ => Comms}/CommsSerialInterface.cs       |  118 +-
 .../{ => Comms}/CommsSerialPort.cs            |  170 +-
 .../{ => Comms}/CommsTCPSerial.cs             |    8 +-
 .../{ => Comms}/CommsUdpSerial.cs             |  605 ++--
 .../Controls/ConfigPanel.cs                   |    2 +-
 .../Controls/CustomMessageBox.cs              |    6 +-
 .../{ => Controls}/HUD.cs                     | 3210 ++++++++---------
 .../Controls/ImageLabel.Designer.cs           |    2 +-
 .../Controls/ImageLabel.cs                    |    2 +-
 .../Controls/LineSeparator.cs                 |   41 +-
 .../ArdupilotMegaPlanner/Controls/MyButton.cs |    2 +-
 .../ArdupilotMegaPlanner/Controls/MyLabel.cs  |    4 +-
 .../Controls/MyTrackBar.cs                    |    2 +-
 .../Controls/MyUserControl.cs                 |    3 +
 .../Controls/ProgressReporterDialogue.cs      |    2 -
 .../Controls/XorPlus.Designer.cs              |  112 -
 .../ArdupilotMegaPlanner/Controls/XorPlus.cs  |   48 -
 .../Controls/XorPlus.resx                     |  120 -
 Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs |    5 +-
 .../GCSViews/Configuration.Designer.cs        |   48 +-
 .../GCSViews/Configuration.cs                 |    1 +
 .../GCSViews/Configuration.resx               |   38 +-
 ...gAccelerometerCalibrationPlane.Designer.cs |    4 +-
 .../ConfigAccelerometerCalibrationPlane.cs    |    1 +
 .../ConfigAccelerometerCalibrationPlane.resx  |    2 +-
 ...igAccelerometerCalibrationQuad.Designer.cs |    4 +-
 .../ConfigAccelerometerCalibrationQuad.cs     |    1 +
 .../ConfigAccelerometerCalibrationQuad.resx   |    2 +-
 .../ConfigArducopter.Designer.cs              |   12 +-
 .../ConfigurationView/ConfigArducopter.cs     |    1 +
 .../ConfigurationView/ConfigArducopter.resx   |    6 +-
 .../ConfigurationView/ConfigArduplane.cs      |    1 +
 .../ConfigBatteryMonitoring.cs                |    1 +
 .../ConfigFlightModes.Designer.cs             |    4 +-
 .../ConfigurationView/ConfigFlightModes.cs    |    1 +
 .../ConfigurationView/ConfigFlightModes.resx  |    2 +-
 .../ConfigHardwareOptions.Designer.cs         |    8 +-
 .../ConfigHardwareOptions.cs                  |    1 +
 .../ConfigHardwareOptions.resx                |    4 +-
 .../ConfigPlanner.Designer.cs                 |   12 +-
 .../ConfigurationView/ConfigPlanner.cs        |    1 +
 .../ConfigurationView/ConfigPlanner.resx      |    6 +-
 .../ConfigRadioInput.Designer.cs              |    4 +-
 .../ConfigurationView/ConfigRadioInput.cs     |    1 +
 .../ConfigurationView/ConfigRadioInput.resx   |    2 +-
 .../ConfigRawParams.Designer.cs               |   20 +-
 .../ConfigurationView/ConfigRawParams.cs      |    1 +
 .../ConfigurationView/ConfigRawParams.resx    |   10 +-
 .../ConfigTradHeli.Designer.cs                |   12 +-
 .../ConfigurationView/ConfigTradHeli.cs       |    3 +-
 .../ConfigurationView/ConfigTradHeli.resx     |    6 +-
 .../ConfigurationView/Configuration.cs        |    3 +-
 .../GCSViews/ConfigurationView/Setup.cs       |    2 +
 .../GCSViews/Firmware.Designer.cs             |   36 +-
 .../ArdupilotMegaPlanner/GCSViews/Firmware.cs |   37 +-
 .../GCSViews/Firmware.resx                    |    2 +-
 .../GCSViews/FlightData.Designer.cs           |  108 +-
 .../GCSViews/FlightData.cs                    |    8 +-
 .../GCSViews/FlightData.resx                  |   64 +-
 .../GCSViews/FlightPlanner.Designer.cs        |   52 +-
 .../GCSViews/FlightPlanner.cs                 |    1 +
 .../GCSViews/FlightPlanner.resx               |   22 +-
 .../GCSViews/Help.Designer.cs                 |    4 +-
 Tools/ArdupilotMegaPlanner/GCSViews/Help.resx |    2 +-
 .../GCSViews/Simulation.Designer.cs           |  208 +-
 .../GCSViews/Simulation.cs                    |    2 +-
 .../GCSViews/Simulation.resx                  |  104 +-
 .../GCSViews/Terminal.Designer.cs             |   20 +-
 .../ArdupilotMegaPlanner/GCSViews/Terminal.cs |    2 +
 .../GCSViews/Terminal.resx                    |   10 +-
 .../JoystickSetup.Designer.cs                 |   40 +-
 Tools/ArdupilotMegaPlanner/JoystickSetup.cs   |   11 +-
 Tools/ArdupilotMegaPlanner/JoystickSetup.resx |   20 +-
 Tools/ArdupilotMegaPlanner/Log.Designer.cs    |   20 +-
 Tools/ArdupilotMegaPlanner/Log.cs             |    1 +
 Tools/ArdupilotMegaPlanner/Log.resx           |   10 +-
 .../LogBrowse.designer.cs                     |   12 +-
 Tools/ArdupilotMegaPlanner/LogBrowse.resx     |    6 +-
 Tools/ArdupilotMegaPlanner/MAVLink.cs         |   22 +-
 Tools/ArdupilotMegaPlanner/MainV2.cs          |   12 +-
 .../MavlinkLog.Designer.cs                    |   12 +-
 Tools/ArdupilotMegaPlanner/MavlinkLog.resx    |    6 +-
 Tools/ArdupilotMegaPlanner/Msi/wix.pdb        |  Bin 19968 -> 19968 bytes
 .../Properties/AssemblyInfo.cs                |    2 +-
 .../RAW_Sensor.Designer.cs                    |    4 +-
 Tools/ArdupilotMegaPlanner/RAW_Sensor.resx    |    2 +-
 .../Radio/3DRradio.Designer.cs                |   36 +-
 Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs  |   12 +-
 .../ArdupilotMegaPlanner/Radio/3DRradio.resx  |   18 +-
 .../SerialInput.Designer.cs                   |    4 +-
 .../SerialOutput.Designer.cs                  |    4 +-
 Tools/ArdupilotMegaPlanner/ThemeManager.cs    |    3 +-
 .../Updater/Updater.csproj                    |    4 +-
 .../arducopter/Models/_propeller0_.skb        |  Bin 43493 -> 0 bytes
 .../arducopter/Models/_propeller0_.skp        |  Bin 44219 -> 0 bytes
 Tools/ArdupilotMegaPlanner/georefimage.cs     |   20 +-
 .../paramcompare.Designer.cs                  |    4 +-
 Tools/ArdupilotMegaPlanner/temp.Designer.cs   |   68 +-
 Tools/ArdupilotMegaPlanner/temp.cs            |    1 +
 Tools/ArdupilotMegaPlanner/test.cs            |    1 -
 114 files changed, 3991 insertions(+), 4248 deletions(-)
 rename Tools/ArdupilotMegaPlanner/{ => Arduino}/ArduinoComms.cs (94%)
 rename Tools/ArdupilotMegaPlanner/{ => Arduino}/ArduinoDetect.cs (96%)
 rename Tools/ArdupilotMegaPlanner/{ => Arduino}/ArduinoSTK.cs (96%)
 rename Tools/ArdupilotMegaPlanner/{ => Arduino}/ArduinoSTKv2.cs (96%)
 rename Tools/ArdupilotMegaPlanner/{ => Comms}/CommsSerialInterface.cs (95%)
 rename Tools/ArdupilotMegaPlanner/{ => Comms}/CommsSerialPort.cs (96%)
 rename Tools/ArdupilotMegaPlanner/{ => Comms}/CommsTCPSerial.cs (94%)
 rename Tools/ArdupilotMegaPlanner/{ => Comms}/CommsUdpSerial.cs (95%)
 rename Tools/ArdupilotMegaPlanner/{ => Controls}/HUD.cs (97%)
 delete mode 100644 Tools/ArdupilotMegaPlanner/Controls/XorPlus.Designer.cs
 delete mode 100644 Tools/ArdupilotMegaPlanner/Controls/XorPlus.cs
 delete mode 100644 Tools/ArdupilotMegaPlanner/Controls/XorPlus.resx
 delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skb
 delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skp
 delete mode 100644 Tools/ArdupilotMegaPlanner/test.cs

diff --git a/Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs b/Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs
index 866532433..8b4fee911 100644
--- a/Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs
+++ b/Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs
@@ -7,7 +7,7 @@ namespace ArdupilotMega.Antenna
 {
     class ArduTracker : ITrackerOutput
     {
-        public SerialPort ComPort { get; set; }
+        public Comms.SerialPort ComPort { get; set; }
         /// <summary>
         ///  0-360
         /// </summary>
diff --git a/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs b/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs
index bee2aa98d..4791cae5f 100644
--- a/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs
+++ b/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs
@@ -7,7 +7,7 @@ namespace ArdupilotMega.Antenna
 {
     interface ITrackerOutput
     {
-        SerialPort ComPort { get; set; }
+        Comms.SerialPort ComPort { get; set; }
 
         double TrimPan { get; set; }
         double TrimTilt { get; set; }
diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs b/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs
index f77df0945..e7e52d304 100644
--- a/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs
+++ b/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs
@@ -7,7 +7,7 @@ namespace ArdupilotMega.Antenna
 {
     class Maestro : ITrackerOutput
     {
-        public SerialPort ComPort { get; set; }
+        public Comms.SerialPort ComPort { get; set; }
         /// <summary>
         ///  0-360
         /// </summary>
diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs
index 7ac7ab2cd..90eea7c06 100644
--- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs
@@ -52,7 +52,7 @@
             this.label10 = new System.Windows.Forms.Label();
             this.label11 = new System.Windows.Forms.Label();
             this.label12 = new System.Windows.Forms.Label();
-            this.BUT_connect = new ArdupilotMega.MyButton();
+            this.BUT_connect = new ArdupilotMega.Controls.MyButton();
             this.LBL_pantrim = new System.Windows.Forms.Label();
             this.LBL_tilttrim = new System.Windows.Forms.Label();
             ((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).BeginInit();
@@ -266,7 +266,7 @@
         private System.Windows.Forms.ComboBox CMB_interface;
         private System.Windows.Forms.Label label1;
         private System.Windows.Forms.ComboBox CMB_baudrate;
-        private MyButton BUT_connect;
+        private ArdupilotMega.Controls.MyButton BUT_connect;
         private System.Windows.Forms.ComboBox CMB_serialport;
         private System.Windows.Forms.TrackBar TRK_pantrim;
         private System.Windows.Forms.TextBox TXT_panrange;
diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
index 589f67111..d768645b7 100644
--- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
+++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
@@ -7,6 +7,7 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega.Controls.BackstageView;
+using ArdupilotMega.Comms;
 
 namespace ArdupilotMega.Antenna
 {
diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx
index ee9137adc..74e13663a 100644
--- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx
+++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx
@@ -750,7 +750,7 @@
     <value>BUT_connect</value>
   </data>
   <data name="&gt;&gt;BUT_connect.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_connect.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/ArduinoComms.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoComms.cs
similarity index 94%
rename from Tools/ArdupilotMegaPlanner/ArduinoComms.cs
rename to Tools/ArdupilotMegaPlanner/Arduino/ArduinoComms.cs
index a68552355..9647491a7 100644
--- a/Tools/ArdupilotMegaPlanner/ArduinoComms.cs
+++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoComms.cs
@@ -1,38 +1,38 @@
-using System;
-using System.Collections.Generic;
-using System.Text;
-using System.IO.Ports;
-using System.IO;
-
-namespace ArdupilotMega
-{
-    public delegate void ProgressEventHandler(int progress,string status);
-
-    /// <summary>
-    /// Arduino STK interface
-    /// </summary>
-    interface ArduinoComms
-    {
-         bool connectAP();
-         bool keepalive();
-         bool sync();
-         byte[] download(short length);
-         byte[] downloadflash(short length);
-         bool setaddress(int address);
-         bool upload(byte[] data, short startfrom, short length, short startaddress);
-         bool uploadflash(byte[] data, int startfrom, int length, int startaddress);
-
-         event ProgressEventHandler Progress;
-
-        // from serialport class
-         int BaudRate { get; set; }
-         bool DtrEnable { get; set; }
-         string PortName { get; set; }
-         StopBits StopBits { get; set; }
-         Parity Parity { get; set; }
-         bool IsOpen { get; }
-         void Open();
-         void Close();
-         int DataBits { get; set; }
-    }
-}
+using System;
+using System.Collections.Generic;
+using System.Text;
+using System.IO.Ports;
+using System.IO;
+
+namespace ArdupilotMega.Arduino
+{
+    public delegate void ProgressEventHandler(int progress,string status);
+
+    /// <summary>
+    /// Arduino STK interface
+    /// </summary>
+    interface ArduinoComms
+    {
+         bool connectAP();
+         bool keepalive();
+         bool sync();
+         byte[] download(short length);
+         byte[] downloadflash(short length);
+         bool setaddress(int address);
+         bool upload(byte[] data, short startfrom, short length, short startaddress);
+         bool uploadflash(byte[] data, int startfrom, int length, int startaddress);
+
+         event ProgressEventHandler Progress;
+
+        // from serialport class
+         int BaudRate { get; set; }
+         bool DtrEnable { get; set; }
+         string PortName { get; set; }
+         StopBits StopBits { get; set; }
+         Parity Parity { get; set; }
+         bool IsOpen { get; }
+         void Open();
+         void Close();
+         int DataBits { get; set; }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoDetect.cs
similarity index 96%
rename from Tools/ArdupilotMegaPlanner/ArduinoDetect.cs
rename to Tools/ArdupilotMegaPlanner/Arduino/ArduinoDetect.cs
index ffa350cb5..19c8bdea7 100644
--- a/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs
+++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoDetect.cs
@@ -1,460 +1,461 @@
-using System;
-using System.Reflection;
-using System.Management;
-using System.Windows.Forms;
-using System.Threading;
-using log4net;
-using System.Globalization;
-
-namespace ArdupilotMega
-{
-    class ArduinoDetect
-    {
-        private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
-        /// <summary>
-        /// detects STK version 1 or 2
-        /// </summary>
-        /// <param name="port">comportname</param>
-        /// <returns>string either (1280/2560) or "" for none</returns>
-        public static string DetectVersion(string port)
-        {
-            SerialPort serialPort = new SerialPort();
-            serialPort.PortName = port;
-
-            if (serialPort.IsOpen)
-                serialPort.Close();
-
-            serialPort.DtrEnable = true;
-            serialPort.BaudRate = 57600;
-            serialPort.Open();
-
-            Thread.Sleep(100);
-
-            int a = 0;
-            while (a < 20) // 20 * 50 = 1 sec
-            {
-                //Console.WriteLine("write " + DateTime.Now.Millisecond);
-                serialPort.DiscardInBuffer();
-                serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
-                a++;
-                Thread.Sleep(50);
-
-                //Console.WriteLine("btr {0}", serialPort.BytesToRead);
-                if (serialPort.BytesToRead >= 2)
-                {
-                    byte b1 = (byte)serialPort.ReadByte();
-                    byte b2 = (byte)serialPort.ReadByte();
-                    if (b1 == 0x14 && b2 == 0x10)
-                    {
-                        serialPort.Close();
-                        return "1280";
-                    }
-                }
-            }
-
-            serialPort.Close();
-
-            log.Warn("Not a 1280");
-
-            Thread.Sleep(500);
-
-            serialPort.DtrEnable = true;
-            serialPort.BaudRate = 115200;
-            serialPort.Open();
-
-            Thread.Sleep(100);
-
-            a = 0;
-            while (a < 4)
-            {
-                byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 };
-                temp = ArduinoDetect.genstkv2packet(serialPort, temp);
-                a++;
-                Thread.Sleep(50);
-
-                try
-                {
-                    if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
-                    {
-                        serialPort.Close();
-
-                        return "2560";
-
-                    }
-                }
-                catch
-                {
-                }
-            }
-
-            serialPort.Close();
-            log.Warn("Not a 2560");
-            return "";
-        }
-
-        /// <summary>
-        /// Detects APM board version
-        /// </summary>
-        /// <param name="port"></param>
-        /// <returns> (1280/2560/2560-2)</returns>
-        public static string DetectBoard(string port)
-        {
-            SerialPort serialPort = new SerialPort();
-            serialPort.PortName = port;
-
-            if (serialPort.IsOpen)
-                serialPort.Close();
-
-            serialPort.DtrEnable = true;
-            serialPort.BaudRate = 57600;
-            serialPort.Open();
-
-            Thread.Sleep(100);
-
-            int a = 0;
-            while (a < 20) // 20 * 50 = 1 sec
-            {
-                //Console.WriteLine("write " + DateTime.Now.Millisecond);
-                serialPort.DiscardInBuffer();
-                serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
-                a++;
-                Thread.Sleep(50);
-
-                //Console.WriteLine("btr {0}", serialPort.BytesToRead);
-                if (serialPort.BytesToRead >= 2)
-                {
-                    byte b1 = (byte)serialPort.ReadByte();
-                    byte b2 = (byte)serialPort.ReadByte();
-                    if (b1 == 0x14 && b2 == 0x10)
-                    {
-                        serialPort.Close();
-                        return "1280";
-                    }
-                }
-            }
-
-            serialPort.Close();
-
-            log.Warn("Not a 1280");
-
-            Thread.Sleep(500);
-
-            serialPort.DtrEnable = true;
-            serialPort.BaudRate = 115200;
-            serialPort.Open();
-
-            Thread.Sleep(100);
-
-            a = 0;
-            while (a < 4)
-            {
-                byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 };
-                temp = ArduinoDetect.genstkv2packet(serialPort, temp);
-                a++;
-                Thread.Sleep(50);
-
-                try
-                {
-                    if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
-                    {
-                        serialPort.Close();
-                        //HKEY_LOCAL_MACHINE\SYSTEM\CurrentControlSet\Enum\USB\VID_2341&PID_0010\640333439373519060F0\Device Parameters
-                        if (!MainV2.MONO && !Thread.CurrentThread.CurrentUICulture.IsChildOf(CultureInfoEx.GetCultureInfo("zh-Hans")))
-                        {
-                            ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_USBControllerDevice");
-                            ManagementObjectSearcher searcher = new ManagementObjectSearcher(query);
-                            foreach (ManagementObject obj2 in searcher.Get())
-                            {
-                                //Console.WriteLine("Dependant : " + obj2["Dependent"]);
-
-                                // all apm 1-1.4 use a ftdi on the imu board.
-
-                                if (obj2["Dependent"].ToString().Contains(@"USB\\VID_2341&PID_0010"))
-                                {
-                                        return "2560-2";
-                                }
-                            }
-
-                            return "2560";
-                        }
-                        else
-                        {
-                            if (DialogResult.Yes == CustomMessageBox.Show("Is this a APM 2?", "APM 2", MessageBoxButtons.YesNo))
-                            {
-                                return "2560-2";
-                            }
-                            else
-                            {
-                                return "2560";
-                            }
-                        }
-
-                    }
-                }
-                catch { }
-            }
-
-            serialPort.Close();
-            log.Warn("Not a 2560");
-            return "";
-        }
-
-        public enum ap_var_type
-        {
-            AP_PARAM_NONE = 0,
-            AP_PARAM_INT8,
-            AP_PARAM_INT16,
-            AP_PARAM_INT32,
-            AP_PARAM_FLOAT,
-            AP_PARAM_VECTOR3F,
-            AP_PARAM_VECTOR6F,
-            AP_PARAM_MATRIX3F,
-            AP_PARAM_GROUP
-        };
-
-        static string[] type_names = new string[] {
-	"NONE", "INT8", "INT16", "INT32", "FLOAT", "VECTOR3F", "VECTOR6F","MATRIX6F", "GROUP"
-};
-
-       static byte type_size(ap_var_type type)
-{
-    switch (type) {
-    case ap_var_type.AP_PARAM_NONE:
-    case ap_var_type.AP_PARAM_GROUP:
-        return 0;
-    case ap_var_type.AP_PARAM_INT8:
-        return 1;
-    case ap_var_type.AP_PARAM_INT16:
-        return 2;
-    case ap_var_type.AP_PARAM_INT32:
-        return 4;
-    case ap_var_type.AP_PARAM_FLOAT:
-        return 4;
-    case ap_var_type.AP_PARAM_VECTOR3F:
-        return 3*4;
-    case ap_var_type.AP_PARAM_VECTOR6F:
-        return 6*4;
-    case ap_var_type.AP_PARAM_MATRIX3F:
-        return 3*3*4;
-    }
-    return 0;
-}
-
-        /// <summary>
-        /// return the software id from eeprom
-        /// </summary>
-        /// <param name="comport">Port</param>
-        /// <param name="version">Board type</param>
-        /// <returns></returns>
-        public static int decodeApVar(string comport, string version)
-        {
-            ArduinoComms port = new ArduinoSTK();
-            if (version == "1280")
-            {
-                port = new ArduinoSTK();
-                port.BaudRate = 57600;
-            }
-            else if (version == "2560" || version == "2560-2")
-            {
-                port = new ArduinoSTKv2();
-                port.BaudRate = 115200;
-            }
-            else { return -1; }
-            port.PortName = comport;
-            port.DtrEnable = true;
-            port.Open();
-            port.connectAP();
-            byte[] buffer = port.download(1024 * 4);
-            port.Close();
-
-            if (buffer[0] != 'A' && buffer[0] != 'P' || buffer[1] != 'P' && buffer[1] != 'A') // this is the apvar header
-            {
-                return -1;
-            }
-            else
-            {
-                if (buffer[0] == 'A' && buffer[1] == 'P' && buffer[2] == 2)
-                { // apvar header and version
-                    int pos = 4;
-                    byte key = 0;
-                    while (pos < (1024 * 4))
-                    {
-                        int size = buffer[pos] & 63;
-                        pos++;
-                        key = buffer[pos];
-                        pos++;
-
-                        log.InfoFormat("{0:X4}: key {1} size {2}\n ", pos - 2, key, size + 1);
-
-                        if (key == 0xff)
-                        {
-                            log.InfoFormat("end sentinal at {0}", pos - 2);
-                            break;
-                        }
-
-                        if (key == 0)
-                        {
-                            //Array.Reverse(buffer, pos, 2);
-                            return BitConverter.ToUInt16(buffer, pos);
-                        }
-
-
-                        for (int i = 0; i <= size; i++)
-                        {
-                            Console.Write(" {0:X2}", buffer[pos]);
-                            pos++;
-                        }
-                    }
-                }
-
-                if (buffer[0] == 'P' && buffer[1] == 'A' && buffer[2] == 5) // ap param
-                {
-                    int pos = 4;
-                    byte key = 0;
-                    while (pos < (1024 * 4))
-                    {
-                        key = buffer[pos];
-                        pos++;
-                        int group = buffer[pos];
-                        pos++;
-                        int type = buffer[pos];
-                        pos++;
-
-                        int size = type_size((ap_var_type)Enum.Parse(typeof(ap_var_type), type.ToString()));
-
-
-                        Console.Write("{0:X4}: type {1} ({2}) key {3} group {4} size {5}\n ", pos - 2, type, type_names[type], key, group, size);
-
-                        if (key == 0xff)
-                        {
-                            log.InfoFormat("end sentinal at {0}", pos - 2);
-                            break;
-                        }
-
-                        if (key == 0)
-                        {
-                            //Array.Reverse(buffer, pos, 2);
-                            return BitConverter.ToUInt16(buffer, pos);
-                        }
-
-
-                        for (int i = 0; i < size; i++)
-                        {
-                            Console.Write(" {0:X2}", buffer[pos]);
-                            pos++;
-                        }
-                    }
-                }
-            }
-            return -1;
-        }
-
-        /// <summary>
-        /// STK v2 generate packet
-        /// </summary>
-        /// <param name="serialPort"></param>
-        /// <param name="message"></param>
-        /// <returns></returns>
-        static byte[] genstkv2packet(SerialPort serialPort, byte[] message)
-        {
-            byte[] data = new byte[300];
-            byte ck = 0;
-
-            data[0] = 0x1b;
-            ck ^= data[0];
-            data[1] = 0x1;
-            ck ^= data[1];
-            data[2] = (byte)((message.Length >> 8) & 0xff);
-            ck ^= data[2];
-            data[3] = (byte)(message.Length & 0xff);
-            ck ^= data[3];
-            data[4] = 0xe;
-            ck ^= data[4];
-
-            int a = 5;
-            foreach (byte let in message)
-            {
-                data[a] = let;
-                ck ^= let;
-                a++;
-            }
-            data[a] = ck;
-            a++;
-
-            serialPort.Write(data, 0, a);
-            //Console.WriteLine("about to read packet");
-
-            byte[] ret = ArduinoDetect.readpacket(serialPort);
-
-            //if (ret[1] == 0x0)
-            {
-                //Console.WriteLine("received OK");
-            }
-
-            return ret;
-        }
-
-        /// <summary>
-        /// 
-        /// </summary>
-        /// <param name="serialPort"></param>
-        /// <returns></returns>
-        static byte[] readpacket(SerialPort serialPort)
-        {
-            byte[] temp = new byte[4000];
-            byte[] mes = new byte[2] { 0x0, 0xC0 }; // fail
-            int a = 7;
-            int count = 0;
-
-            serialPort.ReadTimeout = 1000;
-
-            while (count < a)
-            {
-                //Console.WriteLine("count {0} a {1} mes leng {2}",count,a,mes.Length);
-                try
-                {
-                    temp[count] = (byte)serialPort.ReadByte();
-                }
-                catch { break; }
-
-
-                //Console.Write("{1}", temp[0], (char)temp[0]);
-
-                if (temp[0] != 0x1b)
-                {
-                    count = 0;
-                    continue;
-                }
-
-                if (count == 3)
-                {
-                    a = (temp[2] << 8) + temp[3];
-                    mes = new byte[a];
-                    a += 5;
-                }
-
-                if (count >= 5)
-                {
-                    mes[count - 5] = temp[count];
-                }
-
-                count++;
-            }
-
-            //Console.WriteLine("read ck");
-            try
-            {
-                temp[count] = (byte)serialPort.ReadByte();
-            }
-            catch { }
-
-            count++;
-
-            Array.Resize<byte>(ref temp, count);
-
-            //Console.WriteLine(this.BytesToRead);
-
-            return mes;
-        }
-    }
+using System;
+using System.Reflection;
+using System.Management;
+using System.Windows.Forms;
+using System.Threading;
+using log4net;
+using System.Globalization;
+using ArdupilotMega.Comms;
+
+namespace ArdupilotMega.Arduino
+{
+    class ArduinoDetect
+    {
+        private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
+        /// <summary>
+        /// detects STK version 1 or 2
+        /// </summary>
+        /// <param name="port">comportname</param>
+        /// <returns>string either (1280/2560) or "" for none</returns>
+        public static string DetectVersion(string port)
+        {
+            SerialPort serialPort = new SerialPort();
+            serialPort.PortName = port;
+
+            if (serialPort.IsOpen)
+                serialPort.Close();
+
+            serialPort.DtrEnable = true;
+            serialPort.BaudRate = 57600;
+            serialPort.Open();
+
+            Thread.Sleep(100);
+
+            int a = 0;
+            while (a < 20) // 20 * 50 = 1 sec
+            {
+                //Console.WriteLine("write " + DateTime.Now.Millisecond);
+                serialPort.DiscardInBuffer();
+                serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
+                a++;
+                Thread.Sleep(50);
+
+                //Console.WriteLine("btr {0}", serialPort.BytesToRead);
+                if (serialPort.BytesToRead >= 2)
+                {
+                    byte b1 = (byte)serialPort.ReadByte();
+                    byte b2 = (byte)serialPort.ReadByte();
+                    if (b1 == 0x14 && b2 == 0x10)
+                    {
+                        serialPort.Close();
+                        return "1280";
+                    }
+                }
+            }
+
+            serialPort.Close();
+
+            log.Warn("Not a 1280");
+
+            Thread.Sleep(500);
+
+            serialPort.DtrEnable = true;
+            serialPort.BaudRate = 115200;
+            serialPort.Open();
+
+            Thread.Sleep(100);
+
+            a = 0;
+            while (a < 4)
+            {
+                byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 };
+                temp = ArduinoDetect.genstkv2packet(serialPort, temp);
+                a++;
+                Thread.Sleep(50);
+
+                try
+                {
+                    if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
+                    {
+                        serialPort.Close();
+
+                        return "2560";
+
+                    }
+                }
+                catch
+                {
+                }
+            }
+
+            serialPort.Close();
+            log.Warn("Not a 2560");
+            return "";
+        }
+
+        /// <summary>
+        /// Detects APM board version
+        /// </summary>
+        /// <param name="port"></param>
+        /// <returns> (1280/2560/2560-2)</returns>
+        public static string DetectBoard(string port)
+        {
+            SerialPort serialPort = new SerialPort();
+            serialPort.PortName = port;
+
+            if (serialPort.IsOpen)
+                serialPort.Close();
+
+            serialPort.DtrEnable = true;
+            serialPort.BaudRate = 57600;
+            serialPort.Open();
+
+            Thread.Sleep(100);
+
+            int a = 0;
+            while (a < 20) // 20 * 50 = 1 sec
+            {
+                //Console.WriteLine("write " + DateTime.Now.Millisecond);
+                serialPort.DiscardInBuffer();
+                serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
+                a++;
+                Thread.Sleep(50);
+
+                //Console.WriteLine("btr {0}", serialPort.BytesToRead);
+                if (serialPort.BytesToRead >= 2)
+                {
+                    byte b1 = (byte)serialPort.ReadByte();
+                    byte b2 = (byte)serialPort.ReadByte();
+                    if (b1 == 0x14 && b2 == 0x10)
+                    {
+                        serialPort.Close();
+                        return "1280";
+                    }
+                }
+            }
+
+            serialPort.Close();
+
+            log.Warn("Not a 1280");
+
+            Thread.Sleep(500);
+
+            serialPort.DtrEnable = true;
+            serialPort.BaudRate = 115200;
+            serialPort.Open();
+
+            Thread.Sleep(100);
+
+            a = 0;
+            while (a < 4)
+            {
+                byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 };
+                temp = ArduinoDetect.genstkv2packet(serialPort, temp);
+                a++;
+                Thread.Sleep(50);
+
+                try
+                {
+                    if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
+                    {
+                        serialPort.Close();
+                        //HKEY_LOCAL_MACHINE\SYSTEM\CurrentControlSet\Enum\USB\VID_2341&PID_0010\640333439373519060F0\Device Parameters
+                        if (!MainV2.MONO && !Thread.CurrentThread.CurrentUICulture.IsChildOf(CultureInfoEx.GetCultureInfo("zh-Hans")))
+                        {
+                            ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_USBControllerDevice");
+                            ManagementObjectSearcher searcher = new ManagementObjectSearcher(query);
+                            foreach (ManagementObject obj2 in searcher.Get())
+                            {
+                                //Console.WriteLine("Dependant : " + obj2["Dependent"]);
+
+                                // all apm 1-1.4 use a ftdi on the imu board.
+
+                                if (obj2["Dependent"].ToString().Contains(@"USB\\VID_2341&PID_0010"))
+                                {
+                                        return "2560-2";
+                                }
+                            }
+
+                            return "2560";
+                        }
+                        else
+                        {
+                            if (DialogResult.Yes == CustomMessageBox.Show("Is this a APM 2?", "APM 2", MessageBoxButtons.YesNo))
+                            {
+                                return "2560-2";
+                            }
+                            else
+                            {
+                                return "2560";
+                            }
+                        }
+
+                    }
+                }
+                catch { }
+            }
+
+            serialPort.Close();
+            log.Warn("Not a 2560");
+            return "";
+        }
+
+        public enum ap_var_type
+        {
+            AP_PARAM_NONE = 0,
+            AP_PARAM_INT8,
+            AP_PARAM_INT16,
+            AP_PARAM_INT32,
+            AP_PARAM_FLOAT,
+            AP_PARAM_VECTOR3F,
+            AP_PARAM_VECTOR6F,
+            AP_PARAM_MATRIX3F,
+            AP_PARAM_GROUP
+        };
+
+        static string[] type_names = new string[] {
+	"NONE", "INT8", "INT16", "INT32", "FLOAT", "VECTOR3F", "VECTOR6F","MATRIX6F", "GROUP"
+};
+
+       static byte type_size(ap_var_type type)
+{
+    switch (type) {
+    case ap_var_type.AP_PARAM_NONE:
+    case ap_var_type.AP_PARAM_GROUP:
+        return 0;
+    case ap_var_type.AP_PARAM_INT8:
+        return 1;
+    case ap_var_type.AP_PARAM_INT16:
+        return 2;
+    case ap_var_type.AP_PARAM_INT32:
+        return 4;
+    case ap_var_type.AP_PARAM_FLOAT:
+        return 4;
+    case ap_var_type.AP_PARAM_VECTOR3F:
+        return 3*4;
+    case ap_var_type.AP_PARAM_VECTOR6F:
+        return 6*4;
+    case ap_var_type.AP_PARAM_MATRIX3F:
+        return 3*3*4;
+    }
+    return 0;
+}
+
+        /// <summary>
+        /// return the software id from eeprom
+        /// </summary>
+        /// <param name="comport">Port</param>
+        /// <param name="version">Board type</param>
+        /// <returns></returns>
+        public static int decodeApVar(string comport, string version)
+        {
+            ArduinoComms port = new ArduinoSTK();
+            if (version == "1280")
+            {
+                port = new ArduinoSTK();
+                port.BaudRate = 57600;
+            }
+            else if (version == "2560" || version == "2560-2")
+            {
+                port = new ArduinoSTKv2();
+                port.BaudRate = 115200;
+            }
+            else { return -1; }
+            port.PortName = comport;
+            port.DtrEnable = true;
+            port.Open();
+            port.connectAP();
+            byte[] buffer = port.download(1024 * 4);
+            port.Close();
+
+            if (buffer[0] != 'A' && buffer[0] != 'P' || buffer[1] != 'P' && buffer[1] != 'A') // this is the apvar header
+            {
+                return -1;
+            }
+            else
+            {
+                if (buffer[0] == 'A' && buffer[1] == 'P' && buffer[2] == 2)
+                { // apvar header and version
+                    int pos = 4;
+                    byte key = 0;
+                    while (pos < (1024 * 4))
+                    {
+                        int size = buffer[pos] & 63;
+                        pos++;
+                        key = buffer[pos];
+                        pos++;
+
+                        log.InfoFormat("{0:X4}: key {1} size {2}\n ", pos - 2, key, size + 1);
+
+                        if (key == 0xff)
+                        {
+                            log.InfoFormat("end sentinal at {0}", pos - 2);
+                            break;
+                        }
+
+                        if (key == 0)
+                        {
+                            //Array.Reverse(buffer, pos, 2);
+                            return BitConverter.ToUInt16(buffer, pos);
+                        }
+
+
+                        for (int i = 0; i <= size; i++)
+                        {
+                            Console.Write(" {0:X2}", buffer[pos]);
+                            pos++;
+                        }
+                    }
+                }
+
+                if (buffer[0] == 'P' && buffer[1] == 'A' && buffer[2] == 5) // ap param
+                {
+                    int pos = 4;
+                    byte key = 0;
+                    while (pos < (1024 * 4))
+                    {
+                        key = buffer[pos];
+                        pos++;
+                        int group = buffer[pos];
+                        pos++;
+                        int type = buffer[pos];
+                        pos++;
+
+                        int size = type_size((ap_var_type)Enum.Parse(typeof(ap_var_type), type.ToString()));
+
+
+                        Console.Write("{0:X4}: type {1} ({2}) key {3} group {4} size {5}\n ", pos - 2, type, type_names[type], key, group, size);
+
+                        if (key == 0xff)
+                        {
+                            log.InfoFormat("end sentinal at {0}", pos - 2);
+                            break;
+                        }
+
+                        if (key == 0)
+                        {
+                            //Array.Reverse(buffer, pos, 2);
+                            return BitConverter.ToUInt16(buffer, pos);
+                        }
+
+
+                        for (int i = 0; i < size; i++)
+                        {
+                            Console.Write(" {0:X2}", buffer[pos]);
+                            pos++;
+                        }
+                    }
+                }
+            }
+            return -1;
+        }
+
+        /// <summary>
+        /// STK v2 generate packet
+        /// </summary>
+        /// <param name="serialPort"></param>
+        /// <param name="message"></param>
+        /// <returns></returns>
+        static byte[] genstkv2packet(SerialPort serialPort, byte[] message)
+        {
+            byte[] data = new byte[300];
+            byte ck = 0;
+
+            data[0] = 0x1b;
+            ck ^= data[0];
+            data[1] = 0x1;
+            ck ^= data[1];
+            data[2] = (byte)((message.Length >> 8) & 0xff);
+            ck ^= data[2];
+            data[3] = (byte)(message.Length & 0xff);
+            ck ^= data[3];
+            data[4] = 0xe;
+            ck ^= data[4];
+
+            int a = 5;
+            foreach (byte let in message)
+            {
+                data[a] = let;
+                ck ^= let;
+                a++;
+            }
+            data[a] = ck;
+            a++;
+
+            serialPort.Write(data, 0, a);
+            //Console.WriteLine("about to read packet");
+
+            byte[] ret = ArduinoDetect.readpacket(serialPort);
+
+            //if (ret[1] == 0x0)
+            {
+                //Console.WriteLine("received OK");
+            }
+
+            return ret;
+        }
+
+        /// <summary>
+        /// 
+        /// </summary>
+        /// <param name="serialPort"></param>
+        /// <returns></returns>
+        static byte[] readpacket(SerialPort serialPort)
+        {
+            byte[] temp = new byte[4000];
+            byte[] mes = new byte[2] { 0x0, 0xC0 }; // fail
+            int a = 7;
+            int count = 0;
+
+            serialPort.ReadTimeout = 1000;
+
+            while (count < a)
+            {
+                //Console.WriteLine("count {0} a {1} mes leng {2}",count,a,mes.Length);
+                try
+                {
+                    temp[count] = (byte)serialPort.ReadByte();
+                }
+                catch { break; }
+
+
+                //Console.Write("{1}", temp[0], (char)temp[0]);
+
+                if (temp[0] != 0x1b)
+                {
+                    count = 0;
+                    continue;
+                }
+
+                if (count == 3)
+                {
+                    a = (temp[2] << 8) + temp[3];
+                    mes = new byte[a];
+                    a += 5;
+                }
+
+                if (count >= 5)
+                {
+                    mes[count - 5] = temp[count];
+                }
+
+                count++;
+            }
+
+            //Console.WriteLine("read ck");
+            try
+            {
+                temp[count] = (byte)serialPort.ReadByte();
+            }
+            catch { }
+
+            count++;
+
+            Array.Resize<byte>(ref temp, count);
+
+            //Console.WriteLine(this.BytesToRead);
+
+            return mes;
+        }
+    }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/ArduinoSTK.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs
similarity index 96%
rename from Tools/ArdupilotMegaPlanner/ArduinoSTK.cs
rename to Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs
index 372cf568c..3a3a825e6 100644
--- a/Tools/ArdupilotMegaPlanner/ArduinoSTK.cs
+++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs
@@ -1,335 +1,336 @@
-using System;
-using System.Collections.Generic;
-using System.Reflection;
-using System.Text;
-using System.IO.Ports;
-using System.Threading;
-using log4net;
-
-// Written by Michael Oborne
-
-namespace ArdupilotMega
-{
-    class ArduinoSTK : SerialPort, ArduinoComms
-    {
-        private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
-        public event ProgressEventHandler Progress;
-
-        public new void Open()
-        {
-            // default dtr status is false
-
-            //from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup
-            base.Open();
-
-            base.DtrEnable = false;
-            base.RtsEnable = false;
-
-            System.Threading.Thread.Sleep(50);
-
-            base.DtrEnable = true;
-            base.RtsEnable = true;
-
-            System.Threading.Thread.Sleep(50);
-        }
-
-        /// <summary>
-        /// Used to start initial connecting after serialport.open
-        /// </summary>
-        /// <returns>true = passed, false = failed</returns>
-        public bool connectAP()
-        {
-            if (!this.IsOpen)
-            {
-                return false;
-            }
-            int a = 0;
-            while (a < 50)
-            {
-                this.DiscardInBuffer();
-                this.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
-                a++;
-                Thread.Sleep(50);
-
-                log.InfoFormat("btr {0}", this.BytesToRead);
-                if (this.BytesToRead >= 2)
-                {
-                    byte b1 = (byte)this.ReadByte();
-                    byte b2 = (byte)this.ReadByte();
-                    if (b1 == 0x14 && b2 == 0x10)
-                    {
-                        return true;
-                    }
-                }
-            }
-            return false;
-        }
-
-        /// <summary>
-        /// Used to keep alive the connection
-        /// </summary>
-        /// <returns>true = passed, false = lost connection</returns>
-        public bool keepalive()
-        {
-            return connectAP();
-        }
-        /// <summary>
-        /// Syncs after a private command has been sent
-        /// </summary>
-        /// <returns>true = passed, false = failed</returns>
-        public bool sync()
-        {
-            if (!this.IsOpen)
-            {
-                return false;
-            }
-            this.ReadTimeout = 1000;
-            int f = 0;
-            while (this.BytesToRead < 1)
-            {
-                f++;
-                System.Threading.Thread.Sleep(1);
-                if (f > 1000)
-                    return false;
-            }
-            int a = 0;
-            while (a < 10)
-            {
-                if (this.BytesToRead >= 2)
-                {
-                    byte b1 = (byte)this.ReadByte();
-                    byte b2 = (byte)this.ReadByte();
-                    log.DebugFormat("bytes {0:X} {1:X}", b1, b2);
-
-                    if (b1 == 0x14 && b2 == 0x10)
-                    {
-                        return true;
-                    }
-                }
-                log.DebugFormat("btr {0}", this.BytesToRead);
-                Thread.Sleep(10);
-                a++;
-            }
-            return false;
-        }
-        /// <summary>
-        /// Downloads the eeprom with the given length - set Address first
-        /// </summary>
-        /// <param name="length">eeprom length</param>
-        /// <returns>downloaded data</returns>
-        public byte[] download(short length)
-        {
-            if (!this.IsOpen)
-            {
-                throw new Exception();
-            }
-            byte[] data = new byte[length];
-
-            byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'E', (byte)' ' };
-            this.Write(command, 0, command.Length);
-
-            if (this.ReadByte() == 0x14)
-            { // 0x14
-
-                int step = 0;
-                while (step < length)
-                {
-                    byte chr = (byte)this.ReadByte();
-                    data[step] = chr;
-                    step++;
-                }
-
-                if (this.ReadByte() != 0x10)  // 0x10
-                    throw new Exception("Lost Sync 0x10");
-            }
-            else
-            {
-                throw new Exception("Lost Sync 0x14");
-            }
-            return data;
-        }
-
-        public byte[] downloadflash(short length)
-        {
-            if (!this.IsOpen)
-            {
-                throw new Exception("Port Not Open");
-            }
-            byte[] data = new byte[length];
-
-            this.ReadTimeout = 1000;
-
-            byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'F', (byte)' ' };
-            this.Write(command, 0, command.Length);
-
-            if (this.ReadByte() == 0x14)
-            { // 0x14
-
-                int read = length;
-                while (read > 0)
-                {
-                    //Console.WriteLine("offset {0} read {1}", length - read, read);
-                    read -= this.Read(data, length - read, read);
-                    //System.Threading.Thread.Sleep(1);
-                }
-
-                if (this.ReadByte() != 0x10)  // 0x10
-                    throw new Exception("Lost Sync 0x10");
-            }
-            else
-            {
-                throw new Exception("Lost Sync 0x14");
-            }
-            return data;
-        }
-
-        public bool uploadflash(byte[] data, int startfrom, int length, int startaddress)
-        {
-            if (!this.IsOpen)
-            {
-                return false;
-            }
-            int loops = (length / 0x100);
-            int totalleft = length;
-            int sending = 0;
-
-            for (int a = 0; a <= loops; a++)
-            {
-                if (totalleft > 0x100)
-                {
-                    sending = 0x100;
-                }
-                else
-                {
-                    sending = totalleft;
-                }
-
-                //startaddress = 256;
-                if (sending == 0)
-                    return true;
-
-                setaddress(startaddress);
-                startaddress += sending;
-
-                byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'F' };
-                this.Write(command, 0, command.Length);
-                log.Info((startfrom + (length - totalleft)) + " - " + sending);
-                this.Write(data, startfrom + (length - totalleft), sending);
-                command = new byte[] { (byte)' ' };
-                this.Write(command, 0, command.Length);
-
-                totalleft -= sending;
-
-
-                if (Progress != null)
-                    Progress((int)(((float)startaddress / (float)length) * 100),"");
-
-                if (!sync())
-                {
-                    log.Info("No Sync");
-                    return false;
-                }
-            }
-            return true;
-        }
-
-        /// <summary>
-        /// Sets the eeprom start read or write address
-        /// </summary>
-        /// <param name="address">address, must be eaven number</param>
-        /// <returns>true = passed, false = failed</returns>
-        public bool setaddress(int address)
-        {
-            if (!this.IsOpen)
-            {
-                return false;
-            }
-
-            if (address % 2 == 1)
-            {
-                throw new Exception("Address must be an even number");
-            }
-
-            log.Info("Sending address   " + ((ushort)(address / 2)));
-
-            address /= 2;
-            address = (ushort)address;
-
-            byte[] command = new byte[] { (byte)'U', (byte)(address & 0xff), (byte)(address >> 8), (byte)' ' };
-            this.Write(command, 0, command.Length);
-
-            return sync();
-        }
-
-        /// <summary>
-        /// Upload data at preset address
-        /// </summary>
-        /// <param name="data">array to read from</param>
-        /// <param name="startfrom">start array index</param>
-        /// <param name="length">length to send</param>
-        /// <param name="startaddress">sets eeprom start programing address</param>
-        /// <returns>true = passed, false = failed</returns>
-        public bool upload(byte[] data, short startfrom, short length, short startaddress)
-        {
-            if (!this.IsOpen)
-            {
-                return false;
-            }
-            int loops = (length / 0x100);
-            int totalleft = length;
-            int sending = 0;
-
-            for (int a = 0; a <= loops; a++)
-            {
-                if (totalleft > 0x100)
-                {
-                    sending = 0x100;
-                }
-                else
-                {
-                    sending = totalleft;
-                }
-
-                if (sending == 0)
-                    return true;
-
-                setaddress(startaddress);
-                startaddress += (short)sending;
-
-                byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'E' };
-                this.Write(command, 0, command.Length);
-                log.Info((startfrom + (length - totalleft)) + " - " + sending);
-                this.Write(data, startfrom + (length - totalleft), sending);
-                command = new byte[] { (byte)' ' };
-                this.Write(command, 0, command.Length);
-
-                totalleft -= sending;
-
-                if (!sync())
-                {
-                    log.Info("No Sync");
-                    return false;
-                }
-            }
-            return true;
-        }
-
-        public new bool Close()
-        {
-            try
-            {
-
-                byte[] command = new byte[] { (byte)'Q', (byte)' ' };
-                this.Write(command, 0, command.Length);
-            }
-            catch { }
-
-            if (base.IsOpen)
-                base.Close();
-
-            this.DtrEnable = false;
-            this.RtsEnable = false;
-            return true;
-        }
-    }
+using System;
+using System.Collections.Generic;
+using System.Reflection;
+using System.Text;
+using System.Threading;
+using log4net;
+using ArdupilotMega.Comms;
+
+
+// Written by Michael Oborne
+
+namespace ArdupilotMega.Arduino
+{
+    class ArduinoSTK : SerialPort, ArduinoComms
+    {
+        private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
+        public event ProgressEventHandler Progress;
+
+        public new void Open()
+        {
+            // default dtr status is false
+
+            //from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup
+            base.Open();
+
+            base.DtrEnable = false;
+            base.RtsEnable = false;
+
+            System.Threading.Thread.Sleep(50);
+
+            base.DtrEnable = true;
+            base.RtsEnable = true;
+
+            System.Threading.Thread.Sleep(50);
+        }
+
+        /// <summary>
+        /// Used to start initial connecting after serialport.open
+        /// </summary>
+        /// <returns>true = passed, false = failed</returns>
+        public bool connectAP()
+        {
+            if (!this.IsOpen)
+            {
+                return false;
+            }
+            int a = 0;
+            while (a < 50)
+            {
+                this.DiscardInBuffer();
+                this.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
+                a++;
+                Thread.Sleep(50);
+
+                log.InfoFormat("btr {0}", this.BytesToRead);
+                if (this.BytesToRead >= 2)
+                {
+                    byte b1 = (byte)this.ReadByte();
+                    byte b2 = (byte)this.ReadByte();
+                    if (b1 == 0x14 && b2 == 0x10)
+                    {
+                        return true;
+                    }
+                }
+            }
+            return false;
+        }
+
+        /// <summary>
+        /// Used to keep alive the connection
+        /// </summary>
+        /// <returns>true = passed, false = lost connection</returns>
+        public bool keepalive()
+        {
+            return connectAP();
+        }
+        /// <summary>
+        /// Syncs after a private command has been sent
+        /// </summary>
+        /// <returns>true = passed, false = failed</returns>
+        public bool sync()
+        {
+            if (!this.IsOpen)
+            {
+                return false;
+            }
+            this.ReadTimeout = 1000;
+            int f = 0;
+            while (this.BytesToRead < 1)
+            {
+                f++;
+                System.Threading.Thread.Sleep(1);
+                if (f > 1000)
+                    return false;
+            }
+            int a = 0;
+            while (a < 10)
+            {
+                if (this.BytesToRead >= 2)
+                {
+                    byte b1 = (byte)this.ReadByte();
+                    byte b2 = (byte)this.ReadByte();
+                    log.DebugFormat("bytes {0:X} {1:X}", b1, b2);
+
+                    if (b1 == 0x14 && b2 == 0x10)
+                    {
+                        return true;
+                    }
+                }
+                log.DebugFormat("btr {0}", this.BytesToRead);
+                Thread.Sleep(10);
+                a++;
+            }
+            return false;
+        }
+        /// <summary>
+        /// Downloads the eeprom with the given length - set Address first
+        /// </summary>
+        /// <param name="length">eeprom length</param>
+        /// <returns>downloaded data</returns>
+        public byte[] download(short length)
+        {
+            if (!this.IsOpen)
+            {
+                throw new Exception();
+            }
+            byte[] data = new byte[length];
+
+            byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'E', (byte)' ' };
+            this.Write(command, 0, command.Length);
+
+            if (this.ReadByte() == 0x14)
+            { // 0x14
+
+                int step = 0;
+                while (step < length)
+                {
+                    byte chr = (byte)this.ReadByte();
+                    data[step] = chr;
+                    step++;
+                }
+
+                if (this.ReadByte() != 0x10)  // 0x10
+                    throw new Exception("Lost Sync 0x10");
+            }
+            else
+            {
+                throw new Exception("Lost Sync 0x14");
+            }
+            return data;
+        }
+
+        public byte[] downloadflash(short length)
+        {
+            if (!this.IsOpen)
+            {
+                throw new Exception("Port Not Open");
+            }
+            byte[] data = new byte[length];
+
+            this.ReadTimeout = 1000;
+
+            byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'F', (byte)' ' };
+            this.Write(command, 0, command.Length);
+
+            if (this.ReadByte() == 0x14)
+            { // 0x14
+
+                int read = length;
+                while (read > 0)
+                {
+                    //Console.WriteLine("offset {0} read {1}", length - read, read);
+                    read -= this.Read(data, length - read, read);
+                    //System.Threading.Thread.Sleep(1);
+                }
+
+                if (this.ReadByte() != 0x10)  // 0x10
+                    throw new Exception("Lost Sync 0x10");
+            }
+            else
+            {
+                throw new Exception("Lost Sync 0x14");
+            }
+            return data;
+        }
+
+        public bool uploadflash(byte[] data, int startfrom, int length, int startaddress)
+        {
+            if (!this.IsOpen)
+            {
+                return false;
+            }
+            int loops = (length / 0x100);
+            int totalleft = length;
+            int sending = 0;
+
+            for (int a = 0; a <= loops; a++)
+            {
+                if (totalleft > 0x100)
+                {
+                    sending = 0x100;
+                }
+                else
+                {
+                    sending = totalleft;
+                }
+
+                //startaddress = 256;
+                if (sending == 0)
+                    return true;
+
+                setaddress(startaddress);
+                startaddress += sending;
+
+                byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'F' };
+                this.Write(command, 0, command.Length);
+                log.Info((startfrom + (length - totalleft)) + " - " + sending);
+                this.Write(data, startfrom + (length - totalleft), sending);
+                command = new byte[] { (byte)' ' };
+                this.Write(command, 0, command.Length);
+
+                totalleft -= sending;
+
+
+                if (Progress != null)
+                    Progress((int)(((float)startaddress / (float)length) * 100),"");
+
+                if (!sync())
+                {
+                    log.Info("No Sync");
+                    return false;
+                }
+            }
+            return true;
+        }
+
+        /// <summary>
+        /// Sets the eeprom start read or write address
+        /// </summary>
+        /// <param name="address">address, must be eaven number</param>
+        /// <returns>true = passed, false = failed</returns>
+        public bool setaddress(int address)
+        {
+            if (!this.IsOpen)
+            {
+                return false;
+            }
+
+            if (address % 2 == 1)
+            {
+                throw new Exception("Address must be an even number");
+            }
+
+            log.Info("Sending address   " + ((ushort)(address / 2)));
+
+            address /= 2;
+            address = (ushort)address;
+
+            byte[] command = new byte[] { (byte)'U', (byte)(address & 0xff), (byte)(address >> 8), (byte)' ' };
+            this.Write(command, 0, command.Length);
+
+            return sync();
+        }
+
+        /// <summary>
+        /// Upload data at preset address
+        /// </summary>
+        /// <param name="data">array to read from</param>
+        /// <param name="startfrom">start array index</param>
+        /// <param name="length">length to send</param>
+        /// <param name="startaddress">sets eeprom start programing address</param>
+        /// <returns>true = passed, false = failed</returns>
+        public bool upload(byte[] data, short startfrom, short length, short startaddress)
+        {
+            if (!this.IsOpen)
+            {
+                return false;
+            }
+            int loops = (length / 0x100);
+            int totalleft = length;
+            int sending = 0;
+
+            for (int a = 0; a <= loops; a++)
+            {
+                if (totalleft > 0x100)
+                {
+                    sending = 0x100;
+                }
+                else
+                {
+                    sending = totalleft;
+                }
+
+                if (sending == 0)
+                    return true;
+
+                setaddress(startaddress);
+                startaddress += (short)sending;
+
+                byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'E' };
+                this.Write(command, 0, command.Length);
+                log.Info((startfrom + (length - totalleft)) + " - " + sending);
+                this.Write(data, startfrom + (length - totalleft), sending);
+                command = new byte[] { (byte)' ' };
+                this.Write(command, 0, command.Length);
+
+                totalleft -= sending;
+
+                if (!sync())
+                {
+                    log.Info("No Sync");
+                    return false;
+                }
+            }
+            return true;
+        }
+
+        public new bool Close()
+        {
+            try
+            {
+
+                byte[] command = new byte[] { (byte)'Q', (byte)' ' };
+                this.Write(command, 0, command.Length);
+            }
+            catch { }
+
+            if (base.IsOpen)
+                base.Close();
+
+            this.DtrEnable = false;
+            this.RtsEnable = false;
+            return true;
+        }
+    }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/ArduinoSTKv2.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs
similarity index 96%
rename from Tools/ArdupilotMegaPlanner/ArduinoSTKv2.cs
rename to Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs
index 746a6f0e1..81351906f 100644
--- a/Tools/ArdupilotMegaPlanner/ArduinoSTKv2.cs
+++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs
@@ -1,388 +1,388 @@
-using System;
-using System.Collections.Generic;
-using System.Reflection;
-using System.Text;
-using System.IO.Ports;
-using System.Threading;
-using log4net;
-
-// Written by Michael Oborne
-
-namespace ArdupilotMega
-{
-    class ArduinoSTKv2 : SerialPort,ArduinoComms
-    {
-        private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
-        public event ProgressEventHandler Progress;
-
-        public new void Open()
-        {
-            // default dtr status is false
-
-            //from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup
-            base.Open();
-
-            base.DtrEnable = false;
-            base.RtsEnable = false;
-
-            System.Threading.Thread.Sleep(50);
-
-            base.DtrEnable = true;
-            base.RtsEnable = true;
-
-            System.Threading.Thread.Sleep(50);
-        }
-
-        public byte[] genstkv2packet(byte[] message)
-        {
-            byte[] data = new byte[300];
-            byte ck = 0;
-
-            data[0] = 0x1b;
-            ck ^= data[0];
-            data[1] = 0x1;
-            ck ^= data[1];
-            data[2] = (byte)((message.Length >> 8) & 0xff);
-            ck ^= data[2];
-            data[3] = (byte)(message.Length & 0xff);
-            ck ^= data[3];
-            data[4] = 0xe;
-            ck ^= data[4];
-
-            int a = 5;
-            foreach (byte let in message)
-            {
-                data[a] = let;
-                ck ^= let;
-                a++;
-            }
-            data[a] = ck;
-            a++;
-
-            this.Write(data,0,a);
-            //Console.WriteLine("about to read packet");
-
-            byte[] ret = readpacket();
-
-            //if (ret[1] == 0x0)
-            {
-                //Console.WriteLine("received OK");
-            }
-
-            return ret;
-        }
-
-        byte[] readpacket() 
-        {
-            byte[] temp = new byte[4000];
-            byte[] mes = new byte[2] { 0x0, 0xC0 }; // fail
-            int a = 7;
-            int count = 0;
-
-            this.ReadTimeout = 1000;
-
-            while (count < a)
-            {
-                //Console.WriteLine("count {0} a {1} mes leng {2}",count,a,mes.Length);
-                try
-                {
-                    temp[count] = (byte)this.ReadByte();
-                }
-                catch { break; }
-
-
-                //Console.Write("{1}", temp[0], (char)temp[0]);
-
-                if (temp[0] != 0x1b)
-                {
-                    count = 0;
-                    continue;
-                }
-
-                if (count == 3)
-                {
-                    a = (temp[2] << 8) + temp[3];
-                    mes = new byte[a];
-                    a += 5;
-                }
-
-                if (count >= 5)
-                {
-                    mes[count - 5] = temp[count];
-                }
-
-                count++;
-            }
-
-            //Console.WriteLine("read ck");
-            try
-            {
-                temp[count] = (byte)this.ReadByte();
-            }
-            catch { }
-
-            count++;
-
-            Array.Resize<byte>(ref temp, count);
-
-            //Console.WriteLine(this.BytesToRead);
-
-            return mes;
-        }
-
-
-        /// <summary>
-        /// Used to start initial connecting after serialport.open
-        /// </summary>
-        /// <returns>true = passed, false = failed</returns>
-        public bool connectAP()
-        {
-            if (!this.IsOpen)
-            {
-                return false;
-            }
-
-            Thread.Sleep(100);
-
-            int a = 0;
-            while (a < 5)
-            {
-                byte[] temp = new byte[] { 0x6, 0,0,0,0};
-                temp = this.genstkv2packet(temp);
-                a++;
-                Thread.Sleep(50);
-
-                try
-                {
-                    if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
-                    {
-                        return true;
-                    }
-                }
-                catch { }
-            }
-            return false;
-        }
-
-        /// <summary>
-        /// Used to keep alive the connection
-        /// </summary>
-        /// <returns>true = passed, false = lost connection</returns>
-        public bool keepalive()
-        {
-            return connectAP();
-        }
-        /// <summary>
-        /// Syncs after a private command has been sent
-        /// </summary>
-        /// <returns>true = passed, false = failed</returns>
-        public bool sync()
-        {
-            if (!this.IsOpen)
-            {
-                return false;
-            }
-            return true;
-        }
-        /// <summary>
-        /// Downloads the eeprom with the given length - set Address first
-        /// </summary>
-        /// <param name="length">eeprom length</param>
-        /// <returns>downloaded data</returns>
-        public byte[] download(short length)
-        {
-            if (!this.IsOpen)
-            {
-                throw new Exception();
-            }
-            byte[] data = new byte[length];
-
-            byte[] temp = new byte[] { 0x16, (byte)((length >> 8) & 0xff), (byte)((length >> 0) & 0xff) };
-            temp = this.genstkv2packet(temp);
-
-            Array.Copy(temp, 2, data, 0, length);
-
-            return data;
-        }
-
-        public byte[] downloadflash(short length)
-        {
-            if (!this.IsOpen)
-            {
-                throw new Exception("Port Closed");
-            }
-            byte[] data = new byte[length];
-
-            byte[] temp = new byte[] { 0x14, (byte)((length >> 8) & 0xff), (byte)((length >> 0) & 0xff) };
-            temp = this.genstkv2packet(temp);
-
-            Array.Copy(temp, 2, data, 0, length);
-
-            return data;
-        }
-
-        public bool uploadflash(byte[] data, int startfrom, int length, int startaddress)
-        {
-            if (!this.IsOpen)
-            {
-                return false;
-            }
-            int loops = (length / 0x100);
-            int totalleft = length;
-            int sending = 0;
-
-            for (int a = 0; a <= loops; a++)
-            {
-                if (totalleft > 0x100)
-                {
-                    sending = 0x100;
-                }
-                else
-                {
-                    sending = totalleft;
-                }
-
-                //startaddress = 256;
-                if (sending == 0)
-                    return true;
-
-                setaddress(startaddress);
-                startaddress += sending;
-
-                // 0x13          
-
-                byte[] command = new byte[] { (byte)0x13, (byte)(sending >> 8), (byte)(sending & 0xff) };
-
-                log.InfoFormat((startfrom + (length - totalleft)) + " - " + sending);
-
-                Array.Resize<byte>(ref command, sending + 10); // sending + head
-
-                Array.Copy(data, startfrom + (length - totalleft), command, 10, sending);
-
-                command = this.genstkv2packet(command);
-
-                totalleft -= sending;
-
-
-                if (Progress != null)
-                    Progress((int)(((float)startaddress / (float)length) * 100),"");
-
-                if (command[1] != 0)
-                {
-                    log.InfoFormat("No Sync");
-                    return false;
-                }
-            }
-            return true;
-        }
-
-        /// <summary>
-        /// Sets the eeprom start read or write address
-        /// </summary>
-        /// <param name="address">address, must be eaven number</param>
-        /// <returns>true = passed, false = failed</returns>
-        public bool setaddress(int address)
-        {
-            if (!this.IsOpen)
-            {
-                return false;
-            }
-
-            if (address % 2 == 1)
-            {
-                throw new Exception("Address must be an even number");
-            }
-                
-            log.InfoFormat("Sending address   " + ((address / 2)));
-
-            int tempstart = address / 2; // words
-            byte[] temp = new byte[] { 0x6, (byte)((tempstart >> 24) & 0xff), (byte)((tempstart >> 16) & 0xff), (byte)((tempstart >> 8) & 0xff), (byte)((tempstart >> 0) & 0xff) };
-            temp = this.genstkv2packet(temp);
-
-            if (temp[1] == 0)
-            {
-                return true;
-            }
-            return false;
-        }
-        /// <summary>
-        /// Upload data at preset address
-        /// </summary>
-        /// <param name="data">array to read from</param>
-        /// <param name="startfrom">start array index</param>
-        /// <param name="length">length to send</param>
-        /// <param name="startaddress">sets eeprom start programing address</param>
-        /// <returns>true = passed, false = failed</returns>
-        public bool upload(byte[] data,short startfrom,short length, short startaddress)
-        {
-            if (!this.IsOpen)
-            {
-                return false;
-            }
-            int loops = (length / 0x100);
-            int totalleft = length;
-            int sending = 0;
-
-            for (int a = 0; a <= loops; a++)
-            {
-                if (totalleft > 0x100)
-                {
-                    sending = 0x100;
-                }
-                else
-                {
-                    sending = totalleft;
-                }
-
-                //startaddress = 256;
-                if (sending == 0)
-                    return true;
-
-                setaddress(startaddress);
-                startaddress += (short)sending;
-
-                // 0x13          
-
-                byte[] command = new byte[] { (byte)0x15, (byte)(sending >> 8), (byte)(sending & 0xff) };
-
-                log.InfoFormat((startfrom + (length - totalleft)) + " - " + sending);
-
-                Array.Resize<byte>(ref command, sending + 10); // sending + head
-
-                Array.Copy(data, startfrom + (length - totalleft), command, 10, sending);
-
-                command = this.genstkv2packet(command);
-
-                totalleft -= sending;
-
-
-                if (Progress != null)
-                    Progress((int)(((float)startaddress / (float)length) * 100),"");
-
-                if (command[1] != 0)
-                {
-                    log.InfoFormat("No Sync");
-                    return false;
-                }
-            }
-            return true;
-        }
-
-        public new bool Close() {
-
-            try
-            {
-                byte[] command = new byte[] { (byte)0x11 };
-                genstkv2packet(command);
-            }
-            catch { }
-
-            if (base.IsOpen)
-                base.Close();
-
-            base.DtrEnable = false;
-            base.RtsEnable = false;
-            return true;
-        }
-    }
-}
+using System;
+using System.Collections.Generic;
+using System.Reflection;
+using System.Text;
+using System.IO.Ports;
+using System.Threading;
+using log4net;
+
+// Written by Michael Oborne
+
+namespace ArdupilotMega.Arduino
+{
+    class ArduinoSTKv2 : SerialPort,ArduinoComms
+    {
+        private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
+        public event ProgressEventHandler Progress;
+
+        public new void Open()
+        {
+            // default dtr status is false
+
+            //from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup
+            base.Open();
+
+            base.DtrEnable = false;
+            base.RtsEnable = false;
+
+            System.Threading.Thread.Sleep(50);
+
+            base.DtrEnable = true;
+            base.RtsEnable = true;
+
+            System.Threading.Thread.Sleep(50);
+        }
+
+        public byte[] genstkv2packet(byte[] message)
+        {
+            byte[] data = new byte[300];
+            byte ck = 0;
+
+            data[0] = 0x1b;
+            ck ^= data[0];
+            data[1] = 0x1;
+            ck ^= data[1];
+            data[2] = (byte)((message.Length >> 8) & 0xff);
+            ck ^= data[2];
+            data[3] = (byte)(message.Length & 0xff);
+            ck ^= data[3];
+            data[4] = 0xe;
+            ck ^= data[4];
+
+            int a = 5;
+            foreach (byte let in message)
+            {
+                data[a] = let;
+                ck ^= let;
+                a++;
+            }
+            data[a] = ck;
+            a++;
+
+            this.Write(data,0,a);
+            //Console.WriteLine("about to read packet");
+
+            byte[] ret = readpacket();
+
+            //if (ret[1] == 0x0)
+            {
+                //Console.WriteLine("received OK");
+            }
+
+            return ret;
+        }
+
+        byte[] readpacket() 
+        {
+            byte[] temp = new byte[4000];
+            byte[] mes = new byte[2] { 0x0, 0xC0 }; // fail
+            int a = 7;
+            int count = 0;
+
+            this.ReadTimeout = 1000;
+
+            while (count < a)
+            {
+                //Console.WriteLine("count {0} a {1} mes leng {2}",count,a,mes.Length);
+                try
+                {
+                    temp[count] = (byte)this.ReadByte();
+                }
+                catch { break; }
+
+
+                //Console.Write("{1}", temp[0], (char)temp[0]);
+
+                if (temp[0] != 0x1b)
+                {
+                    count = 0;
+                    continue;
+                }
+
+                if (count == 3)
+                {
+                    a = (temp[2] << 8) + temp[3];
+                    mes = new byte[a];
+                    a += 5;
+                }
+
+                if (count >= 5)
+                {
+                    mes[count - 5] = temp[count];
+                }
+
+                count++;
+            }
+
+            //Console.WriteLine("read ck");
+            try
+            {
+                temp[count] = (byte)this.ReadByte();
+            }
+            catch { }
+
+            count++;
+
+            Array.Resize<byte>(ref temp, count);
+
+            //Console.WriteLine(this.BytesToRead);
+
+            return mes;
+        }
+
+
+        /// <summary>
+        /// Used to start initial connecting after serialport.open
+        /// </summary>
+        /// <returns>true = passed, false = failed</returns>
+        public bool connectAP()
+        {
+            if (!this.IsOpen)
+            {
+                return false;
+            }
+
+            Thread.Sleep(100);
+
+            int a = 0;
+            while (a < 5)
+            {
+                byte[] temp = new byte[] { 0x6, 0,0,0,0};
+                temp = this.genstkv2packet(temp);
+                a++;
+                Thread.Sleep(50);
+
+                try
+                {
+                    if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
+                    {
+                        return true;
+                    }
+                }
+                catch { }
+            }
+            return false;
+        }
+
+        /// <summary>
+        /// Used to keep alive the connection
+        /// </summary>
+        /// <returns>true = passed, false = lost connection</returns>
+        public bool keepalive()
+        {
+            return connectAP();
+        }
+        /// <summary>
+        /// Syncs after a private command has been sent
+        /// </summary>
+        /// <returns>true = passed, false = failed</returns>
+        public bool sync()
+        {
+            if (!this.IsOpen)
+            {
+                return false;
+            }
+            return true;
+        }
+        /// <summary>
+        /// Downloads the eeprom with the given length - set Address first
+        /// </summary>
+        /// <param name="length">eeprom length</param>
+        /// <returns>downloaded data</returns>
+        public byte[] download(short length)
+        {
+            if (!this.IsOpen)
+            {
+                throw new Exception();
+            }
+            byte[] data = new byte[length];
+
+            byte[] temp = new byte[] { 0x16, (byte)((length >> 8) & 0xff), (byte)((length >> 0) & 0xff) };
+            temp = this.genstkv2packet(temp);
+
+            Array.Copy(temp, 2, data, 0, length);
+
+            return data;
+        }
+
+        public byte[] downloadflash(short length)
+        {
+            if (!this.IsOpen)
+            {
+                throw new Exception("Port Closed");
+            }
+            byte[] data = new byte[length];
+
+            byte[] temp = new byte[] { 0x14, (byte)((length >> 8) & 0xff), (byte)((length >> 0) & 0xff) };
+            temp = this.genstkv2packet(temp);
+
+            Array.Copy(temp, 2, data, 0, length);
+
+            return data;
+        }
+
+        public bool uploadflash(byte[] data, int startfrom, int length, int startaddress)
+        {
+            if (!this.IsOpen)
+            {
+                return false;
+            }
+            int loops = (length / 0x100);
+            int totalleft = length;
+            int sending = 0;
+
+            for (int a = 0; a <= loops; a++)
+            {
+                if (totalleft > 0x100)
+                {
+                    sending = 0x100;
+                }
+                else
+                {
+                    sending = totalleft;
+                }
+
+                //startaddress = 256;
+                if (sending == 0)
+                    return true;
+
+                setaddress(startaddress);
+                startaddress += sending;
+
+                // 0x13          
+
+                byte[] command = new byte[] { (byte)0x13, (byte)(sending >> 8), (byte)(sending & 0xff) };
+
+                log.InfoFormat((startfrom + (length - totalleft)) + " - " + sending);
+
+                Array.Resize<byte>(ref command, sending + 10); // sending + head
+
+                Array.Copy(data, startfrom + (length - totalleft), command, 10, sending);
+
+                command = this.genstkv2packet(command);
+
+                totalleft -= sending;
+
+
+                if (Progress != null)
+                    Progress((int)(((float)startaddress / (float)length) * 100),"");
+
+                if (command[1] != 0)
+                {
+                    log.InfoFormat("No Sync");
+                    return false;
+                }
+            }
+            return true;
+        }
+
+        /// <summary>
+        /// Sets the eeprom start read or write address
+        /// </summary>
+        /// <param name="address">address, must be eaven number</param>
+        /// <returns>true = passed, false = failed</returns>
+        public bool setaddress(int address)
+        {
+            if (!this.IsOpen)
+            {
+                return false;
+            }
+
+            if (address % 2 == 1)
+            {
+                throw new Exception("Address must be an even number");
+            }
+                
+            log.InfoFormat("Sending address   " + ((address / 2)));
+
+            int tempstart = address / 2; // words
+            byte[] temp = new byte[] { 0x6, (byte)((tempstart >> 24) & 0xff), (byte)((tempstart >> 16) & 0xff), (byte)((tempstart >> 8) & 0xff), (byte)((tempstart >> 0) & 0xff) };
+            temp = this.genstkv2packet(temp);
+
+            if (temp[1] == 0)
+            {
+                return true;
+            }
+            return false;
+        }
+        /// <summary>
+        /// Upload data at preset address
+        /// </summary>
+        /// <param name="data">array to read from</param>
+        /// <param name="startfrom">start array index</param>
+        /// <param name="length">length to send</param>
+        /// <param name="startaddress">sets eeprom start programing address</param>
+        /// <returns>true = passed, false = failed</returns>
+        public bool upload(byte[] data,short startfrom,short length, short startaddress)
+        {
+            if (!this.IsOpen)
+            {
+                return false;
+            }
+            int loops = (length / 0x100);
+            int totalleft = length;
+            int sending = 0;
+
+            for (int a = 0; a <= loops; a++)
+            {
+                if (totalleft > 0x100)
+                {
+                    sending = 0x100;
+                }
+                else
+                {
+                    sending = totalleft;
+                }
+
+                //startaddress = 256;
+                if (sending == 0)
+                    return true;
+
+                setaddress(startaddress);
+                startaddress += (short)sending;
+
+                // 0x13          
+
+                byte[] command = new byte[] { (byte)0x15, (byte)(sending >> 8), (byte)(sending & 0xff) };
+
+                log.InfoFormat((startfrom + (length - totalleft)) + " - " + sending);
+
+                Array.Resize<byte>(ref command, sending + 10); // sending + head
+
+                Array.Copy(data, startfrom + (length - totalleft), command, 10, sending);
+
+                command = this.genstkv2packet(command);
+
+                totalleft -= sending;
+
+
+                if (Progress != null)
+                    Progress((int)(((float)startaddress / (float)length) * 100),"");
+
+                if (command[1] != 0)
+                {
+                    log.InfoFormat("No Sync");
+                    return false;
+                }
+            }
+            return true;
+        }
+
+        public new bool Close() {
+
+            try
+            {
+                byte[] command = new byte[] { (byte)0x11 };
+                genstkv2packet(command);
+            }
+            catch { }
+
+            if (base.IsOpen)
+                base.Close();
+
+            base.DtrEnable = false;
+            base.RtsEnable = false;
+            return true;
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
index 7a63c6dae..32227d2fb 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
@@ -355,7 +355,7 @@
     <Compile Include="Controls\AGauge.cs">
       <SubType>UserControl</SubType>
     </Compile>
-    <Compile Include="ArduinoDetect.cs" />
+    <Compile Include="Arduino\ArduinoDetect.cs" />
     <Compile Include="AviWriter.cs" />
     <Compile Include="Camera.cs">
       <SubType>Form</SubType>
@@ -364,12 +364,12 @@
       <DependentUpon>Camera.cs</DependentUpon>
     </Compile>
     <Compile Include="Capture.cs" />
-    <Compile Include="CommsSerialInterface.cs" />
-    <Compile Include="CommsSerialPort.cs">
+    <Compile Include="Comms\CommsSerialInterface.cs" />
+    <Compile Include="Comms\CommsSerialPort.cs">
       <SubType>Component</SubType>
     </Compile>
-    <Compile Include="CommsTCPSerial.cs" />
-    <Compile Include="CommsUdpSerial.cs" />
+    <Compile Include="Comms\CommsTCPSerial.cs" />
+    <Compile Include="Comms\CommsUdpSerial.cs" />
     <Compile Include="Controls\ImageLabel.cs">
       <SubType>UserControl</SubType>
     </Compile>
@@ -379,12 +379,6 @@
     <Compile Include="Controls\myGMAP.cs">
       <SubType>UserControl</SubType>
     </Compile>
-    <Compile Include="Controls\XorPlus.cs">
-      <SubType>Form</SubType>
-    </Compile>
-    <Compile Include="Controls\XorPlus.Designer.cs">
-      <DependentUpon>XorPlus.cs</DependentUpon>
-    </Compile>
     <Compile Include="Radio\IHex.cs" />
     <Compile Include="Mavlink\MavlinkCRC.cs" />
     <Compile Include="Mavlink\MavlinkUtil.cs" />
@@ -439,14 +433,14 @@
     <Compile Include="Common.cs">
       <SubType>Component</SubType>
     </Compile>
-    <Compile Include="ArduinoComms.cs" />
+    <Compile Include="Arduino\ArduinoComms.cs" />
     <Compile Include="Controls\MyLabel.cs">
       <SubType>Component</SubType>
     </Compile>
     <Compile Include="Controls\MyUserControl.cs">
       <SubType>UserControl</SubType>
     </Compile>
-    <Compile Include="ArduinoSTKv2.cs">
+    <Compile Include="Arduino\ArduinoSTKv2.cs">
       <SubType>Component</SubType>
     </Compile>
     <Compile Include="paramcompare.cs">
@@ -473,7 +467,7 @@
     <Compile Include="GCSViews\Terminal.Designer.cs">
       <DependentUpon>Terminal.cs</DependentUpon>
     </Compile>
-    <Compile Include="HUD.cs">
+    <Compile Include="Controls\HUD.cs">
       <SubType>UserControl</SubType>
     </Compile>
     <Compile Include="MainV2.cs">
@@ -515,7 +509,7 @@
       <DependentUpon>ElevationProfile.cs</DependentUpon>
     </Compile>
     <Compile Include="MAVLink.cs" />
-    <Compile Include="ArduinoSTK.cs">
+    <Compile Include="Arduino\ArduinoSTK.cs">
       <SubType>Component</SubType>
     </Compile>
     <Compile Include="Log.cs">
@@ -757,9 +751,6 @@
     <EmbeddedResource Include="Controls\ImageLabel.resx">
       <DependentUpon>ImageLabel.cs</DependentUpon>
     </EmbeddedResource>
-    <EmbeddedResource Include="Controls\XorPlus.resx">
-      <DependentUpon>XorPlus.cs</DependentUpon>
-    </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\Configuration.es-ES.resx">
       <DependentUpon>Configuration.cs</DependentUpon>
     </EmbeddedResource>
@@ -1021,6 +1012,7 @@
     </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\Simulation.resx">
       <DependentUpon>Simulation.cs</DependentUpon>
+      <SubType>Designer</SubType>
     </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\Simulation.zh-Hans.resx">
       <DependentUpon>Simulation.cs</DependentUpon>
@@ -1096,10 +1088,6 @@
     <None Include="m3u\networklink.kml">
       <CopyToOutputDirectory>Always</CopyToOutputDirectory>
     </None>
-    <None Include="MAC\Info.plist" />
-    <None Include="MAC\run.sh" />
-    <None Include="Msi\installer.bat" />
-    <None Include="Msi\installer.wxs" />
     <None Include="mykey.snk" />
     <None Include="Properties\app.manifest" />
     <None Include="Properties\DataSources\CurrentState.datasource" />
diff --git a/Tools/ArdupilotMegaPlanner/Camera.Designer.cs b/Tools/ArdupilotMegaPlanner/Camera.Designer.cs
index a748b9749..b2ff93843 100644
--- a/Tools/ArdupilotMegaPlanner/Camera.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/Camera.Designer.cs
@@ -61,7 +61,7 @@
             this.TXT_distacflphotos = new System.Windows.Forms.TextBox();
             this.TXT_distflphotos = new System.Windows.Forms.TextBox();
             this.CMB_camera = new System.Windows.Forms.ComboBox();
-            this.BUT_save = new ArdupilotMega.MyButton();
+            this.BUT_save = new ArdupilotMega.Controls.MyButton();
             ((System.ComponentModel.ISupportInitialize)(this.num_agl)).BeginInit();
             ((System.ComponentModel.ISupportInitialize)(this.num_focallength)).BeginInit();
             ((System.ComponentModel.ISupportInitialize)(this.num_overlap)).BeginInit();
@@ -379,6 +379,6 @@
         private System.Windows.Forms.TextBox TXT_distacflphotos;
         private System.Windows.Forms.TextBox TXT_distflphotos;
         private System.Windows.Forms.ComboBox CMB_camera;
-        private MyButton BUT_save;
+        private ArdupilotMega.Controls.MyButton BUT_save;
     }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Camera.resx b/Tools/ArdupilotMegaPlanner/Camera.resx
index b5668d74b..8e934149d 100644
--- a/Tools/ArdupilotMegaPlanner/Camera.resx
+++ b/Tools/ArdupilotMegaPlanner/Camera.resx
@@ -915,7 +915,7 @@
     <value>BUT_save</value>
   </data>
   <data name="&gt;&gt;BUT_save.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_save.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs
index c6453757d..30b539568 100644
--- a/Tools/ArdupilotMegaPlanner/Common.cs
+++ b/Tools/ArdupilotMegaPlanner/Common.cs
@@ -1,5 +1,6 @@
 using System;
 using System.Collections.Generic;
+using System.Linq;
 using System.ComponentModel;
 using System.Data;
 using System.Drawing;
@@ -23,6 +24,7 @@ using log4net;
 using ZedGraph; // Graphs
 using ArdupilotMega;
 using System.Reflection;
+using ArdupilotMega.Utilities;
 
 using System.IO;
 
@@ -710,6 +712,22 @@ namespace ArdupilotMega
             return null;
         }
 
+        public static List<KeyValuePair<int,string>> getModesList()
+        {
+            if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+            {
+                var flightModes = EnumTranslator.Translate<apmmodes>();
+                return flightModes.ToList();
+            }
+            else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+            {
+                var flightModes = EnumTranslator.Translate<ac2modes>();
+                return flightModes.ToList();
+            }
+
+            return null;
+        }
+
         public static Form LoadingBox(string title, string promptText)
         {
             Form form = new Form();
@@ -746,7 +764,7 @@ namespace ArdupilotMega
             Form form = new Form();
             System.Windows.Forms.Label label = new System.Windows.Forms.Label();
             CheckBox chk = new CheckBox();
-            MyButton buttonOk = new MyButton();
+            ArdupilotMega.Controls.MyButton buttonOk = new ArdupilotMega.Controls.MyButton();
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2));
             form.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
 
@@ -806,8 +824,8 @@ namespace ArdupilotMega
             Form form = new Form();
             System.Windows.Forms.Label label = new System.Windows.Forms.Label();
             TextBox textBox = new TextBox();
-            MyButton buttonOk = new MyButton();
-            MyButton buttonCancel = new MyButton();
+            ArdupilotMega.Controls.MyButton buttonOk = new ArdupilotMega.Controls.MyButton();
+            ArdupilotMega.Controls.MyButton buttonCancel = new ArdupilotMega.Controls.MyButton();
 
             form.TopMost = true;
 
diff --git a/Tools/ArdupilotMegaPlanner/CommsSerialInterface.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialInterface.cs
similarity index 95%
rename from Tools/ArdupilotMegaPlanner/CommsSerialInterface.cs
rename to Tools/ArdupilotMegaPlanner/Comms/CommsSerialInterface.cs
index cd85b9244..aee48f040 100644
--- a/Tools/ArdupilotMegaPlanner/CommsSerialInterface.cs
+++ b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialInterface.cs
@@ -1,59 +1,59 @@
-using System;
-using System.Collections.Generic;
-using System.Text;
-using System.IO.Ports;
-using System.IO;
-using System.Reflection;
-
-namespace ArdupilotMega
-{
-    public interface ICommsSerial
-    {
-        // from serialport class
-        // Methods
-         void Close();
-         void DiscardInBuffer();
-         //void DiscardOutBuffer();
-         void Open();
-         int Read(byte[] buffer, int offset, int count);
-         //int Read(char[] buffer, int offset, int count);
-         int ReadByte();
-         int ReadChar();
-         string ReadExisting();
-         string ReadLine();
-         //string ReadTo(string value);
-         void Write(string text);
-         void Write(byte[] buffer, int offset, int count);
-         //void Write(char[] buffer, int offset, int count);
-         void WriteLine(string text);
-
-         void toggleDTR();
-
-        // Properties
-         //Stream BaseStream { get; }
-         int BaudRate { get; set; }
-         //bool BreakState { get; set; }
-         int BytesToRead { get; }
-         int BytesToWrite { get; }
-         //bool CDHolding { get; }
-         //bool CtsHolding { get; }
-         int DataBits { get; set; }
-         //bool DiscardNull { get; set; }
-         //bool DsrHolding { get; }
-         bool DtrEnable { get; set; }
-         //Encoding Encoding { get; set; }
-         //Handshake Handshake { get; set; }
-         bool IsOpen { get; }
-         //string NewLine { get; set; }
-         Parity Parity { get; set; }
-         //byte ParityReplace { get; set; }
-         string PortName { get; set; }
-         int ReadBufferSize { get; set; }
-         int ReadTimeout { get; set; }
-         int ReceivedBytesThreshold { get; set; }
-         bool RtsEnable { get; set; }
-         StopBits StopBits { get; set; }
-         int WriteBufferSize { get; set; }
-         int WriteTimeout { get; set; }
-    }
-}
+using System;
+using System.Collections.Generic;
+using System.Text;
+using System.IO.Ports;
+using System.IO;
+using System.Reflection;
+
+namespace ArdupilotMega.Comms
+{
+    public interface ICommsSerial
+    {
+        // from serialport class
+        // Methods
+         void Close();
+         void DiscardInBuffer();
+         //void DiscardOutBuffer();
+         void Open();
+         int Read(byte[] buffer, int offset, int count);
+         //int Read(char[] buffer, int offset, int count);
+         int ReadByte();
+         int ReadChar();
+         string ReadExisting();
+         string ReadLine();
+         //string ReadTo(string value);
+         void Write(string text);
+         void Write(byte[] buffer, int offset, int count);
+         //void Write(char[] buffer, int offset, int count);
+         void WriteLine(string text);
+
+         void toggleDTR();
+
+        // Properties
+         //Stream BaseStream { get; }
+         int BaudRate { get; set; }
+         //bool BreakState { get; set; }
+         int BytesToRead { get; }
+         int BytesToWrite { get; }
+         //bool CDHolding { get; }
+         //bool CtsHolding { get; }
+         int DataBits { get; set; }
+         //bool DiscardNull { get; set; }
+         //bool DsrHolding { get; }
+         bool DtrEnable { get; set; }
+         //Encoding Encoding { get; set; }
+         //Handshake Handshake { get; set; }
+         bool IsOpen { get; }
+         //string NewLine { get; set; }
+         Parity Parity { get; set; }
+         //byte ParityReplace { get; set; }
+         string PortName { get; set; }
+         int ReadBufferSize { get; set; }
+         int ReadTimeout { get; set; }
+         int ReceivedBytesThreshold { get; set; }
+         bool RtsEnable { get; set; }
+         StopBits StopBits { get; set; }
+         int WriteBufferSize { get; set; }
+         int WriteTimeout { get; set; }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs
similarity index 96%
rename from Tools/ArdupilotMegaPlanner/CommsSerialPort.cs
rename to Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs
index 2fe153f28..ac07fc4a3 100644
--- a/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs
+++ b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs
@@ -1,85 +1,85 @@
-using System;
-using System.Collections.Generic;
-using System.Text;
-using System.IO.Ports;
-using System.IO;
-using System.Linq;
-
-namespace ArdupilotMega
-{
-    class SerialPort : System.IO.Ports.SerialPort,ICommsSerial
-    {
-        public new void Open()
-        {
-            if (base.IsOpen)
-                return;
-
-            base.Open();
-        }
-
-        public void toggleDTR()
-        {
-            bool open = this.IsOpen;
-
-            if (!open)
-                this.Open();
-
-            base.DtrEnable = false;
-            base.RtsEnable = false;
-
-            System.Threading.Thread.Sleep(50);
-
-            base.DtrEnable = true;
-            base.RtsEnable = true;
-
-            System.Threading.Thread.Sleep(50);
-
-            if (!open)
-                this.Close();
-        }
-
-        public new static string[] GetPortNames()
-        {
-            List<string> allPorts = new List<string>();
-
-            if (Directory.Exists("/dev/"))
-            {
-                if (Directory.Exists("/dev/serial/by-id/"))
-                    allPorts.AddRange(Directory.GetFiles("/dev/serial/by-id/", "*"));
-                allPorts.AddRange(Directory.GetFiles("/dev/", "ttyACM*"));
-                allPorts.AddRange(Directory.GetFiles("/dev/", "ttyUSB*"));
-            }
-
-            string[] ports = System.IO.Ports.SerialPort.GetPortNames()
-            .Select(p => p.TrimEnd())
-            .Select(FixBlueToothPortNameBug)
-            .ToArray();
-
-            allPorts.AddRange(ports);
-
-            return allPorts.ToArray();
-        }
-
-
-        // .NET bug: sometimes bluetooth ports are enumerated with bogus characters 
-        // eg 'COM10' becomes 'COM10c' - one workaround is to remove the non numeric  
-        // char. Annoyingly, sometimes a numeric char is added, which means this 
-        // does not work in all cases. 
-        // See http://connect.microsoft.com/VisualStudio/feedback/details/236183/system-io-ports-serialport-getportnames-error-with-bluetooth 
-        private static string FixBlueToothPortNameBug(string portName)
-        {
-            if (!portName.StartsWith("COM"))
-                return portName;
-            var newPortName = "COM";                                // Start over with "COM" 
-            foreach (var portChar in portName.Substring(3).ToCharArray())  //  Remove "COM", put the rest in a character array 
-            {
-                if (char.IsDigit(portChar))
-                    newPortName += portChar.ToString(); // Good character, append to portName 
-                //  else
-                //log.WarnFormat("Bad (Non Numeric) character in port name '{0}' - removing", portName);
-            }
-
-            return newPortName;
-        }
-    }
-}
+using System;
+using System.Collections.Generic;
+using System.Text;
+using System.IO.Ports;
+using System.IO;
+using System.Linq;
+
+namespace ArdupilotMega.Comms
+{
+    class SerialPort : System.IO.Ports.SerialPort,ICommsSerial
+    {
+        public new void Open()
+        {
+            if (base.IsOpen)
+                return;
+
+            base.Open();
+        }
+
+        public void toggleDTR()
+        {
+            bool open = this.IsOpen;
+
+            if (!open)
+                this.Open();
+
+            base.DtrEnable = false;
+            base.RtsEnable = false;
+
+            System.Threading.Thread.Sleep(50);
+
+            base.DtrEnable = true;
+            base.RtsEnable = true;
+
+            System.Threading.Thread.Sleep(50);
+
+            if (!open)
+                this.Close();
+        }
+
+        public new static string[] GetPortNames()
+        {
+            List<string> allPorts = new List<string>();
+
+            if (Directory.Exists("/dev/"))
+            {
+                if (Directory.Exists("/dev/serial/by-id/"))
+                    allPorts.AddRange(Directory.GetFiles("/dev/serial/by-id/", "*"));
+                allPorts.AddRange(Directory.GetFiles("/dev/", "ttyACM*"));
+                allPorts.AddRange(Directory.GetFiles("/dev/", "ttyUSB*"));
+            }
+
+            string[] ports = System.IO.Ports.SerialPort.GetPortNames()
+            .Select(p => p.TrimEnd())
+            .Select(FixBlueToothPortNameBug)
+            .ToArray();
+
+            allPorts.AddRange(ports);
+
+            return allPorts.ToArray();
+        }
+
+
+        // .NET bug: sometimes bluetooth ports are enumerated with bogus characters 
+        // eg 'COM10' becomes 'COM10c' - one workaround is to remove the non numeric  
+        // char. Annoyingly, sometimes a numeric char is added, which means this 
+        // does not work in all cases. 
+        // See http://connect.microsoft.com/VisualStudio/feedback/details/236183/system-io-ports-serialport-getportnames-error-with-bluetooth 
+        private static string FixBlueToothPortNameBug(string portName)
+        {
+            if (!portName.StartsWith("COM"))
+                return portName;
+            var newPortName = "COM";                                // Start over with "COM" 
+            foreach (var portChar in portName.Substring(3).ToCharArray())  //  Remove "COM", put the rest in a character array 
+            {
+                if (char.IsDigit(portChar))
+                    newPortName += portChar.ToString(); // Good character, append to portName 
+                //  else
+                //log.WarnFormat("Bad (Non Numeric) character in port name '{0}' - removing", portName);
+            }
+
+            return newPortName;
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsTCPSerial.cs
similarity index 94%
rename from Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs
rename to Tools/ArdupilotMegaPlanner/Comms/CommsTCPSerial.cs
index 76492e1e8..435e3f46e 100644
--- a/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs
+++ b/Tools/ArdupilotMegaPlanner/Comms/CommsTCPSerial.cs
@@ -9,9 +9,9 @@ using System.Net; // dns, ip address
 using System.Net.Sockets; // tcplistner
 using log4net;
 
-namespace System.IO.Ports
+namespace ArdupilotMega.Comms
 {
-    public class TcpSerial : ArdupilotMega.ICommsSerial
+    public class TcpSerial : ArdupilotMega.Comms.ICommsSerial
     {
         private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
         TcpClient client = new TcpClient();
@@ -93,11 +93,11 @@ namespace System.IO.Ports
             if (ArdupilotMega.MainV2.config["TCP_host"] != null)
                 host = ArdupilotMega.MainV2.config["TCP_host"].ToString();
 
-            if (Windows.Forms.DialogResult.Cancel == ArdupilotMega.Common.InputBox("remote host", "Enter host name/ip (ensure remote end is already started)", ref host))
+            if (System.Windows.Forms.DialogResult.Cancel == ArdupilotMega.Common.InputBox("remote host", "Enter host name/ip (ensure remote end is already started)", ref host))
             {
                 throw new Exception("Canceled by request");
             }
-            if (Windows.Forms.DialogResult.Cancel == ArdupilotMega.Common.InputBox("remote Port", "Enter remote port", ref dest))
+            if (System.Windows.Forms.DialogResult.Cancel == ArdupilotMega.Common.InputBox("remote Port", "Enter remote port", ref dest))
             {
                 throw new Exception("Canceled by request");
             }
diff --git a/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsUdpSerial.cs
similarity index 95%
rename from Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs
rename to Tools/ArdupilotMegaPlanner/Comms/CommsUdpSerial.cs
index f5b5feb3e..d569cad89 100644
--- a/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs
+++ b/Tools/ArdupilotMegaPlanner/Comms/CommsUdpSerial.cs
@@ -1,301 +1,304 @@
-using System.Reflection;
-using System.Text;
-using System.Net; // dns, ip address
-using System.Net.Sockets; // tcplistner
-using log4net;
-using ArdupilotMega.Controls;
-
-namespace System.IO.Ports
-{
-    public class UdpSerial : ArdupilotMega.ICommsSerial
-    {
-        private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
-        UdpClient client = new UdpClient();
-        IPEndPoint RemoteIpEndPoint = new IPEndPoint(IPAddress.Any, 0);
-        byte[] rbuffer = new byte[0];
-        int rbufferread = 0;
-
-        public int WriteBufferSize { get; set; }
-        public int WriteTimeout { get; set; }
-        public int ReceivedBytesThreshold { get; set; }
-        public bool RtsEnable { get; set; }
-
-        ~UdpSerial()
-        {
-            this.Close();
-            client = null;
-        }
-
-        public UdpSerial()
-        {
-            //System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
-            //System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
-
-            Port = "14550";
-        }
-
-        public void toggleDTR()
-        {
-        }
-
-        public string Port { get; set; }
-
-        public int ReadTimeout
-        {
-            get;// { return client.ReceiveTimeout; }
-            set;// { client.ReceiveTimeout = value; }
-        }
-
-        public int ReadBufferSize {get;set;}
-
-        public int BaudRate { get; set; }
-        public StopBits StopBits { get; set; }
-        public  Parity Parity { get; set; }
-        public  int DataBits { get; set; }
-
-        public string PortName { get; set; }
-
-        public  int BytesToRead
-        {
-            get { return client.Available + rbuffer.Length - rbufferread; }
-        }
-
-        public int BytesToWrite { get {return 0;} }
-
-        public bool IsOpen { get { if (client.Client == null) return false; return client.Client.Connected; } }
-
-        public bool DtrEnable
-        {
-            get;
-            set;
-        }
-
-        public  void Open()
-        {
-            if (client.Client.Connected)
-            {
-                log.Info("udpserial socket already open");
-                return;
-            }
-
-            ProgressReporterDialogue frmProgressReporter = new ProgressReporterDialogue
-            {
-                StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
-                Text = "Connecting Mavlink UDP"
-            };
-
-            frmProgressReporter.DoWork += frmProgressReporter_DoWork;
-
-            frmProgressReporter.UpdateProgressAndStatus(-1, "Connecting Mavlink UDP");
-
-            ArdupilotMega.ThemeManager.ApplyThemeTo(frmProgressReporter);
-
-            frmProgressReporter.RunBackgroundOperationAsync();
-
-            
-        }
-
-        void frmProgressReporter_DoWork(object sender, ArdupilotMega.Controls.ProgressWorkerEventArgs e)
-        {
-            string dest = Port;
-
-            if (ArdupilotMega.MainV2.config["UDP_port"] != null)
-                dest = ArdupilotMega.MainV2.config["UDP_port"].ToString();
-
-            ArdupilotMega.Common.InputBox("Listern Port", "Enter Local port (ensure remote end is already sending)", ref dest);
-            Port = dest;
-
-            ArdupilotMega.MainV2.config["UDP_port"] = Port;
-
-            client = new UdpClient(int.Parse(Port));
-
-            while (true)
-            {
-                ((ProgressReporterDialogue)sender).UpdateProgressAndStatus(-1, "Waiting for UDP");
-                System.Threading.Thread.Sleep(500);
-
-                if (((ProgressReporterDialogue)sender).doWorkArgs.CancelRequested)
-                {
-                    ((ProgressReporterDialogue)sender).doWorkArgs.CancelAcknowledged = true;
-                    try
-                    {
-                        client.Close();
-                    }
-                    catch { }
-                    return;
-                }
-
-                if (BytesToRead > 0)
-                    break;
-            }
-
-            if (BytesToRead == 0)
-                return;
-
-            try
-            {
-                client.Receive(ref RemoteIpEndPoint);
-                log.InfoFormat("NetSerial connecting to {0} : {1}", RemoteIpEndPoint.Address, RemoteIpEndPoint.Port);
-                client.Connect(RemoteIpEndPoint);
-            }
-            catch (Exception ex)
-            {
-                if (client != null && client.Client.Connected)
-                {
-                    client.Close();
-                }
-                log.Info(ex.ToString());
-                System.Windows.Forms.CustomMessageBox.Show("Please check your Firewall settings\nPlease try running this command\n1.    Run the following command in an elevated command prompt to disable Windows Firewall temporarily:\n    \nNetsh advfirewall set allprofiles state off\n    \nNote: This is just for test; please turn it back on with the command 'Netsh advfirewall set allprofiles state on'.\n");
-                throw new Exception("The socket/serialproxy is closed " + e);
-            }
-        }
-
-        void VerifyConnected()
-        {
-            if (client == null || !IsOpen)
-            {
-                throw new Exception("The socket/serialproxy is closed");
-            }
-        }
-
-        public  int Read(byte[] readto,int offset,int length)
-        {
-            VerifyConnected();
-            try
-            {
-                if (length < 1) { return 0; }
-
-                if (rbufferread == rbuffer.Length)
-                {
-                    MemoryStream r = new MemoryStream();
-                    while (client.Available > 0)
-                    {
-                        Byte[] b = client.Receive(ref RemoteIpEndPoint);
-                        r.Write(b, 0, b.Length);
-                    }
-                    rbuffer = r.ToArray();
-                    rbufferread = 0;
-                }
-
-                Array.Copy(rbuffer, rbufferread, readto, offset, length);
-
-                rbufferread += length;
-
-                return length;
-            }
-            catch { throw new Exception("Socket Closed"); }
-        }
-
-        public  int ReadByte()
-        {
-            VerifyConnected();
-            int count = 0;
-            while (this.BytesToRead == 0)
-            {
-                System.Threading.Thread.Sleep(1);
-                if (count > ReadTimeout)
-                    throw new Exception("NetSerial Timeout on read");
-                count++;
-            }
-            byte[] buffer = new byte[1];
-            Read(buffer, 0, 1);
-            return buffer[0];
-        }
-
-        public  int ReadChar()
-        {
-            return ReadByte();
-        }
-
-        public  string ReadExisting() 
-        {
-            VerifyConnected();
-            byte[] data = new byte[client.Available];
-            if (data.Length > 0)
-                Read(data, 0, data.Length);
-
-            string line = Encoding.ASCII.GetString(data, 0, data.Length);
-
-            return line;
-        }
-
-        public  void WriteLine(string line)
-        {
-            VerifyConnected();
-            line = line + "\n";
-            Write(line);
-        }
-
-        public  void Write(string line)
-        {
-            VerifyConnected();
-            byte[] data = new System.Text.ASCIIEncoding().GetBytes(line);
-            Write(data, 0, data.Length);
-        }
-
-        public  void Write(byte[] write, int offset, int length)
-        {
-            VerifyConnected();
-            try
-            {
-                client.Send(write, length);
-            }
-            catch { }//throw new Exception("Comport / Socket Closed"); }
-        }
-
-        public  void DiscardInBuffer()
-        {
-            VerifyConnected();
-            int size = client.Available;
-            byte[] crap = new byte[size];
-            log.InfoFormat("UdpSerial DiscardInBuffer {0}",size);
-            Read(crap, 0, size);
-        }
-
-        public  string ReadLine() {
-            byte[] temp = new byte[4000];
-            int count = 0;
-            int timeout = 0;
-
-            while (timeout <= 100)
-            {
-                if (!this.IsOpen) { break; }
-                if (this.BytesToRead > 0)
-                {
-                    byte letter = (byte)this.ReadByte();
-
-                    temp[count] = letter;
-
-                    if (letter == '\n') // normal line
-                    {
-                        break;
-                    }
-
-
-                    count++;
-                    if (count == temp.Length)
-                        break;
-                    timeout = 0;
-                } else {
-                    timeout++;
-                    System.Threading.Thread.Sleep(5);
-                }
-            }
-
-            Array.Resize<byte>(ref temp, count + 1);
-
-            return Encoding.ASCII.GetString(temp, 0, temp.Length);
-        }
-
-        public void Close()
-        {
-            if (client.Client != null && client.Client.Connected)
-            {
-                client.Client.Close();
-                client.Close();
-            }
-
-            client = new UdpClient();
-        }
-    }
-}
+using System.Reflection;
+using System.Text;
+using System.Net; // dns, ip address
+using System.Net.Sockets; // tcplistner
+using log4net;
+using ArdupilotMega.Controls;
+using System.IO.Ports;
+using System.IO;
+using System;
+
+namespace ArdupilotMega.Comms
+{
+    public class UdpSerial : ArdupilotMega.Comms.ICommsSerial
+    {
+        private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
+        UdpClient client = new UdpClient();
+        IPEndPoint RemoteIpEndPoint = new IPEndPoint(IPAddress.Any, 0);
+        byte[] rbuffer = new byte[0];
+        int rbufferread = 0;
+
+        public int WriteBufferSize { get; set; }
+        public int WriteTimeout { get; set; }
+        public int ReceivedBytesThreshold { get; set; }
+        public bool RtsEnable { get; set; }
+
+        ~UdpSerial()
+        {
+            this.Close();
+            client = null;
+        }
+
+        public UdpSerial()
+        {
+            //System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
+            //System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
+
+            Port = "14550";
+        }
+
+        public void toggleDTR()
+        {
+        }
+
+        public string Port { get; set; }
+
+        public int ReadTimeout
+        {
+            get;// { return client.ReceiveTimeout; }
+            set;// { client.ReceiveTimeout = value; }
+        }
+
+        public int ReadBufferSize {get;set;}
+
+        public int BaudRate { get; set; }
+        public StopBits StopBits { get; set; }
+        public  Parity Parity { get; set; }
+        public  int DataBits { get; set; }
+
+        public string PortName { get; set; }
+
+        public  int BytesToRead
+        {
+            get { return client.Available + rbuffer.Length - rbufferread; }
+        }
+
+        public int BytesToWrite { get {return 0;} }
+
+        public bool IsOpen { get { if (client.Client == null) return false; return client.Client.Connected; } }
+
+        public bool DtrEnable
+        {
+            get;
+            set;
+        }
+
+        public  void Open()
+        {
+            if (client.Client.Connected)
+            {
+                log.Info("udpserial socket already open");
+                return;
+            }
+
+            ProgressReporterDialogue frmProgressReporter = new ProgressReporterDialogue
+            {
+                StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
+                Text = "Connecting Mavlink UDP"
+            };
+
+            frmProgressReporter.DoWork += frmProgressReporter_DoWork;
+
+            frmProgressReporter.UpdateProgressAndStatus(-1, "Connecting Mavlink UDP");
+
+            ArdupilotMega.ThemeManager.ApplyThemeTo(frmProgressReporter);
+
+            frmProgressReporter.RunBackgroundOperationAsync();
+
+            
+        }
+
+        void frmProgressReporter_DoWork(object sender, ArdupilotMega.Controls.ProgressWorkerEventArgs e)
+        {
+            string dest = Port;
+
+            if (ArdupilotMega.MainV2.config["UDP_port"] != null)
+                dest = ArdupilotMega.MainV2.config["UDP_port"].ToString();
+
+            ArdupilotMega.Common.InputBox("Listern Port", "Enter Local port (ensure remote end is already sending)", ref dest);
+            Port = dest;
+
+            ArdupilotMega.MainV2.config["UDP_port"] = Port;
+
+            client = new UdpClient(int.Parse(Port));
+
+            while (true)
+            {
+                ((ProgressReporterDialogue)sender).UpdateProgressAndStatus(-1, "Waiting for UDP");
+                System.Threading.Thread.Sleep(500);
+
+                if (((ProgressReporterDialogue)sender).doWorkArgs.CancelRequested)
+                {
+                    ((ProgressReporterDialogue)sender).doWorkArgs.CancelAcknowledged = true;
+                    try
+                    {
+                        client.Close();
+                    }
+                    catch { }
+                    return;
+                }
+
+                if (BytesToRead > 0)
+                    break;
+            }
+
+            if (BytesToRead == 0)
+                return;
+
+            try
+            {
+                client.Receive(ref RemoteIpEndPoint);
+                log.InfoFormat("NetSerial connecting to {0} : {1}", RemoteIpEndPoint.Address, RemoteIpEndPoint.Port);
+                client.Connect(RemoteIpEndPoint);
+            }
+            catch (Exception ex)
+            {
+                if (client != null && client.Client.Connected)
+                {
+                    client.Close();
+                }
+                log.Info(ex.ToString());
+                System.Windows.Forms.CustomMessageBox.Show("Please check your Firewall settings\nPlease try running this command\n1.    Run the following command in an elevated command prompt to disable Windows Firewall temporarily:\n    \nNetsh advfirewall set allprofiles state off\n    \nNote: This is just for test; please turn it back on with the command 'Netsh advfirewall set allprofiles state on'.\n");
+                throw new Exception("The socket/serialproxy is closed " + e);
+            }
+        }
+
+        void VerifyConnected()
+        {
+            if (client == null || !IsOpen)
+            {
+                throw new Exception("The socket/serialproxy is closed");
+            }
+        }
+
+        public  int Read(byte[] readto,int offset,int length)
+        {
+            VerifyConnected();
+            try
+            {
+                if (length < 1) { return 0; }
+
+                if (rbufferread == rbuffer.Length)
+                {
+                    MemoryStream r = new MemoryStream();
+                    while (client.Available > 0)
+                    {
+                        Byte[] b = client.Receive(ref RemoteIpEndPoint);
+                        r.Write(b, 0, b.Length);
+                    }
+                    rbuffer = r.ToArray();
+                    rbufferread = 0;
+                }
+
+                Array.Copy(rbuffer, rbufferread, readto, offset, length);
+
+                rbufferread += length;
+
+                return length;
+            }
+            catch { throw new Exception("Socket Closed"); }
+        }
+
+        public  int ReadByte()
+        {
+            VerifyConnected();
+            int count = 0;
+            while (this.BytesToRead == 0)
+            {
+                System.Threading.Thread.Sleep(1);
+                if (count > ReadTimeout)
+                    throw new Exception("NetSerial Timeout on read");
+                count++;
+            }
+            byte[] buffer = new byte[1];
+            Read(buffer, 0, 1);
+            return buffer[0];
+        }
+
+        public  int ReadChar()
+        {
+            return ReadByte();
+        }
+
+        public  string ReadExisting() 
+        {
+            VerifyConnected();
+            byte[] data = new byte[client.Available];
+            if (data.Length > 0)
+                Read(data, 0, data.Length);
+
+            string line = Encoding.ASCII.GetString(data, 0, data.Length);
+
+            return line;
+        }
+
+        public  void WriteLine(string line)
+        {
+            VerifyConnected();
+            line = line + "\n";
+            Write(line);
+        }
+
+        public  void Write(string line)
+        {
+            VerifyConnected();
+            byte[] data = new System.Text.ASCIIEncoding().GetBytes(line);
+            Write(data, 0, data.Length);
+        }
+
+        public  void Write(byte[] write, int offset, int length)
+        {
+            VerifyConnected();
+            try
+            {
+                client.Send(write, length);
+            }
+            catch { }//throw new Exception("Comport / Socket Closed"); }
+        }
+
+        public  void DiscardInBuffer()
+        {
+            VerifyConnected();
+            int size = client.Available;
+            byte[] crap = new byte[size];
+            log.InfoFormat("UdpSerial DiscardInBuffer {0}",size);
+            Read(crap, 0, size);
+        }
+
+        public  string ReadLine() {
+            byte[] temp = new byte[4000];
+            int count = 0;
+            int timeout = 0;
+
+            while (timeout <= 100)
+            {
+                if (!this.IsOpen) { break; }
+                if (this.BytesToRead > 0)
+                {
+                    byte letter = (byte)this.ReadByte();
+
+                    temp[count] = letter;
+
+                    if (letter == '\n') // normal line
+                    {
+                        break;
+                    }
+
+
+                    count++;
+                    if (count == temp.Length)
+                        break;
+                    timeout = 0;
+                } else {
+                    timeout++;
+                    System.Threading.Thread.Sleep(5);
+                }
+            }
+
+            Array.Resize<byte>(ref temp, count + 1);
+
+            return Encoding.ASCII.GetString(temp, 0, temp.Length);
+        }
+
+        public void Close()
+        {
+            if (client.Client != null && client.Client.Connected)
+            {
+                client.Client.Close();
+                client.Close();
+            }
+
+            client = new UdpClient();
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs b/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs
index 6e33d77c3..26ab3db6c 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs
@@ -118,7 +118,7 @@ namespace ArdupilotMega.Controls
 
                             this.Controls.Add(lbl);
 
-                            MyButton but = new MyButton();
+                            ArdupilotMega.Controls.MyButton but = new ArdupilotMega.Controls.MyButton();
 
                             but.Text = "Save";
                             but.Location = new Point(optionx + 100, y);
diff --git a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
index e26038bdc..2326987b3 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
@@ -169,7 +169,7 @@ namespace System.Windows.Forms
             switch (buttons)
             {
                 case MessageBoxButtons.OK:
-                    var but = new MyButton
+                    var but = new ArdupilotMega.Controls.MyButton
                                   {
                                       Size = new Size(75, 23),
                                       Text = "OK",
@@ -187,7 +187,7 @@ namespace System.Windows.Forms
                     if (msgBoxFrm.Width < (75 * 2 + FORM_X_MARGIN * 3))
                         msgBoxFrm.Width = (75 * 2 + FORM_X_MARGIN * 3);
 
-                    var butyes = new MyButton
+                    var butyes = new ArdupilotMega.Controls.MyButton
                     {
                         Size = new Size(75, 23),
                         Text = "Yes",
@@ -199,7 +199,7 @@ namespace System.Windows.Forms
                     msgBoxFrm.Controls.Add(butyes);
                     msgBoxFrm.AcceptButton = butyes;
 
-                    var butno = new MyButton
+                    var butno = new ArdupilotMega.Controls.MyButton
                     {
                         Size = new Size(75, 23),
                         Text = "No",
diff --git a/Tools/ArdupilotMegaPlanner/HUD.cs b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs
similarity index 97%
rename from Tools/ArdupilotMegaPlanner/HUD.cs
rename to Tools/ArdupilotMegaPlanner/Controls/HUD.cs
index e87062fb4..1ca4337e6 100644
--- a/Tools/ArdupilotMegaPlanner/HUD.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs
@@ -1,1606 +1,1606 @@
-using System;
-using System.Collections.Generic;
-using System.ComponentModel;
-using System.Drawing;
-using System.Data;
-using System.Text;
-using System.Windows.Forms;
-using System.IO;
-using System.Drawing.Imaging;
-
-using System.Threading;
- 
-using System.Drawing.Drawing2D;
-using log4net;
-using OpenTK;
-using OpenTK.Graphics.OpenGL;
-using OpenTK.Graphics;
-
-
-// Control written by Michael Oborne 2011
-// dual opengl and GDI+
-
-namespace hud
-{
-    public class HUD : GLControl
-    {
-        private static readonly ILog log = LogManager.GetLogger(
-  System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
-        object paintlock = new object();
-        object streamlock = new object();
-        MemoryStream _streamjpg = new MemoryStream();
-        [System.ComponentModel.Browsable(false)]
-        public MemoryStream streamjpg { get { lock (streamlock) { return _streamjpg; } } set { lock (streamlock) { _streamjpg = value; } } }
-        /// <summary>
-        /// this is to reduce cpu usage
-        /// </summary>
-        public bool streamjpgenable = false;
-
-        Bitmap[] charbitmaps = new Bitmap[6000];
-        int[] charbitmaptexid = new int[6000];
-        int[] charwidth = new int[6000];
-
-        public int huddrawtime = 0;
-
-        public bool opengl { get { return base.UseOpenGL; } set { base.UseOpenGL = value; } }
-
-        bool started = false;
-
-        public bool SixteenXNine = false;
-
-        public HUD()
-        {
-            if (this.DesignMode)
-            {
-                opengl = false;
-                //return;
-            }
-
-            //InitializeComponent();
-
-            graphicsObject = this;
-            graphicsObjectGDIP = Graphics.FromImage(objBitmap);
-        }
-        /*
-        private void InitializeComponent()
-        {
-            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(HUD));
-            this.SuspendLayout();
-            // 
-            // HUD
-            // 
-            this.BackColor = System.Drawing.Color.Black;
-            this.Name = "HUD";
-            resources.ApplyResources(this, "$this");
-            this.ResumeLayout(false);
-
-        }*/
-
-        float _roll = 0;
-        float _navroll = 0;
-        float _pitch = 0;
-        float _navpitch = 0;
-        float _heading = 0;
-        float _targetheading = 0;
-        float _alt = 0;
-        float _targetalt = 0;
-        float _groundspeed = 0;
-        float _airspeed = 0;
-        float _targetspeed = 0;
-        float _batterylevel = 0;
-        float _batteryremaining = 0;
-        float _gpsfix = 0;
-        float _gpshdop = 0;
-        float _disttowp = 0;
-        float _groundcourse = 0;
-        float _xtrack_error = 0;
-        float _turnrate = 0;
-        float _verticalspeed = 0;
-        float _linkqualitygcs = 0;
-        DateTime _datetime;
-        string _mode = "Manual";
-        int _wpno = 0;
-        
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float roll { get { return _roll; } set { if (_roll != value) { _roll = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float navroll { get { return _navroll; } set { if (_navroll != value) { _navroll = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float pitch { get { return _pitch; } set { if (_pitch != value) { _pitch = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float navpitch { get { return _navpitch; } set { if (_navpitch != value) { _navpitch = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float heading { get { return _heading; } set { if (_heading != value) { _heading = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float targetheading { get { return _targetheading; } set { if (_targetheading != value) { _targetheading = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float alt { get { return _alt; } set { if (_alt != value) { _alt = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float targetalt { get { return _targetalt; } set { if (_targetalt != value) { _targetalt = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float groundspeed { get { return _groundspeed; } set { if (_groundspeed != value) { _groundspeed = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float airspeed { get { return _airspeed; } set { if (_airspeed != value) { _airspeed = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float targetspeed { get { return _targetspeed; } set { if (_targetspeed != value) { _targetspeed = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float batterylevel { get { return _batterylevel; } set { if (_batterylevel != value) { _batterylevel = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float batteryremaining { get { return _batteryremaining; } set { if (_batteryremaining != value) { _batteryremaining = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float gpsfix { get { return _gpsfix; } set { if (_gpsfix != value) { _gpsfix = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float gpshdop { get { return _gpshdop; } set { if (_gpshdop != value) { _gpshdop = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float disttowp { get { return _disttowp; } set { if (_disttowp != value) { _disttowp = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public string mode { get { return _mode; } set { if (_mode != value) { _mode = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public int wpno { get { return _wpno; } set { if (_wpno != value) { _wpno = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float groundcourse { get { return _groundcourse; } set { if (_groundcourse != value) { _groundcourse = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float xtrack_error { get { return _xtrack_error; } set { if (_xtrack_error != value) { _xtrack_error = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float turnrate { get { return _turnrate; } set { if (_turnrate != value) { _turnrate = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float verticalspeed { get { return _verticalspeed; } set { if (_verticalspeed != value) { _verticalspeed = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public float linkqualitygcs { get { return _linkqualitygcs; } set { if (_linkqualitygcs != value) { _linkqualitygcs = value; this.Invalidate(); } } }
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public DateTime datetime { get { return _datetime; } set { if (_datetime != value) { _datetime = value; this.Invalidate(); } } }
-
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public int status { get; set; }
-        
-        int statuslast = 0;
-        DateTime armedtimer = DateTime.MinValue;
-
-        public bool bgon = true;
-        public bool hudon = true;
-
-        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
-        public Color hudcolor { get { return whitePen.Color; } set { whitePen = new Pen(value, 2); } }
-
-        Pen whitePen = new Pen(Color.White, 2);
-
-        public Image bgimage { set { _bgimage = value; this.Invalidate(); } }
-        Image _bgimage;
-
-        // move these global as they rarely change - reduce GC
-        Font font = new Font("Arial", 10);
-        Bitmap objBitmap = new Bitmap(1024, 1024);
-        int count = 0;
-        DateTime countdate = DateTime.Now;
-        HUD graphicsObject;
-        Graphics graphicsObjectGDIP;
-
-        DateTime starttime = DateTime.MinValue;
-
-        System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(HUD));
-
-        public override void Refresh()
-        {
-            //base.Refresh();
-            OnPaint(new PaintEventArgs(this.CreateGraphics(),this.ClientRectangle));
-        }
-
-        protected override void OnLoad(EventArgs e)
-        {
-            if (opengl)
-            {
-                try
-                {
-
-                    GraphicsMode test = this.GraphicsMode;
-                    log.Info(test.ToString());
-                    log.Info("Vendor: " + GL.GetString(StringName.Vendor));
-                    log.Info("Version: " + GL.GetString(StringName.Version));
-                    log.Info("Device: " + GL.GetString(StringName.Renderer));
-                    //Console.WriteLine("Extensions: " + GL.GetString(StringName.Extensions));
-
-                    int[] viewPort = new int[4];
-
-                    GL.GetInteger(GetPName.Viewport, viewPort);
-
-                    GL.MatrixMode(MatrixMode.Projection);
-                    GL.LoadIdentity();
-                    GL.Ortho(0, Width, Height, 0, -1, 1);
-                    GL.MatrixMode(MatrixMode.Modelview);
-                    GL.LoadIdentity();
-
-                    GL.PushAttrib(AttribMask.DepthBufferBit);
-                    GL.Disable(EnableCap.DepthTest);
-                    //GL.Enable(EnableCap.Texture2D); 
-                    GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha);
-                    GL.Enable(EnableCap.Blend);
-
-                }
-                catch (Exception ex) { log.Info("HUD opengl onload " + ex.ToString()); }
-
-                try
-                {
-                    GL.Hint(HintTarget.PerspectiveCorrectionHint, HintMode.Nicest);
-
-                    GL.Hint(HintTarget.LineSmoothHint, HintMode.Nicest);
-                    GL.Hint(HintTarget.PolygonSmoothHint, HintMode.Nicest);
-                    GL.Hint(HintTarget.PointSmoothHint, HintMode.Nicest);
-
-                    GL.Hint(HintTarget.TextureCompressionHint, HintMode.Nicest);
-                }
-                catch { }
-
-                try
-                {
-
-                    GL.Enable(EnableCap.LineSmooth);
-                    GL.Enable(EnableCap.PointSmooth);
-                    GL.Enable(EnableCap.PolygonSmooth);
-
-                }
-                catch { }
-            }
-
-            started = true;
-        }
-
-        bool inOnPaint = false;
-        string otherthread = "";
-
-        protected override void OnPaint(PaintEventArgs e)
-        {
-            //GL.Enable(EnableCap.AlphaTest)
-
-            if (!started)
-                return;
-
-            if (this.DesignMode)
-            {
-                e.Graphics.Clear(this.BackColor);
-                e.Graphics.Flush();
-            }
-
-            if ((DateTime.Now - starttime).TotalMilliseconds < 30 && (_bgimage == null))
-            {
-                //Console.WriteLine("ms "+(DateTime.Now - starttime).TotalMilliseconds);
-                //e.Graphics.DrawImageUnscaled(objBitmap, 0, 0);          
-                return;              
-            }
-
-            if (inOnPaint)
-            {
-                log.Info("Was in onpaint Hud th:" + System.Threading.Thread.CurrentThread.Name + " in " + otherthread);
-                return;
-            }
-
-            otherthread = System.Threading.Thread.CurrentThread.Name;
-
-            inOnPaint = true;
-
-            starttime = DateTime.Now;
-
-            try
-            {
-
-                if (opengl)
-                {
-                    MakeCurrent();
-
-                    GL.Clear(ClearBufferMask.ColorBufferBit);
-
-                }
-
-                doPaint(e);
-
-                if (opengl)
-                {
-                    this.SwapBuffers();
-                }
-
-            }
-            catch (Exception ex) { log.Info(ex.ToString()); }
-
-            inOnPaint = false;
-
-            count++;
-
-            huddrawtime += (int)(DateTime.Now - starttime).TotalMilliseconds;
-
-            if (DateTime.Now.Second != countdate.Second)
-            {
-                countdate = DateTime.Now;
-               // Console.WriteLine("HUD " + count + " hz drawtime " + (huddrawtime / count) + " gl " + opengl);
-                if ((huddrawtime / count) > 1000)
-                    opengl = false;
-
-                count = 0;
-                huddrawtime = 0;
-            }
-        }
-
-        void Clear(Color color)
-        {
-            if (opengl)
-            {
-                GL.ClearColor(color);
-            } else 
-            {
-                graphicsObjectGDIP.Clear(color);
-            }
-        }
-
-        const float rad2deg = (float)(180 / Math.PI);
-        const float deg2rad = (float)(1.0 / rad2deg);
-
-        public void DrawArc(Pen penn,RectangleF rect, float start,float degrees)
-        {
-            if (opengl)
-            {
-                GL.LineWidth(penn.Width);
-                GL.Color4(penn.Color);
-
-                GL.Begin(BeginMode.LineStrip);
-                start -= 90;
-                float x = 0, y = 0;
-                for (int i = (int)start; i <= start + degrees; i++)
-                {
-                    x = (float)Math.Sin(i * deg2rad) * rect.Width / 2;
-                    y = (float)Math.Cos(i * deg2rad) * rect.Height / 2;
-                    x = x + rect.X + rect.Width / 2;
-                    y = y + rect.Y + rect.Height / 2;
-                    GL.Vertex2(x, y);
-                }
-                GL.End();
-            }
-            else
-            {
-                graphicsObjectGDIP.DrawArc(penn, rect, start, degrees);
-            }
-        }
-
-        public void DrawEllipse(Pen penn, Rectangle rect)
-        {
-            if (opengl)
-            {
-                GL.LineWidth(penn.Width);
-                GL.Color4(penn.Color);
-
-                GL.Begin(BeginMode.LineLoop);
-                float x, y;
-                for (float i = 0; i < 360; i += 1)
-                {
-                    x = (float)Math.Sin(i * deg2rad) * rect.Width / 2;
-                    y = (float)Math.Cos(i * deg2rad) * rect.Height / 2;
-                    x = x + rect.X + rect.Width / 2;
-                    y = y + rect.Y + rect.Height / 2;
-                    GL.Vertex2(x, y);
-                }
-                GL.End();
-            }
-            else
-            {
-                graphicsObjectGDIP.DrawEllipse(penn, rect);
-            }
-        }
-
-        int texture;
-        Bitmap bitmap = new Bitmap(512,512);
-
-        public void DrawImage(Image img, int x, int y, int width, int height)
-        {
-            if (opengl)
-            {
-                if (img == null)
-                    return;
-                //bitmap = new Bitmap(512,512);
-
-                using (Graphics graphics = Graphics.FromImage(bitmap))
-                {
-                    graphics.CompositingQuality = System.Drawing.Drawing2D.CompositingQuality.HighSpeed;
-                    graphics.InterpolationMode = System.Drawing.Drawing2D.InterpolationMode.NearestNeighbor;
-                    graphics.SmoothingMode = System.Drawing.Drawing2D.SmoothingMode.HighSpeed;
-                    //draw the image into the target bitmap 
-                    graphics.DrawImage(img, 0, 0, bitmap.Width, bitmap.Height);
-                }
-
-
-                GL.DeleteTexture(texture);
-
-                GL.GenTextures(1, out texture);
-                GL.BindTexture(TextureTarget.Texture2D, texture);
-
-                BitmapData data = bitmap.LockBits(new System.Drawing.Rectangle(0, 0, bitmap.Width, bitmap.Height),
-        ImageLockMode.ReadOnly, System.Drawing.Imaging.PixelFormat.Format32bppArgb);
-
-                //Console.WriteLine("w {0} h {1}",data.Width, data.Height);
-
-                GL.TexImage2D(TextureTarget.Texture2D, 0, PixelInternalFormat.Rgba, data.Width, data.Height, 0,
-                    OpenTK.Graphics.OpenGL.PixelFormat.Bgra, PixelType.UnsignedByte, data.Scan0);
-
-                bitmap.UnlockBits(data);
-
-                GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear);
-                GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)TextureMagFilter.Linear);
-
-                GL.Enable(EnableCap.Texture2D);
-
-                GL.BindTexture(TextureTarget.Texture2D, texture);
-
-                GL.Begin(BeginMode.Quads);
-
-                GL.TexCoord2(0.0f, 1.0f); GL.Vertex2(0, this.Height);
-                GL.TexCoord2(1.0f, 1.0f); GL.Vertex2(this.Width, this.Height);
-                GL.TexCoord2(1.0f, 0.0f); GL.Vertex2(this.Width, 0);
-                GL.TexCoord2(0.0f, 0.0f); GL.Vertex2(0, 0);
-
-                GL.End();
-
-                GL.Disable(EnableCap.Texture2D);
-            }
-            else
-            {
-                graphicsObjectGDIP.DrawImage(img,x,y,width,height);
-            }
-        }
-
-        public void DrawPath(Pen penn, GraphicsPath gp)
-        {
-            try
-            {
-               DrawPolygon(penn, gp.PathPoints);
-            }
-            catch { }
-        }
-
-        public void FillPath(Brush brushh, GraphicsPath gp)
-        {
-            try
-            {
-                FillPolygon(brushh, gp.PathPoints);
-            }
-            catch { }
-        }
-
-        public void SetClip(Rectangle rect)
-        {
-            
-        }
-
-        public void ResetClip()
-        {
-
-        }
-
-        public void ResetTransform()
-        {
-            if (opengl)
-            {
-                GL.LoadIdentity();
-            }
-            else
-            {
-                graphicsObjectGDIP.ResetTransform();
-            }
-        }
-
-        public void RotateTransform(float angle)
-        {
-            if (opengl)
-            {
-                GL.Rotate(angle, 0, 0, 1);
-            }
-            else
-            {
-                graphicsObjectGDIP.RotateTransform(angle);
-            }
-        }
-
-        public void TranslateTransform(float x, float y)
-        {
-            if (opengl)
-            {
-                GL.Translate(x, y, 0f);
-            }
-            else
-            {
-                graphicsObjectGDIP.TranslateTransform(x, y);
-            }
-        }
-
-        public void FillPolygon(Brush brushh, Point[] list)
-        {
-            if (opengl)
-            {
-                GL.Begin(BeginMode.TriangleFan);
-                GL.Color4(((SolidBrush)brushh).Color);
-                foreach (Point pnt in list)
-                {
-                    GL.Vertex2(pnt.X, pnt.Y);
-                }
-                GL.Vertex2(list[list.Length - 1].X, list[list.Length - 1].Y);
-                GL.End();
-            }
-            else
-            {
-                graphicsObjectGDIP.FillPolygon(brushh, list);
-            }
-        }
-
-        public void FillPolygon(Brush brushh, PointF[] list)
-        {
-            if (opengl)
-            {
-                GL.Begin(BeginMode.Quads);
-                GL.Color4(((SolidBrush)brushh).Color);
-                foreach (PointF pnt in list)
-                {
-                    GL.Vertex2(pnt.X, pnt.Y);
-                }
-                GL.Vertex2(list[0].X, list[0].Y);
-                GL.End();
-            }
-            else
-            {
-                graphicsObjectGDIP.FillPolygon(brushh, list);
-            }
-        }
-
-        public void DrawPolygon(Pen penn, Point[] list)
-        {
-            if (opengl)
-            {
-                GL.LineWidth(penn.Width);
-                GL.Color4(penn.Color);
-
-                GL.Begin(BeginMode.LineLoop);
-                foreach (Point pnt in list)
-                {
-                    GL.Vertex2(pnt.X, pnt.Y);
-                }
-                GL.End();
-            }
-            else
-            {
-                graphicsObjectGDIP.DrawPolygon(penn, list);
-            }                       
-        }
-
-        public void DrawPolygon(Pen penn, PointF[] list)
-        {         
-            if (opengl)
-            {
-            GL.LineWidth(penn.Width);
-            GL.Color4(penn.Color);
-
-            GL.Begin(BeginMode.LineLoop);
-            foreach (PointF pnt in list)
-            {
-                GL.Vertex2(pnt.X, pnt.Y);
-            }
-
-            GL.End();
-            }
-            else
-            {
-                graphicsObjectGDIP.DrawPolygon(penn, list);
-            } 
-        }
-
-
-        public void FillRectangle(Brush brushh, RectangleF rectf)
-        {
-            if (opengl)
-            {
-                float x1 = rectf.X;
-                float y1 = rectf.Y;
-
-                float width = rectf.Width;
-                float height = rectf.Height;
-
-                GL.Begin(BeginMode.Quads);
-
-                if (((Type)brushh.GetType()) == typeof(LinearGradientBrush))
-                {
-                    LinearGradientBrush temp = (LinearGradientBrush)brushh;
-                    GL.Color4(temp.LinearColors[0]);
-                }
-                else
-                {
-                    GL.Color4(((SolidBrush)brushh).Color.R / 255f, ((SolidBrush)brushh).Color.G / 255f, ((SolidBrush)brushh).Color.B / 255f, ((SolidBrush)brushh).Color.A / 255f);
-                }
-
-                GL.Vertex2(x1, y1);
-                GL.Vertex2(x1 + width, y1);
-
-                if (((Type)brushh.GetType()) == typeof(LinearGradientBrush))
-                {
-                    LinearGradientBrush temp = (LinearGradientBrush)brushh;
-                    GL.Color4(temp.LinearColors[1]);
-                }
-                else
-                {
-                    GL.Color4(((SolidBrush)brushh).Color.R / 255f, ((SolidBrush)brushh).Color.G / 255f, ((SolidBrush)brushh).Color.B / 255f, ((SolidBrush)brushh).Color.A / 255f);
-                }
-
-                GL.Vertex2(x1 + width, y1 + height);
-                GL.Vertex2(x1, y1 + height);
-                GL.End();
-            }
-            else
-            {
-                graphicsObjectGDIP.FillRectangle(brushh, rectf);
-            }
-        }
-
-        public void DrawRectangle(Pen penn, RectangleF rect)
-        {
-            DrawRectangle(penn, rect.X, rect.Y, rect.Width, rect.Height);
-        }
-
-        public void DrawRectangle(Pen penn, double x1, double y1, double width, double height)
-        {
-
-            if (opengl)
-            {
-                GL.LineWidth(penn.Width);
-                GL.Color4(penn.Color);
-
-                GL.Begin(BeginMode.LineLoop);
-                GL.Vertex2(x1, y1);
-                GL.Vertex2(x1 + width, y1);
-                GL.Vertex2(x1 + width, y1 + height);
-                GL.Vertex2(x1, y1 + height);
-                GL.End();
-            }
-            else
-            {
-                graphicsObjectGDIP.DrawRectangle(penn, (float)x1, (float)y1, (float)width, (float)height);
-            }
-        }
-
-        public void DrawLine(Pen penn, double x1, double y1, double x2, double y2)
-        {
-
-            if (opengl)
-            {
-                GL.Color4(penn.Color);
-                GL.LineWidth(penn.Width);
-
-                GL.Begin(BeginMode.Lines);
-                GL.Vertex2(x1, y1);
-                GL.Vertex2(x2, y2);
-                GL.End();
-            }
-            else
-            {
-                graphicsObjectGDIP.DrawLine(penn, (float)x1, (float)y1, (float)x2, (float)y2);
-            }
-        }
-
-        void doPaint(PaintEventArgs e)
-        {
-            bool isNaN = false;
-            try
-            {
-                if (graphicsObjectGDIP == null || !opengl && (objBitmap.Width != this.Width || objBitmap.Height != this.Height))
-                {
-                    objBitmap = new Bitmap(this.Width, this.Height);
-                    graphicsObjectGDIP = Graphics.FromImage(objBitmap);
-
-                    graphicsObjectGDIP.SmoothingMode = SmoothingMode.AntiAlias;
-                    graphicsObjectGDIP.InterpolationMode = InterpolationMode.NearestNeighbor;
-                    graphicsObjectGDIP.CompositingMode = CompositingMode.SourceOver;
-                    graphicsObjectGDIP.CompositingQuality = CompositingQuality.HighSpeed;
-                    graphicsObjectGDIP.PixelOffsetMode = PixelOffsetMode.HighSpeed;
-                    graphicsObjectGDIP.TextRenderingHint = System.Drawing.Text.TextRenderingHint.SystemDefault;
-                }
-
-
-                graphicsObject.Clear(Color.Gray);
-
-                if (_bgimage != null)
-                {
-                    bgon = false;
-                    graphicsObject.DrawImage(_bgimage, 0, 0, this.Width, this.Height);
-
-                    if (hudon == false)
-                    {
-                        return;
-                    }
-                }
-                else
-                {
-                    bgon = true;
-                }
-
-
-                if (float.IsNaN(_roll) || float.IsNaN(_pitch) || float.IsNaN(_heading))
-                {
-                    isNaN = true;
-
-                    _roll = 0;
-                    _pitch = 0;
-                    _heading = 0;
-                }
-
-                graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2);
-
-
-
-                    graphicsObject.RotateTransform(-_roll);
-
-
-                int fontsize = this.Height / 30; // = 10
-                int fontoffset = fontsize - 10;
-
-                float every5deg = -this.Height / 60;
-
-                float pitchoffset = -_pitch * every5deg;
-
-                int halfwidth = this.Width / 2;
-                int halfheight = this.Height / 2;
-
-                SolidBrush whiteBrush = new SolidBrush(whitePen.Color);
-
-                Pen blackPen = new Pen(Color.Black, 2);
-                Pen greenPen = new Pen(Color.Green, 2);
-                Pen redPen = new Pen(Color.Red, 2);
-
-                // draw sky
-                if (bgon == true)
-                {
-                    RectangleF bg = new RectangleF(-halfwidth * 2, -halfheight * 2, this.Width * 2, halfheight * 2 + pitchoffset);
-
-                    if (bg.Height != 0)
-                    {
-                        LinearGradientBrush linearBrush = new LinearGradientBrush(bg, Color.Blue,
-                            Color.LightBlue, LinearGradientMode.Vertical);
-
-                        graphicsObject.FillRectangle(linearBrush, bg);
-                    }
-                    // draw ground
-
-                    bg = new RectangleF(-halfwidth * 2, pitchoffset, this.Width * 2, halfheight * 2 - pitchoffset);
-
-                    if (bg.Height != 0)
-                    {
-                        LinearGradientBrush linearBrush = new LinearGradientBrush(bg, Color.FromArgb(0x9b, 0xb8, 0x24),
-                            Color.FromArgb(0x41, 0x4f, 0x07), LinearGradientMode.Vertical);
-
-                        graphicsObject.FillRectangle(linearBrush, bg);
-                    }
-
-                    //draw centerline
-                    graphicsObject.DrawLine(whitePen, -halfwidth * 2, pitchoffset + 0, halfwidth * 2, pitchoffset + 0);
-                }
-
-                graphicsObject.ResetTransform();
-
-                graphicsObject.SetClip(new Rectangle(0, this.Height / 14, this.Width, this.Height - this.Height / 14));
-
-                graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2);
-                graphicsObject.RotateTransform(-_roll);
-
-                // draw armed
-
-                if (status != statuslast)
-                {
-                    armedtimer = DateTime.Now;
-                }
-
-                if (status == 3) // not armed
-                {
-                    //if ((armedtimer.AddSeconds(8) > DateTime.Now))
-                    {
-                        drawstring(graphicsObject, "DISARMED", font, fontsize + 10, Brushes.Red, -85, halfheight / -3);
-                        statuslast = status;
-                    }
-                }
-                else if (status == 4) // armed
-                {
-                    if ((armedtimer.AddSeconds(8) > DateTime.Now))
-                    {
-                        drawstring(graphicsObject, "ARMED", font, fontsize + 20, Brushes.Red, -70, halfheight / -3);
-                        statuslast = status;
-                    }
-                }
-
-                //draw pitch           
-
-                int lengthshort = this.Width / 12;
-                int lengthlong = this.Width / 8;
-
-                for (int a = -90; a <= 90; a += 5)
-                {
-                    // limit to 40 degrees
-                    if (a >= _pitch - 34 && a <= _pitch + 25)
-                    {
-                        if (a % 10 == 0)
-                        {
-                            if (a == 0)
-                            {
-                                graphicsObject.DrawLine(greenPen, this.Width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg);
-                            }
-                            else
-                            {
-                                graphicsObject.DrawLine(whitePen, this.Width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg);
-                            }
-                            drawstring(graphicsObject, a.ToString(), font, fontsize + 2, whiteBrush, this.Width / 2 - lengthlong - 30 - halfwidth - (int)(fontoffset * 1.7), pitchoffset + a * every5deg - 8 - fontoffset);
-                        }
-                        else
-                        {
-                            graphicsObject.DrawLine(whitePen, this.Width / 2 - lengthshort - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthshort - halfwidth, pitchoffset + a * every5deg);
-                            //drawstring(e,a.ToString(), new Font("Arial", 10), whiteBrush, this.Width / 2 - lengthshort - 20 - halfwidth, this.Height / 2 + pitchoffset + a * every5deg - 8);
-                        }
-                    }
-                }
-
-                graphicsObject.ResetTransform();
-
-                // draw roll ind needle
-
-                graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2 + this.Height / 14);
-
-                graphicsObject.RotateTransform(-_roll);
-
-                Point[] pointlist = new Point[3];
-
-                lengthlong = this.Height / 66;
-
-                int extra = this.Height / 15 * 7;
-
-                pointlist[0] = new Point(0, -lengthlong * 2 - extra);
-                pointlist[1] = new Point(-lengthlong, -lengthlong - extra);
-                pointlist[2] = new Point(lengthlong, -lengthlong - extra);
-
-                if (Math.Abs(_roll) > 45)
-                {
-                    redPen.Width = 10;
-                }
-
-                graphicsObject.DrawPolygon(redPen, pointlist);
-
-                redPen.Width = 2;
-
-                for (int a = -45; a <= 45; a += 15)
-                {
-                    graphicsObject.ResetTransform();
-                    graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2 + this.Height / 14);
-                    graphicsObject.RotateTransform(a);
-                    drawstring(graphicsObject, Math.Abs(a).ToString("##"), font, fontsize, whiteBrush, 0 - 6 - fontoffset, -lengthlong * 2 - extra);
-                    graphicsObject.DrawLine(whitePen, 0, -halfheight, 0, -halfheight - 10);
-                }
-
-                graphicsObject.ResetTransform();
-
-                //draw centre / current att
-
-                Rectangle centercircle = new Rectangle(halfwidth - 10, halfheight - 10, 20, 20);
-
-                graphicsObject.DrawEllipse(redPen, centercircle);
-                graphicsObject.DrawLine(redPen, centercircle.Left - 10, halfheight, centercircle.Left, halfheight);
-                graphicsObject.DrawLine(redPen, centercircle.Right, halfheight, centercircle.Right + 10, halfheight);
-                graphicsObject.DrawLine(redPen, centercircle.Left + centercircle.Width / 2, centercircle.Top, centercircle.Left + centercircle.Width / 2, centercircle.Top - 10);
-
-                // draw roll ind
-
-                Rectangle arcrect = new Rectangle(this.Width / 2 - this.Height / 2, this.Height / 14, this.Height, this.Height);
-
-                graphicsObject.DrawArc(whitePen, arcrect, 180 + 45, 90);
-
-                //draw heading ind
-
-                graphicsObject.ResetClip();
-
-                Rectangle headbg = new Rectangle(0, 0, this.Width - 0, this.Height / 14);
-
-                graphicsObject.DrawRectangle(blackPen, headbg);
-
-                SolidBrush solidBrush = new SolidBrush(Color.FromArgb(0x55, 0xff, 0xff, 0xff));
-
-                graphicsObject.FillRectangle(solidBrush, headbg);
-
-                // center
-                graphicsObject.DrawLine(redPen, headbg.Width / 2, headbg.Bottom, headbg.Width / 2, headbg.Top);
-
-                //bottom line
-                graphicsObject.DrawLine(whitePen, headbg.Left + 5, headbg.Bottom - 5, headbg.Width - 5, headbg.Bottom - 5);
-
-                float space = (headbg.Width - 10) / 60.0f;
-                int start = (int)Math.Round((_heading - 30),1);
-
-                // draw for outside the 60 deg
-                if (_targetheading < start)
-                {
-                    greenPen.Width = 6;
-                    graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 0, headbg.Bottom, headbg.Left + 5 + space * (0), headbg.Top);
-                }
-                if (_targetheading > _heading + 30)
-                {
-                    greenPen.Width = 6;
-                    graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 60, headbg.Bottom, headbg.Left + 5 + space * (60), headbg.Top);
-                }
-
-                for (int a = start; a <= _heading + 30; a += 1)
-                {
-                    // target heading
-                    if (((int)(a + 360) % 360) == (int)_targetheading)
-                    {
-                        greenPen.Width = 6;
-                        graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top);
-                    }
-
-                    if (((int)(a + 360) % 360) == (int)_groundcourse)
-                    {
-                        blackPen.Width = 6;
-                        graphicsObject.DrawLine(blackPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top);
-                        blackPen.Width = 2;
-                    }
-
-                    if ((int)a % 5 == 0)
-                    {
-                        //Console.WriteLine(a + " " + Math.Round(a, 1, MidpointRounding.AwayFromZero));
-                        //Console.WriteLine(space +" " + a +" "+ (headbg.Left + 5 + space * (a - start)));
-                        graphicsObject.DrawLine(whitePen, headbg.Left + 5 + space * (a - start), headbg.Bottom - 5, headbg.Left + 5 + space * (a - start), headbg.Bottom - 10);
-                        int disp = (int)a;
-                        if (disp < 0)
-                            disp += 360;
-                        disp = disp % 360;
-                        if (disp == 0)
-                        {
-                            drawstring(graphicsObject, "N".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7));
-                        }
-                        else if (disp == 90)
-                        {
-                            drawstring(graphicsObject, "E".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7));
-                        }
-                        else if (disp == 180)
-                        {
-                            drawstring(graphicsObject, "S".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7));
-                        }
-                        else if (disp == 270)
-                        {
-                            drawstring(graphicsObject, "W".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7));
-                        }
-                        else
-                        {
-                            drawstring(graphicsObject, (disp % 360).ToString().PadLeft(3), font, fontsize, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7));
-                        }
-                    }
-                }
-
-                //                Console.WriteLine("HUD 0 " + (DateTime.Now - starttime).TotalMilliseconds + " " + DateTime.Now.Millisecond);
-
-                // xtrack error
-                // center
-
-                float xtspace = this.Width / 10.0f / 3.0f;
-                int pad = 10;
-
-                float myxtrack_error = _xtrack_error;
-
-                myxtrack_error = Math.Min(myxtrack_error, 40);
-                myxtrack_error = Math.Max(myxtrack_error, -40);
-
-                //  xtrack - distance scale - space
-                float loc = myxtrack_error / 20.0f * xtspace;
-
-                // current xtrack
-                if (Math.Abs(myxtrack_error) == 40)
-                {
-                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
-                }
-
-                graphicsObject.DrawLine(greenPen, this.Width / 10 + loc, headbg.Bottom + 5, this.Width / 10 + loc, headbg.Bottom + this.Height / 10);
-
-                greenPen.Color = Color.FromArgb(255, greenPen.Color);
-
-                graphicsObject.DrawLine(whitePen, this.Width / 10, headbg.Bottom + 5, this.Width / 10, headbg.Bottom + this.Height / 10);
-
-                graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace, headbg.Bottom + 5 + pad, this.Width / 10 - xtspace, headbg.Bottom + this.Height / 10 - pad);
-
-                graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 2, headbg.Bottom + 5 + pad, this.Width / 10 - xtspace * 2, headbg.Bottom + this.Height / 10 - pad);
-
-                graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace, headbg.Bottom + 5 + pad, this.Width / 10 + xtspace, headbg.Bottom + this.Height / 10 - pad);
-
-                graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace * 2, headbg.Bottom + 5 + pad, this.Width / 10 + xtspace * 2, headbg.Bottom + this.Height / 10 - pad);
-
-                // rate of turn
-
-                whitePen.Width = 4;
-                graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 2 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 - xtspace * 2 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10);
-
-                graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 0 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 - xtspace * 0 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10);
-
-                graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace * 2 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 + xtspace * 2 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10);
-
-                float myturnrate = _turnrate;
-                float trwidth = (this.Width / 10 + xtspace * 2 - xtspace / 2) - (this.Width / 10 - xtspace * 2 - xtspace / 2);
-
-                float range = 12;
-
-                myturnrate = Math.Min(myturnrate, range / 2);
-                myturnrate = Math.Max(myturnrate, (range / 2) * -1.0f);
-
-                loc = myturnrate / range * trwidth;
-
-                greenPen.Width = 4;
-
-                if (Math.Abs(myturnrate) == (range / 2))
-                {
-                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
-                }
-
-                graphicsObject.DrawLine(greenPen, this.Width / 10 + loc - xtspace / 2, headbg.Bottom + this.Height / 10 + 10 + 3, this.Width / 10 + loc + xtspace / 2, headbg.Bottom + this.Height / 10 + 10 + 3);
-                graphicsObject.DrawLine(greenPen, this.Width / 10 + loc, headbg.Bottom + this.Height / 10 + 10 + 3, this.Width / 10 + loc, headbg.Bottom + this.Height / 10 + 10 + 10);
-
-                greenPen.Color = Color.FromArgb(255, greenPen.Color);
-
-                whitePen.Width = 2;
-
-
-
-                // left scroller
-
-                Rectangle scrollbg = new Rectangle(0, halfheight - halfheight / 2, this.Width / 10, this.Height / 2);
-
-                graphicsObject.DrawRectangle(whitePen, scrollbg);
-
-                graphicsObject.FillRectangle(solidBrush, scrollbg);
-
-                Point[] arrow = new Point[5];
-
-                arrow[0] = new Point(0, -10);
-                arrow[1] = new Point(scrollbg.Width - 10, -10);
-                arrow[2] = new Point(scrollbg.Width - 5, 0);
-                arrow[3] = new Point(scrollbg.Width - 10, 10);
-                arrow[4] = new Point(0, 10);
-
-                graphicsObject.TranslateTransform(0, this.Height / 2);
-
-                int viewrange = 26;
-
-                float speed = _airspeed;
-                if (speed == 0)
-                    speed = _groundspeed;
-
-                space = (scrollbg.Height) / (float)viewrange;
-                start = ((int)speed - viewrange / 2);
-
-                if (start > _targetspeed)
-                {
-                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
-                    greenPen.Width = 6;
-                    graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top);
-                    greenPen.Color = Color.FromArgb(255, greenPen.Color);
-                }
-                if ((speed + viewrange / 2) < _targetspeed)
-                {
-                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
-                    greenPen.Width = 6;
-                    graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * viewrange, scrollbg.Left + scrollbg.Width, scrollbg.Top - space * viewrange);
-                    greenPen.Color = Color.FromArgb(255, greenPen.Color);
-                }
-
-                for (int a = (int)start; a <= (speed + viewrange / 2); a += 1)
-                {
-                    if (a == (int)_targetspeed && _targetspeed != 0)
-                    {
-                        greenPen.Width = 6;
-                        graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start));
-                    }
-                    if (a % 5 == 0)
-                    {
-                        //Console.WriteLine(a + " " + scrollbg.Right + " " + (scrollbg.Top - space * (a - start)) + " " + (scrollbg.Right - 20) + " " + (scrollbg.Top - space * (a - start)));
-                        graphicsObject.DrawLine(whitePen, scrollbg.Right, scrollbg.Top - space * (a - start), scrollbg.Right - 10, scrollbg.Top - space * (a - start));
-                        drawstring(graphicsObject, a.ToString().PadLeft(5), font, fontsize, whiteBrush, scrollbg.Right - 50 - 4 * fontoffset, scrollbg.Top - space * (a - start) - 6 - fontoffset);
-                    }
-                }
-
-                graphicsObject.DrawPolygon(blackPen, arrow);
-                graphicsObject.FillPolygon(Brushes.Black, arrow);
-                drawstring(graphicsObject, ((int)speed).ToString("0"), font, 10, Brushes.AliceBlue, 0, -9);
-
-                graphicsObject.ResetTransform();
-
-                // extra text data
-
-                drawstring(graphicsObject, "AS " + _airspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + 5);
-                drawstring(graphicsObject, "GS " + _groundspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10);
-
-                //drawstring(e,, new Font("Arial", fontsize + 2), whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10);
-
-                // right scroller
-
-                scrollbg = new Rectangle(this.Width - this.Width / 10, halfheight - halfheight / 2, this.Width / 10, this.Height / 2);
-
-                graphicsObject.DrawRectangle(whitePen, scrollbg);
-
-                graphicsObject.FillRectangle(solidBrush, scrollbg);
-
-                arrow = new Point[5];
-
-                arrow[0] = new Point(0, -10);
-                arrow[1] = new Point(scrollbg.Width - 10, -10);
-                arrow[2] = new Point(scrollbg.Width - 5, 0);
-                arrow[3] = new Point(scrollbg.Width - 10, 10);
-                arrow[4] = new Point(0, 10);
-
-
-
-                graphicsObject.TranslateTransform(0, this.Height / 2);
-
-
-
-
-                viewrange = 26;
-
-                space = (scrollbg.Height) / (float)viewrange;
-                start = ((int)_alt - viewrange / 2);
-
-                if (start > _targetalt)
-                {
-                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
-                    greenPen.Width = 6;
-                    graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top);
-                    greenPen.Color = Color.FromArgb(255, greenPen.Color);
-                }
-                if ((_alt + viewrange / 2) < _targetalt)
-                {
-                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
-                    greenPen.Width = 6;
-                    graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * viewrange, scrollbg.Left + scrollbg.Width, scrollbg.Top - space * viewrange);
-                    greenPen.Color = Color.FromArgb(255, greenPen.Color);
-                }
-
-                for (int a = (int)start; a <= (_alt + viewrange / 2); a += 1)
-                {
-                    if (a == Math.Round(_targetalt) && _targetalt != 0)
-                    {
-                        greenPen.Width = 6;
-                        graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start));
-                    }
-                    if (a % 5 == 0)
-                    {
-                        //Console.WriteLine(a + " " + scrollbg.Left + " " + (scrollbg.Top - space * (a - start)) + " " + (scrollbg.Left + 20) + " " + (scrollbg.Top - space * (a - start)));
-                        graphicsObject.DrawLine(whitePen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + 10, scrollbg.Top - space * (a - start));
-                        drawstring(graphicsObject, a.ToString().PadLeft(5), font, fontsize, whiteBrush, scrollbg.Left + 7 + (int)(0 * fontoffset), scrollbg.Top - space * (a - start) - 6 - fontoffset);
-                    }
-                }
-
-                greenPen.Width = 4;
-
-                // vsi
-
-                graphicsObject.ResetTransform();
-
-                PointF[] poly = new PointF[4];
-
-                poly[0] = new PointF(scrollbg.Left, scrollbg.Top);
-                poly[1] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + scrollbg.Width / 4);
-                poly[2] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Bottom - scrollbg.Width / 4);
-                poly[3] = new PointF(scrollbg.Left, scrollbg.Bottom);
-
-                //verticalspeed
-
-                viewrange = 12;
-
-                _verticalspeed = Math.Min(viewrange / 2, _verticalspeed);
-                _verticalspeed = Math.Max(viewrange / -2, _verticalspeed);
-
-                float scaledvalue = _verticalspeed / -viewrange * (scrollbg.Bottom - scrollbg.Top);
-
-                float linespace = (float)1 / -viewrange * (scrollbg.Bottom - scrollbg.Top);
-
-                PointF[] polyn = new PointF[4];
-
-                polyn[0] = new PointF(scrollbg.Left, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2);
-                polyn[1] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2);
-                polyn[2] = polyn[1];
-                float peak = 0;
-                if (scaledvalue > 0)
-                {
-                    peak = -scrollbg.Width / 4;
-                    if (scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak < scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2)
-                        peak = -scaledvalue;
-                }
-                else if (scaledvalue < 0)
-                {
-                    peak = +scrollbg.Width / 4;
-                    if (scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak > scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2)
-                        peak = -scaledvalue;
-                }
-                
-                polyn[2] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak);
-                polyn[3] = new PointF(scrollbg.Left, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue);
-
-                //graphicsObject.DrawPolygon(redPen, poly);
-                graphicsObject.FillPolygon(Brushes.Blue, polyn);
-
-                // draw outsidebox
-                graphicsObject.DrawPolygon(whitePen, poly);
-
-                for (int a = 1; a < viewrange; a++)
-                {
-                    graphicsObject.DrawLine(whitePen, scrollbg.Left - scrollbg.Width / 4, scrollbg.Top - linespace * a, scrollbg.Left - scrollbg.Width / 8, scrollbg.Top - linespace * a);
-                }
-
-                // draw arrow and text
-                
-                graphicsObject.ResetTransform();
-                graphicsObject.TranslateTransform(this.Width, this.Height / 2);
-                graphicsObject.RotateTransform(180);
-
-                graphicsObject.DrawPolygon(blackPen, arrow);
-                graphicsObject.FillPolygon(Brushes.Black, arrow);
-                graphicsObject.ResetTransform();
-                graphicsObject.TranslateTransform(0, this.Height / 2);
-
-                drawstring(graphicsObject, ((int)_alt).ToString("0"), font, 10, Brushes.AliceBlue, scrollbg.Left + 10, -9);
-                graphicsObject.ResetTransform();
-
-                // mode and wp dist and wp
-
-                drawstring(graphicsObject, _mode, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + 5);
-                drawstring(graphicsObject, (int)_disttowp + ">" + _wpno, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + fontsize + 2 + 10);
-
-                graphicsObject.DrawLine(greenPen, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize) - 2 - 20);
-                graphicsObject.DrawLine(greenPen, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 15, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize) - 2 - 20);
-                graphicsObject.DrawLine(greenPen, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 10, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize ) - 2 - 20);
-
-                drawstring(graphicsObject, _linkqualitygcs.ToString("0") + "%", font, fontsize, whiteBrush, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20);
-                if (_linkqualitygcs == 0)
-                {
-                    graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2);
-
-                    graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20);
-                }
-                drawstring(graphicsObject, _datetime.ToString("HH:mm:ss"), font, fontsize, whiteBrush, scrollbg.Left - 20, scrollbg.Top - fontsize - 2 - 20);
-
-
-                // battery
-
-                graphicsObject.ResetTransform();
-
-                drawstring(graphicsObject, "Bat", font, fontsize + 2, whiteBrush, fontsize, this.Height - 30 - fontoffset);
-                drawstring(graphicsObject, _batterylevel.ToString("0.00v"), font, fontsize + 2, whiteBrush, fontsize * 4, this.Height - 30 - fontoffset);
-                drawstring(graphicsObject, _batteryremaining.ToString("0%"), font, fontsize + 2, whiteBrush, fontsize * 9, this.Height - 30 - fontoffset);
-
-                // gps
-
-                string gps = "";
-
-                if (_gpsfix == 0)
-                {
-                    gps = ("GPS: No GPS");
-                }
-                else if (_gpsfix == 1)
-                {
-                    gps = ("GPS: No Fix");
-                }
-                else if (_gpsfix == 2)
-                {
-                    gps = ("GPS: 3D Fix");
-                }
-                else if (_gpsfix == 3)
-                {
-                    gps = ("GPS: 3D Fix");
-                }
-
-                drawstring(graphicsObject, gps, font, fontsize + 2, whiteBrush, this.Width - 10 * fontsize, this.Height - 30 - fontoffset);
-
-
-                if (isNaN)
-                    drawstring(graphicsObject, "NaN Error " + DateTime.Now, font, this.Height / 30 + 10, Brushes.Red, 50, 50);
-
-
-                if (!opengl)
-                {
-                    e.Graphics.DrawImageUnscaled(objBitmap, 0, 0);
-                }
-
-                if (DesignMode)
-                {
-                    return;
-                }
-
-                //                Console.WriteLine("HUD 1 " + (DateTime.Now - starttime).TotalMilliseconds + " " + DateTime.Now.Millisecond);
-
-                ImageCodecInfo ici = GetImageCodec("image/jpeg");
-                EncoderParameters eps = new EncoderParameters(1);
-                eps.Param[0] = new EncoderParameter(System.Drawing.Imaging.Encoder.Quality, 50L); // or whatever other quality value you want
-
-                lock (streamlock)
-                {
-                    if (streamjpgenable || streamjpg == null) // init image and only update when needed
-                    {
-                        if (opengl)
-                        {
-                            objBitmap = GrabScreenshot();
-                        }
-                        streamjpg = new MemoryStream();
-                        objBitmap.Save(streamjpg, ici, eps);
-                        //objBitmap.Save(streamjpg,ImageFormat.Bmp);
-                    }
-                }
-            }
-            catch (Exception ex)
-            {
-                log.Info("hud error "+ex.ToString());
-            }
-        }
-
-        protected override void OnPaintBackground(PaintEventArgs e)
-        {
-            //base.OnPaintBackground(e);
-        }
-
-        ImageCodecInfo GetImageCodec(string mimetype)
-        {
-            foreach (ImageCodecInfo ici in ImageCodecInfo.GetImageEncoders())
-            {
-                if (ici.MimeType == mimetype) return ici;
-            }
-            return null;
-        }
-
-        // Returns a System.Drawing.Bitmap with the contents of the current framebuffer
-        public new Bitmap GrabScreenshot()
-        {
-            if (GraphicsContext.CurrentContext == null)
-                throw new GraphicsContextMissingException();
-
-            Bitmap bmp = new Bitmap(this.ClientSize.Width, this.ClientSize.Height);
-            System.Drawing.Imaging.BitmapData data =
-                bmp.LockBits(this.ClientRectangle, System.Drawing.Imaging.ImageLockMode.WriteOnly, System.Drawing.Imaging.PixelFormat.Format24bppRgb);
-            GL.ReadPixels(0, 0, this.ClientSize.Width, this.ClientSize.Height,OpenTK.Graphics.OpenGL.PixelFormat.Bgr, PixelType.UnsignedByte, data.Scan0);
-            bmp.UnlockBits(data);
-
-            bmp.RotateFlip(RotateFlipType.RotateNoneFlipY);
-            return bmp;
-        }
-
-
-        float wrap360(float noin)
-        {
-            if (noin < 0)
-                return noin + 360;
-            return noin;
-        }
-
-        /// <summary>
-        /// pen for drawstring
-        /// </summary>
-        Pen P = new Pen(Color.FromArgb(0x26, 0x27, 0x28), 2f);
-        /// <summary>
-        /// pth for drawstring
-        /// </summary>
-        GraphicsPath pth = new GraphicsPath();
-
-        void drawstring(HUD e, string text, Font font, float fontsize, Brush brush, float x, float y)
-        {
-            if (!opengl)
-            {
-                drawstring(graphicsObjectGDIP, text, font, fontsize, brush, x, y);
-                return;
-            }
-
-            if (text == null || text == "")
-                return;
-            /*
-            OpenTK.Graphics.Begin(); 
-            GL.PushMatrix(); 
-            GL.Translate(x, y, 0);
-            printer.Print(text, font, c); 
-            GL.PopMatrix(); printer.End();
-            */
-
-            char[] chars = text.ToCharArray();
-
-            float maxy = 1;
-
-            foreach (char cha in chars)
-            {
-                int charno = (int)cha;
-
-                int charid = charno  + (128 * (int)fontsize); // 128 * 40 * 5;128
-
-                if (charbitmaps[charid] == null)
-                {
-                    charbitmaps[charid] = new Bitmap(128, 128, System.Drawing.Imaging.PixelFormat.Format32bppArgb);
-
-                    charbitmaps[charid].MakeTransparent(Color.Transparent);
-
-                    //charbitmaptexid
-
-                    float maxx = this.Width / 150; // for space
-
-
-                    // create bitmap
-                    using (Graphics gfx = Graphics.FromImage(charbitmaps[charid]))
-                    {
-                        pth.Reset();
-
-                        if (text != null)
-                            pth.AddString(cha + "", font.FontFamily, 0, fontsize + 5, new Point((int)0, (int)0), StringFormat.GenericTypographic);
-
-                        gfx.SmoothingMode = System.Drawing.Drawing2D.SmoothingMode.AntiAlias;
-
-                        gfx.DrawPath(P, pth);
-
-                        //Draw the face
-
-                        gfx.FillPath(brush, pth);
-
-
-                        if (pth.PointCount > 0)
-                        {
-                            foreach (PointF pnt in pth.PathPoints)
-                            {
-                                if (pnt.X > maxx)
-                                    maxx = pnt.X;
-
-                                if (pnt.Y > maxy)
-                                    maxy = pnt.Y;
-                            }
-                        }
-                    }
-
-                    charwidth[charid] = (int)(maxx + 2);
-
-                    //charbitmaps[charid] = charbitmaps[charid].Clone(new RectangleF(0, 0, maxx + 2, maxy + 2), charbitmaps[charid].PixelFormat);
-
-                    //charbitmaps[charno * (int)fontsize].Save(charno + " " + (int)fontsize + ".png");
-
-                    // create texture
-                    int textureId;
-                    GL.TexEnv(TextureEnvTarget.TextureEnv, TextureEnvParameter.TextureEnvMode, (float)TextureEnvModeCombine.Replace);//Important, or wrong color on some computers
-
-                    Bitmap bitmap = charbitmaps[charid];
-                    GL.GenTextures(1, out textureId);
-                    GL.BindTexture(TextureTarget.Texture2D, textureId);
-
-                    BitmapData data = bitmap.LockBits(new System.Drawing.Rectangle(0, 0, bitmap.Width, bitmap.Height), ImageLockMode.ReadOnly, System.Drawing.Imaging.PixelFormat.Format32bppArgb);
-
-                    GL.TexImage2D(TextureTarget.Texture2D, 0, PixelInternalFormat.Rgba, data.Width, data.Height, 0, OpenTK.Graphics.OpenGL.PixelFormat.Bgra, PixelType.UnsignedByte, data.Scan0);
-
-                    GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear);
-                    GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)TextureMagFilter.Linear);
-
-                    //    GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)All.Nearest);
-                    //GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)All.Nearest);
-                    GL.Finish();
-                    bitmap.UnlockBits(data);
-
-                    charbitmaptexid[charid] = textureId;
-                }
-
-                //GL.Enable(EnableCap.Blend);
-                GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha);
-
-                GL.Enable(EnableCap.Texture2D);
-                GL.BindTexture(TextureTarget.Texture2D, charbitmaptexid[charid]);
-
-                float scale = 1.0f;
-
-                GL.Begin(BeginMode.Quads);
-                GL.TexCoord2(0, 0); GL.Vertex2(x, y);
-                GL.TexCoord2(1, 0); GL.Vertex2(x + charbitmaps[charid].Width * scale, y);
-                GL.TexCoord2(1, 1); GL.Vertex2(x + charbitmaps[charid].Width * scale, y + charbitmaps[charid].Height * scale);
-                GL.TexCoord2(0, 1); GL.Vertex2(x + 0, y + charbitmaps[charid].Height * scale);
-                GL.End();
-
-                //GL.Disable(EnableCap.Blend);
-                GL.Disable(EnableCap.Texture2D);
-
-                x += charwidth[charid] * scale;
-            }
-        }
-		
-		void drawstring(Graphics e, string text, Font font, float fontsize, Brush brush, float x, float y)
-        {
-            if (text == null || text == "")
-                return;
-
-            pth.Reset();
-            
-            if (text != null)
-                pth.AddString(text, font.FontFamily, 0, fontsize + 5, new Point((int)x, (int)y), StringFormat.GenericTypographic);
-
-            //Draw the edge
-            // this uses lots of cpu time
-
-            //e.SmoothingMode = SmoothingMode.HighSpeed;
-
-            if (e == null || P == null || pth == null || pth.PointCount == 0)
-                return;
-            
-            //if (!ArdupilotMega.MainV2.MONO)
-                e.DrawPath(P, pth);
-
-            //Draw the face
-
-            e.FillPath(brush, pth);
-
-            //pth.Dispose();
-        }
-
-        protected override void OnHandleCreated(EventArgs e)
-        {
-            try
-            {
-                if (opengl)
-                {
-                    base.OnHandleCreated(e);
-                }
-            }
-            catch (Exception ex) { log.Info(ex.ToString()); opengl = false; } // macs fail here
-        }
-
-        protected override void OnHandleDestroyed(EventArgs e)
-        {
-            try
-            {
-                if (opengl)
-                {
-                    base.OnHandleDestroyed(e);
-                }
-            }
-            catch (Exception ex) { log.Info(ex.ToString()); opengl = false; }
-        }
-
-        protected override void OnResize(EventArgs e)
-        {
-            if (DesignMode || !started)
-                return;
-
-           
-            if (SixteenXNine)
-            {
-                this.Height = (int)(this.Width / 1.777f);
-            }
-            else
-            {
-                // 4x3
-                this.Height = (int)(this.Width / 1.333f);
-            }
-
-            base.OnResize(e);
-
-            graphicsObjectGDIP = Graphics.FromImage(objBitmap);
-
-            charbitmaps = new Bitmap[charbitmaps.Length];
-
-            try
-            {
-                if (opengl)
-                {
-                    foreach (int texid in charbitmaptexid)
-                    {
-                        if (texid != 0)
-                            GL.DeleteTexture(texid);
-                    }
-                }
-            }
-            catch { }
-
-            GC.Collect();
-            
-            try
-            {
-                if (opengl)
-                {
-                    GL.MatrixMode(MatrixMode.Projection);
-                    GL.LoadIdentity();
-                    GL.Ortho(0, Width, Height, 0, -1, 1);
-                    GL.MatrixMode(MatrixMode.Modelview);
-                    GL.LoadIdentity();
-
-                    GL.Viewport(0, 0, Width, Height);
-                }
-            }
-            catch { }
-             
-        }
-    }
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Text;
+using System.Windows.Forms;
+using System.IO;
+using System.Drawing.Imaging;
+
+using System.Threading;
+ 
+using System.Drawing.Drawing2D;
+using log4net;
+using OpenTK;
+using OpenTK.Graphics.OpenGL;
+using OpenTK.Graphics;
+
+
+// Control written by Michael Oborne 2011
+// dual opengl and GDI+
+
+namespace ArdupilotMega.Controls
+{
+    public class HUD : GLControl
+    {
+        private static readonly ILog log = LogManager.GetLogger(
+  System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
+        object paintlock = new object();
+        object streamlock = new object();
+        MemoryStream _streamjpg = new MemoryStream();
+        [System.ComponentModel.Browsable(false)]
+        public MemoryStream streamjpg { get { lock (streamlock) { return _streamjpg; } } set { lock (streamlock) { _streamjpg = value; } } }
+        /// <summary>
+        /// this is to reduce cpu usage
+        /// </summary>
+        public bool streamjpgenable = false;
+
+        Bitmap[] charbitmaps = new Bitmap[6000];
+        int[] charbitmaptexid = new int[6000];
+        int[] charwidth = new int[6000];
+
+        public int huddrawtime = 0;
+
+        public bool opengl { get { return base.UseOpenGL; } set { base.UseOpenGL = value; } }
+
+        bool started = false;
+
+        public bool SixteenXNine = false;
+
+        public HUD()
+        {
+            if (this.DesignMode)
+            {
+                opengl = false;
+                //return;
+            }
+
+            //InitializeComponent();
+
+            graphicsObject = this;
+            graphicsObjectGDIP = Graphics.FromImage(objBitmap);
+        }
+        /*
+        private void InitializeComponent()
+        {
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(HUD));
+            this.SuspendLayout();
+            // 
+            // HUD
+            // 
+            this.BackColor = System.Drawing.Color.Black;
+            this.Name = "HUD";
+            resources.ApplyResources(this, "$this");
+            this.ResumeLayout(false);
+
+        }*/
+
+        float _roll = 0;
+        float _navroll = 0;
+        float _pitch = 0;
+        float _navpitch = 0;
+        float _heading = 0;
+        float _targetheading = 0;
+        float _alt = 0;
+        float _targetalt = 0;
+        float _groundspeed = 0;
+        float _airspeed = 0;
+        float _targetspeed = 0;
+        float _batterylevel = 0;
+        float _batteryremaining = 0;
+        float _gpsfix = 0;
+        float _gpshdop = 0;
+        float _disttowp = 0;
+        float _groundcourse = 0;
+        float _xtrack_error = 0;
+        float _turnrate = 0;
+        float _verticalspeed = 0;
+        float _linkqualitygcs = 0;
+        DateTime _datetime;
+        string _mode = "Manual";
+        int _wpno = 0;
+        
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float roll { get { return _roll; } set { if (_roll != value) { _roll = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float navroll { get { return _navroll; } set { if (_navroll != value) { _navroll = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float pitch { get { return _pitch; } set { if (_pitch != value) { _pitch = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float navpitch { get { return _navpitch; } set { if (_navpitch != value) { _navpitch = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float heading { get { return _heading; } set { if (_heading != value) { _heading = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float targetheading { get { return _targetheading; } set { if (_targetheading != value) { _targetheading = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float alt { get { return _alt; } set { if (_alt != value) { _alt = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float targetalt { get { return _targetalt; } set { if (_targetalt != value) { _targetalt = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float groundspeed { get { return _groundspeed; } set { if (_groundspeed != value) { _groundspeed = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float airspeed { get { return _airspeed; } set { if (_airspeed != value) { _airspeed = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float targetspeed { get { return _targetspeed; } set { if (_targetspeed != value) { _targetspeed = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float batterylevel { get { return _batterylevel; } set { if (_batterylevel != value) { _batterylevel = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float batteryremaining { get { return _batteryremaining; } set { if (_batteryremaining != value) { _batteryremaining = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float gpsfix { get { return _gpsfix; } set { if (_gpsfix != value) { _gpsfix = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float gpshdop { get { return _gpshdop; } set { if (_gpshdop != value) { _gpshdop = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float disttowp { get { return _disttowp; } set { if (_disttowp != value) { _disttowp = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public string mode { get { return _mode; } set { if (_mode != value) { _mode = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public int wpno { get { return _wpno; } set { if (_wpno != value) { _wpno = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float groundcourse { get { return _groundcourse; } set { if (_groundcourse != value) { _groundcourse = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float xtrack_error { get { return _xtrack_error; } set { if (_xtrack_error != value) { _xtrack_error = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float turnrate { get { return _turnrate; } set { if (_turnrate != value) { _turnrate = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float verticalspeed { get { return _verticalspeed; } set { if (_verticalspeed != value) { _verticalspeed = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public float linkqualitygcs { get { return _linkqualitygcs; } set { if (_linkqualitygcs != value) { _linkqualitygcs = value; this.Invalidate(); } } }
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public DateTime datetime { get { return _datetime; } set { if (_datetime != value) { _datetime = value; this.Invalidate(); } } }
+
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public int status { get; set; }
+        
+        int statuslast = 0;
+        DateTime armedtimer = DateTime.MinValue;
+
+        public bool bgon = true;
+        public bool hudon = true;
+
+        [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
+        public Color hudcolor { get { return whitePen.Color; } set { whitePen = new Pen(value, 2); } }
+
+        Pen whitePen = new Pen(Color.White, 2);
+
+        public Image bgimage { set { _bgimage = value; this.Invalidate(); } }
+        Image _bgimage;
+
+        // move these global as they rarely change - reduce GC
+        Font font = new Font("Arial", 10);
+        Bitmap objBitmap = new Bitmap(1024, 1024);
+        int count = 0;
+        DateTime countdate = DateTime.Now;
+        HUD graphicsObject;
+        Graphics graphicsObjectGDIP;
+
+        DateTime starttime = DateTime.MinValue;
+
+        System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(HUD));
+
+        public override void Refresh()
+        {
+            //base.Refresh();
+            OnPaint(new PaintEventArgs(this.CreateGraphics(),this.ClientRectangle));
+        }
+
+        protected override void OnLoad(EventArgs e)
+        {
+            if (opengl)
+            {
+                try
+                {
+
+                    GraphicsMode test = this.GraphicsMode;
+                    log.Info(test.ToString());
+                    log.Info("Vendor: " + GL.GetString(StringName.Vendor));
+                    log.Info("Version: " + GL.GetString(StringName.Version));
+                    log.Info("Device: " + GL.GetString(StringName.Renderer));
+                    //Console.WriteLine("Extensions: " + GL.GetString(StringName.Extensions));
+
+                    int[] viewPort = new int[4];
+
+                    GL.GetInteger(GetPName.Viewport, viewPort);
+
+                    GL.MatrixMode(MatrixMode.Projection);
+                    GL.LoadIdentity();
+                    GL.Ortho(0, Width, Height, 0, -1, 1);
+                    GL.MatrixMode(MatrixMode.Modelview);
+                    GL.LoadIdentity();
+
+                    GL.PushAttrib(AttribMask.DepthBufferBit);
+                    GL.Disable(EnableCap.DepthTest);
+                    //GL.Enable(EnableCap.Texture2D); 
+                    GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha);
+                    GL.Enable(EnableCap.Blend);
+
+                }
+                catch (Exception ex) { log.Info("HUD opengl onload " + ex.ToString()); }
+
+                try
+                {
+                    GL.Hint(HintTarget.PerspectiveCorrectionHint, HintMode.Nicest);
+
+                    GL.Hint(HintTarget.LineSmoothHint, HintMode.Nicest);
+                    GL.Hint(HintTarget.PolygonSmoothHint, HintMode.Nicest);
+                    GL.Hint(HintTarget.PointSmoothHint, HintMode.Nicest);
+
+                    GL.Hint(HintTarget.TextureCompressionHint, HintMode.Nicest);
+                }
+                catch { }
+
+                try
+                {
+
+                    GL.Enable(EnableCap.LineSmooth);
+                    GL.Enable(EnableCap.PointSmooth);
+                    GL.Enable(EnableCap.PolygonSmooth);
+
+                }
+                catch { }
+            }
+
+            started = true;
+        }
+
+        bool inOnPaint = false;
+        string otherthread = "";
+
+        protected override void OnPaint(PaintEventArgs e)
+        {
+            //GL.Enable(EnableCap.AlphaTest)
+
+            if (!started)
+                return;
+
+            if (this.DesignMode)
+            {
+                e.Graphics.Clear(this.BackColor);
+                e.Graphics.Flush();
+            }
+
+            if ((DateTime.Now - starttime).TotalMilliseconds < 30 && (_bgimage == null))
+            {
+                //Console.WriteLine("ms "+(DateTime.Now - starttime).TotalMilliseconds);
+                //e.Graphics.DrawImageUnscaled(objBitmap, 0, 0);          
+                return;              
+            }
+
+            if (inOnPaint)
+            {
+                log.Info("Was in onpaint Hud th:" + System.Threading.Thread.CurrentThread.Name + " in " + otherthread);
+                return;
+            }
+
+            otherthread = System.Threading.Thread.CurrentThread.Name;
+
+            inOnPaint = true;
+
+            starttime = DateTime.Now;
+
+            try
+            {
+
+                if (opengl)
+                {
+                    MakeCurrent();
+
+                    GL.Clear(ClearBufferMask.ColorBufferBit);
+
+                }
+
+                doPaint(e);
+
+                if (opengl)
+                {
+                    this.SwapBuffers();
+                }
+
+            }
+            catch (Exception ex) { log.Info(ex.ToString()); }
+
+            inOnPaint = false;
+
+            count++;
+
+            huddrawtime += (int)(DateTime.Now - starttime).TotalMilliseconds;
+
+            if (DateTime.Now.Second != countdate.Second)
+            {
+                countdate = DateTime.Now;
+               // Console.WriteLine("HUD " + count + " hz drawtime " + (huddrawtime / count) + " gl " + opengl);
+                if ((huddrawtime / count) > 1000)
+                    opengl = false;
+
+                count = 0;
+                huddrawtime = 0;
+            }
+        }
+
+        void Clear(Color color)
+        {
+            if (opengl)
+            {
+                GL.ClearColor(color);
+            } else 
+            {
+                graphicsObjectGDIP.Clear(color);
+            }
+        }
+
+        const float rad2deg = (float)(180 / Math.PI);
+        const float deg2rad = (float)(1.0 / rad2deg);
+
+        public void DrawArc(Pen penn,RectangleF rect, float start,float degrees)
+        {
+            if (opengl)
+            {
+                GL.LineWidth(penn.Width);
+                GL.Color4(penn.Color);
+
+                GL.Begin(BeginMode.LineStrip);
+                start -= 90;
+                float x = 0, y = 0;
+                for (int i = (int)start; i <= start + degrees; i++)
+                {
+                    x = (float)Math.Sin(i * deg2rad) * rect.Width / 2;
+                    y = (float)Math.Cos(i * deg2rad) * rect.Height / 2;
+                    x = x + rect.X + rect.Width / 2;
+                    y = y + rect.Y + rect.Height / 2;
+                    GL.Vertex2(x, y);
+                }
+                GL.End();
+            }
+            else
+            {
+                graphicsObjectGDIP.DrawArc(penn, rect, start, degrees);
+            }
+        }
+
+        public void DrawEllipse(Pen penn, Rectangle rect)
+        {
+            if (opengl)
+            {
+                GL.LineWidth(penn.Width);
+                GL.Color4(penn.Color);
+
+                GL.Begin(BeginMode.LineLoop);
+                float x, y;
+                for (float i = 0; i < 360; i += 1)
+                {
+                    x = (float)Math.Sin(i * deg2rad) * rect.Width / 2;
+                    y = (float)Math.Cos(i * deg2rad) * rect.Height / 2;
+                    x = x + rect.X + rect.Width / 2;
+                    y = y + rect.Y + rect.Height / 2;
+                    GL.Vertex2(x, y);
+                }
+                GL.End();
+            }
+            else
+            {
+                graphicsObjectGDIP.DrawEllipse(penn, rect);
+            }
+        }
+
+        int texture;
+        Bitmap bitmap = new Bitmap(512,512);
+
+        public void DrawImage(Image img, int x, int y, int width, int height)
+        {
+            if (opengl)
+            {
+                if (img == null)
+                    return;
+                //bitmap = new Bitmap(512,512);
+
+                using (Graphics graphics = Graphics.FromImage(bitmap))
+                {
+                    graphics.CompositingQuality = System.Drawing.Drawing2D.CompositingQuality.HighSpeed;
+                    graphics.InterpolationMode = System.Drawing.Drawing2D.InterpolationMode.NearestNeighbor;
+                    graphics.SmoothingMode = System.Drawing.Drawing2D.SmoothingMode.HighSpeed;
+                    //draw the image into the target bitmap 
+                    graphics.DrawImage(img, 0, 0, bitmap.Width, bitmap.Height);
+                }
+
+
+                GL.DeleteTexture(texture);
+
+                GL.GenTextures(1, out texture);
+                GL.BindTexture(TextureTarget.Texture2D, texture);
+
+                BitmapData data = bitmap.LockBits(new System.Drawing.Rectangle(0, 0, bitmap.Width, bitmap.Height),
+        ImageLockMode.ReadOnly, System.Drawing.Imaging.PixelFormat.Format32bppArgb);
+
+                //Console.WriteLine("w {0} h {1}",data.Width, data.Height);
+
+                GL.TexImage2D(TextureTarget.Texture2D, 0, PixelInternalFormat.Rgba, data.Width, data.Height, 0,
+                    OpenTK.Graphics.OpenGL.PixelFormat.Bgra, PixelType.UnsignedByte, data.Scan0);
+
+                bitmap.UnlockBits(data);
+
+                GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear);
+                GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)TextureMagFilter.Linear);
+
+                GL.Enable(EnableCap.Texture2D);
+
+                GL.BindTexture(TextureTarget.Texture2D, texture);
+
+                GL.Begin(BeginMode.Quads);
+
+                GL.TexCoord2(0.0f, 1.0f); GL.Vertex2(0, this.Height);
+                GL.TexCoord2(1.0f, 1.0f); GL.Vertex2(this.Width, this.Height);
+                GL.TexCoord2(1.0f, 0.0f); GL.Vertex2(this.Width, 0);
+                GL.TexCoord2(0.0f, 0.0f); GL.Vertex2(0, 0);
+
+                GL.End();
+
+                GL.Disable(EnableCap.Texture2D);
+            }
+            else
+            {
+                graphicsObjectGDIP.DrawImage(img,x,y,width,height);
+            }
+        }
+
+        public void DrawPath(Pen penn, GraphicsPath gp)
+        {
+            try
+            {
+               DrawPolygon(penn, gp.PathPoints);
+            }
+            catch { }
+        }
+
+        public void FillPath(Brush brushh, GraphicsPath gp)
+        {
+            try
+            {
+                FillPolygon(brushh, gp.PathPoints);
+            }
+            catch { }
+        }
+
+        public void SetClip(Rectangle rect)
+        {
+            
+        }
+
+        public void ResetClip()
+        {
+
+        }
+
+        public void ResetTransform()
+        {
+            if (opengl)
+            {
+                GL.LoadIdentity();
+            }
+            else
+            {
+                graphicsObjectGDIP.ResetTransform();
+            }
+        }
+
+        public void RotateTransform(float angle)
+        {
+            if (opengl)
+            {
+                GL.Rotate(angle, 0, 0, 1);
+            }
+            else
+            {
+                graphicsObjectGDIP.RotateTransform(angle);
+            }
+        }
+
+        public void TranslateTransform(float x, float y)
+        {
+            if (opengl)
+            {
+                GL.Translate(x, y, 0f);
+            }
+            else
+            {
+                graphicsObjectGDIP.TranslateTransform(x, y);
+            }
+        }
+
+        public void FillPolygon(Brush brushh, Point[] list)
+        {
+            if (opengl)
+            {
+                GL.Begin(BeginMode.TriangleFan);
+                GL.Color4(((SolidBrush)brushh).Color);
+                foreach (Point pnt in list)
+                {
+                    GL.Vertex2(pnt.X, pnt.Y);
+                }
+                GL.Vertex2(list[list.Length - 1].X, list[list.Length - 1].Y);
+                GL.End();
+            }
+            else
+            {
+                graphicsObjectGDIP.FillPolygon(brushh, list);
+            }
+        }
+
+        public void FillPolygon(Brush brushh, PointF[] list)
+        {
+            if (opengl)
+            {
+                GL.Begin(BeginMode.Quads);
+                GL.Color4(((SolidBrush)brushh).Color);
+                foreach (PointF pnt in list)
+                {
+                    GL.Vertex2(pnt.X, pnt.Y);
+                }
+                GL.Vertex2(list[0].X, list[0].Y);
+                GL.End();
+            }
+            else
+            {
+                graphicsObjectGDIP.FillPolygon(brushh, list);
+            }
+        }
+
+        public void DrawPolygon(Pen penn, Point[] list)
+        {
+            if (opengl)
+            {
+                GL.LineWidth(penn.Width);
+                GL.Color4(penn.Color);
+
+                GL.Begin(BeginMode.LineLoop);
+                foreach (Point pnt in list)
+                {
+                    GL.Vertex2(pnt.X, pnt.Y);
+                }
+                GL.End();
+            }
+            else
+            {
+                graphicsObjectGDIP.DrawPolygon(penn, list);
+            }                       
+        }
+
+        public void DrawPolygon(Pen penn, PointF[] list)
+        {         
+            if (opengl)
+            {
+            GL.LineWidth(penn.Width);
+            GL.Color4(penn.Color);
+
+            GL.Begin(BeginMode.LineLoop);
+            foreach (PointF pnt in list)
+            {
+                GL.Vertex2(pnt.X, pnt.Y);
+            }
+
+            GL.End();
+            }
+            else
+            {
+                graphicsObjectGDIP.DrawPolygon(penn, list);
+            } 
+        }
+
+
+        public void FillRectangle(Brush brushh, RectangleF rectf)
+        {
+            if (opengl)
+            {
+                float x1 = rectf.X;
+                float y1 = rectf.Y;
+
+                float width = rectf.Width;
+                float height = rectf.Height;
+
+                GL.Begin(BeginMode.Quads);
+
+                if (((Type)brushh.GetType()) == typeof(LinearGradientBrush))
+                {
+                    LinearGradientBrush temp = (LinearGradientBrush)brushh;
+                    GL.Color4(temp.LinearColors[0]);
+                }
+                else
+                {
+                    GL.Color4(((SolidBrush)brushh).Color.R / 255f, ((SolidBrush)brushh).Color.G / 255f, ((SolidBrush)brushh).Color.B / 255f, ((SolidBrush)brushh).Color.A / 255f);
+                }
+
+                GL.Vertex2(x1, y1);
+                GL.Vertex2(x1 + width, y1);
+
+                if (((Type)brushh.GetType()) == typeof(LinearGradientBrush))
+                {
+                    LinearGradientBrush temp = (LinearGradientBrush)brushh;
+                    GL.Color4(temp.LinearColors[1]);
+                }
+                else
+                {
+                    GL.Color4(((SolidBrush)brushh).Color.R / 255f, ((SolidBrush)brushh).Color.G / 255f, ((SolidBrush)brushh).Color.B / 255f, ((SolidBrush)brushh).Color.A / 255f);
+                }
+
+                GL.Vertex2(x1 + width, y1 + height);
+                GL.Vertex2(x1, y1 + height);
+                GL.End();
+            }
+            else
+            {
+                graphicsObjectGDIP.FillRectangle(brushh, rectf);
+            }
+        }
+
+        public void DrawRectangle(Pen penn, RectangleF rect)
+        {
+            DrawRectangle(penn, rect.X, rect.Y, rect.Width, rect.Height);
+        }
+
+        public void DrawRectangle(Pen penn, double x1, double y1, double width, double height)
+        {
+
+            if (opengl)
+            {
+                GL.LineWidth(penn.Width);
+                GL.Color4(penn.Color);
+
+                GL.Begin(BeginMode.LineLoop);
+                GL.Vertex2(x1, y1);
+                GL.Vertex2(x1 + width, y1);
+                GL.Vertex2(x1 + width, y1 + height);
+                GL.Vertex2(x1, y1 + height);
+                GL.End();
+            }
+            else
+            {
+                graphicsObjectGDIP.DrawRectangle(penn, (float)x1, (float)y1, (float)width, (float)height);
+            }
+        }
+
+        public void DrawLine(Pen penn, double x1, double y1, double x2, double y2)
+        {
+
+            if (opengl)
+            {
+                GL.Color4(penn.Color);
+                GL.LineWidth(penn.Width);
+
+                GL.Begin(BeginMode.Lines);
+                GL.Vertex2(x1, y1);
+                GL.Vertex2(x2, y2);
+                GL.End();
+            }
+            else
+            {
+                graphicsObjectGDIP.DrawLine(penn, (float)x1, (float)y1, (float)x2, (float)y2);
+            }
+        }
+
+        void doPaint(PaintEventArgs e)
+        {
+            bool isNaN = false;
+            try
+            {
+                if (graphicsObjectGDIP == null || !opengl && (objBitmap.Width != this.Width || objBitmap.Height != this.Height))
+                {
+                    objBitmap = new Bitmap(this.Width, this.Height);
+                    graphicsObjectGDIP = Graphics.FromImage(objBitmap);
+
+                    graphicsObjectGDIP.SmoothingMode = SmoothingMode.AntiAlias;
+                    graphicsObjectGDIP.InterpolationMode = InterpolationMode.NearestNeighbor;
+                    graphicsObjectGDIP.CompositingMode = CompositingMode.SourceOver;
+                    graphicsObjectGDIP.CompositingQuality = CompositingQuality.HighSpeed;
+                    graphicsObjectGDIP.PixelOffsetMode = PixelOffsetMode.HighSpeed;
+                    graphicsObjectGDIP.TextRenderingHint = System.Drawing.Text.TextRenderingHint.SystemDefault;
+                }
+
+
+                graphicsObject.Clear(Color.Gray);
+
+                if (_bgimage != null)
+                {
+                    bgon = false;
+                    graphicsObject.DrawImage(_bgimage, 0, 0, this.Width, this.Height);
+
+                    if (hudon == false)
+                    {
+                        return;
+                    }
+                }
+                else
+                {
+                    bgon = true;
+                }
+
+
+                if (float.IsNaN(_roll) || float.IsNaN(_pitch) || float.IsNaN(_heading))
+                {
+                    isNaN = true;
+
+                    _roll = 0;
+                    _pitch = 0;
+                    _heading = 0;
+                }
+
+                graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2);
+
+
+
+                    graphicsObject.RotateTransform(-_roll);
+
+
+                int fontsize = this.Height / 30; // = 10
+                int fontoffset = fontsize - 10;
+
+                float every5deg = -this.Height / 60;
+
+                float pitchoffset = -_pitch * every5deg;
+
+                int halfwidth = this.Width / 2;
+                int halfheight = this.Height / 2;
+
+                SolidBrush whiteBrush = new SolidBrush(whitePen.Color);
+
+                Pen blackPen = new Pen(Color.Black, 2);
+                Pen greenPen = new Pen(Color.Green, 2);
+                Pen redPen = new Pen(Color.Red, 2);
+
+                // draw sky
+                if (bgon == true)
+                {
+                    RectangleF bg = new RectangleF(-halfwidth * 2, -halfheight * 2, this.Width * 2, halfheight * 2 + pitchoffset);
+
+                    if (bg.Height != 0)
+                    {
+                        LinearGradientBrush linearBrush = new LinearGradientBrush(bg, Color.Blue,
+                            Color.LightBlue, LinearGradientMode.Vertical);
+
+                        graphicsObject.FillRectangle(linearBrush, bg);
+                    }
+                    // draw ground
+
+                    bg = new RectangleF(-halfwidth * 2, pitchoffset, this.Width * 2, halfheight * 2 - pitchoffset);
+
+                    if (bg.Height != 0)
+                    {
+                        LinearGradientBrush linearBrush = new LinearGradientBrush(bg, Color.FromArgb(0x9b, 0xb8, 0x24),
+                            Color.FromArgb(0x41, 0x4f, 0x07), LinearGradientMode.Vertical);
+
+                        graphicsObject.FillRectangle(linearBrush, bg);
+                    }
+
+                    //draw centerline
+                    graphicsObject.DrawLine(whitePen, -halfwidth * 2, pitchoffset + 0, halfwidth * 2, pitchoffset + 0);
+                }
+
+                graphicsObject.ResetTransform();
+
+                graphicsObject.SetClip(new Rectangle(0, this.Height / 14, this.Width, this.Height - this.Height / 14));
+
+                graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2);
+                graphicsObject.RotateTransform(-_roll);
+
+                // draw armed
+
+                if (status != statuslast)
+                {
+                    armedtimer = DateTime.Now;
+                }
+
+                if (status == 3) // not armed
+                {
+                    //if ((armedtimer.AddSeconds(8) > DateTime.Now))
+                    {
+                        drawstring(graphicsObject, "DISARMED", font, fontsize + 10, Brushes.Red, -85, halfheight / -3);
+                        statuslast = status;
+                    }
+                }
+                else if (status == 4) // armed
+                {
+                    if ((armedtimer.AddSeconds(8) > DateTime.Now))
+                    {
+                        drawstring(graphicsObject, "ARMED", font, fontsize + 20, Brushes.Red, -70, halfheight / -3);
+                        statuslast = status;
+                    }
+                }
+
+                //draw pitch           
+
+                int lengthshort = this.Width / 12;
+                int lengthlong = this.Width / 8;
+
+                for (int a = -90; a <= 90; a += 5)
+                {
+                    // limit to 40 degrees
+                    if (a >= _pitch - 34 && a <= _pitch + 25)
+                    {
+                        if (a % 10 == 0)
+                        {
+                            if (a == 0)
+                            {
+                                graphicsObject.DrawLine(greenPen, this.Width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg);
+                            }
+                            else
+                            {
+                                graphicsObject.DrawLine(whitePen, this.Width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg);
+                            }
+                            drawstring(graphicsObject, a.ToString(), font, fontsize + 2, whiteBrush, this.Width / 2 - lengthlong - 30 - halfwidth - (int)(fontoffset * 1.7), pitchoffset + a * every5deg - 8 - fontoffset);
+                        }
+                        else
+                        {
+                            graphicsObject.DrawLine(whitePen, this.Width / 2 - lengthshort - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthshort - halfwidth, pitchoffset + a * every5deg);
+                            //drawstring(e,a.ToString(), new Font("Arial", 10), whiteBrush, this.Width / 2 - lengthshort - 20 - halfwidth, this.Height / 2 + pitchoffset + a * every5deg - 8);
+                        }
+                    }
+                }
+
+                graphicsObject.ResetTransform();
+
+                // draw roll ind needle
+
+                graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2 + this.Height / 14);
+
+                graphicsObject.RotateTransform(-_roll);
+
+                Point[] pointlist = new Point[3];
+
+                lengthlong = this.Height / 66;
+
+                int extra = this.Height / 15 * 7;
+
+                pointlist[0] = new Point(0, -lengthlong * 2 - extra);
+                pointlist[1] = new Point(-lengthlong, -lengthlong - extra);
+                pointlist[2] = new Point(lengthlong, -lengthlong - extra);
+
+                if (Math.Abs(_roll) > 45)
+                {
+                    redPen.Width = 10;
+                }
+
+                graphicsObject.DrawPolygon(redPen, pointlist);
+
+                redPen.Width = 2;
+
+                for (int a = -45; a <= 45; a += 15)
+                {
+                    graphicsObject.ResetTransform();
+                    graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2 + this.Height / 14);
+                    graphicsObject.RotateTransform(a);
+                    drawstring(graphicsObject, Math.Abs(a).ToString("##"), font, fontsize, whiteBrush, 0 - 6 - fontoffset, -lengthlong * 2 - extra);
+                    graphicsObject.DrawLine(whitePen, 0, -halfheight, 0, -halfheight - 10);
+                }
+
+                graphicsObject.ResetTransform();
+
+                //draw centre / current att
+
+                Rectangle centercircle = new Rectangle(halfwidth - 10, halfheight - 10, 20, 20);
+
+                graphicsObject.DrawEllipse(redPen, centercircle);
+                graphicsObject.DrawLine(redPen, centercircle.Left - 10, halfheight, centercircle.Left, halfheight);
+                graphicsObject.DrawLine(redPen, centercircle.Right, halfheight, centercircle.Right + 10, halfheight);
+                graphicsObject.DrawLine(redPen, centercircle.Left + centercircle.Width / 2, centercircle.Top, centercircle.Left + centercircle.Width / 2, centercircle.Top - 10);
+
+                // draw roll ind
+
+                Rectangle arcrect = new Rectangle(this.Width / 2 - this.Height / 2, this.Height / 14, this.Height, this.Height);
+
+                graphicsObject.DrawArc(whitePen, arcrect, 180 + 45, 90);
+
+                //draw heading ind
+
+                graphicsObject.ResetClip();
+
+                Rectangle headbg = new Rectangle(0, 0, this.Width - 0, this.Height / 14);
+
+                graphicsObject.DrawRectangle(blackPen, headbg);
+
+                SolidBrush solidBrush = new SolidBrush(Color.FromArgb(0x55, 0xff, 0xff, 0xff));
+
+                graphicsObject.FillRectangle(solidBrush, headbg);
+
+                // center
+                graphicsObject.DrawLine(redPen, headbg.Width / 2, headbg.Bottom, headbg.Width / 2, headbg.Top);
+
+                //bottom line
+                graphicsObject.DrawLine(whitePen, headbg.Left + 5, headbg.Bottom - 5, headbg.Width - 5, headbg.Bottom - 5);
+
+                float space = (headbg.Width - 10) / 60.0f;
+                int start = (int)Math.Round((_heading - 30),1);
+
+                // draw for outside the 60 deg
+                if (_targetheading < start)
+                {
+                    greenPen.Width = 6;
+                    graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 0, headbg.Bottom, headbg.Left + 5 + space * (0), headbg.Top);
+                }
+                if (_targetheading > _heading + 30)
+                {
+                    greenPen.Width = 6;
+                    graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 60, headbg.Bottom, headbg.Left + 5 + space * (60), headbg.Top);
+                }
+
+                for (int a = start; a <= _heading + 30; a += 1)
+                {
+                    // target heading
+                    if (((int)(a + 360) % 360) == (int)_targetheading)
+                    {
+                        greenPen.Width = 6;
+                        graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top);
+                    }
+
+                    if (((int)(a + 360) % 360) == (int)_groundcourse)
+                    {
+                        blackPen.Width = 6;
+                        graphicsObject.DrawLine(blackPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top);
+                        blackPen.Width = 2;
+                    }
+
+                    if ((int)a % 5 == 0)
+                    {
+                        //Console.WriteLine(a + " " + Math.Round(a, 1, MidpointRounding.AwayFromZero));
+                        //Console.WriteLine(space +" " + a +" "+ (headbg.Left + 5 + space * (a - start)));
+                        graphicsObject.DrawLine(whitePen, headbg.Left + 5 + space * (a - start), headbg.Bottom - 5, headbg.Left + 5 + space * (a - start), headbg.Bottom - 10);
+                        int disp = (int)a;
+                        if (disp < 0)
+                            disp += 360;
+                        disp = disp % 360;
+                        if (disp == 0)
+                        {
+                            drawstring(graphicsObject, "N".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7));
+                        }
+                        else if (disp == 90)
+                        {
+                            drawstring(graphicsObject, "E".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7));
+                        }
+                        else if (disp == 180)
+                        {
+                            drawstring(graphicsObject, "S".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7));
+                        }
+                        else if (disp == 270)
+                        {
+                            drawstring(graphicsObject, "W".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7));
+                        }
+                        else
+                        {
+                            drawstring(graphicsObject, (disp % 360).ToString().PadLeft(3), font, fontsize, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7));
+                        }
+                    }
+                }
+
+                //                Console.WriteLine("HUD 0 " + (DateTime.Now - starttime).TotalMilliseconds + " " + DateTime.Now.Millisecond);
+
+                // xtrack error
+                // center
+
+                float xtspace = this.Width / 10.0f / 3.0f;
+                int pad = 10;
+
+                float myxtrack_error = _xtrack_error;
+
+                myxtrack_error = Math.Min(myxtrack_error, 40);
+                myxtrack_error = Math.Max(myxtrack_error, -40);
+
+                //  xtrack - distance scale - space
+                float loc = myxtrack_error / 20.0f * xtspace;
+
+                // current xtrack
+                if (Math.Abs(myxtrack_error) == 40)
+                {
+                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
+                }
+
+                graphicsObject.DrawLine(greenPen, this.Width / 10 + loc, headbg.Bottom + 5, this.Width / 10 + loc, headbg.Bottom + this.Height / 10);
+
+                greenPen.Color = Color.FromArgb(255, greenPen.Color);
+
+                graphicsObject.DrawLine(whitePen, this.Width / 10, headbg.Bottom + 5, this.Width / 10, headbg.Bottom + this.Height / 10);
+
+                graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace, headbg.Bottom + 5 + pad, this.Width / 10 - xtspace, headbg.Bottom + this.Height / 10 - pad);
+
+                graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 2, headbg.Bottom + 5 + pad, this.Width / 10 - xtspace * 2, headbg.Bottom + this.Height / 10 - pad);
+
+                graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace, headbg.Bottom + 5 + pad, this.Width / 10 + xtspace, headbg.Bottom + this.Height / 10 - pad);
+
+                graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace * 2, headbg.Bottom + 5 + pad, this.Width / 10 + xtspace * 2, headbg.Bottom + this.Height / 10 - pad);
+
+                // rate of turn
+
+                whitePen.Width = 4;
+                graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 2 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 - xtspace * 2 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10);
+
+                graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 0 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 - xtspace * 0 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10);
+
+                graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace * 2 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 + xtspace * 2 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10);
+
+                float myturnrate = _turnrate;
+                float trwidth = (this.Width / 10 + xtspace * 2 - xtspace / 2) - (this.Width / 10 - xtspace * 2 - xtspace / 2);
+
+                float range = 12;
+
+                myturnrate = Math.Min(myturnrate, range / 2);
+                myturnrate = Math.Max(myturnrate, (range / 2) * -1.0f);
+
+                loc = myturnrate / range * trwidth;
+
+                greenPen.Width = 4;
+
+                if (Math.Abs(myturnrate) == (range / 2))
+                {
+                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
+                }
+
+                graphicsObject.DrawLine(greenPen, this.Width / 10 + loc - xtspace / 2, headbg.Bottom + this.Height / 10 + 10 + 3, this.Width / 10 + loc + xtspace / 2, headbg.Bottom + this.Height / 10 + 10 + 3);
+                graphicsObject.DrawLine(greenPen, this.Width / 10 + loc, headbg.Bottom + this.Height / 10 + 10 + 3, this.Width / 10 + loc, headbg.Bottom + this.Height / 10 + 10 + 10);
+
+                greenPen.Color = Color.FromArgb(255, greenPen.Color);
+
+                whitePen.Width = 2;
+
+
+
+                // left scroller
+
+                Rectangle scrollbg = new Rectangle(0, halfheight - halfheight / 2, this.Width / 10, this.Height / 2);
+
+                graphicsObject.DrawRectangle(whitePen, scrollbg);
+
+                graphicsObject.FillRectangle(solidBrush, scrollbg);
+
+                Point[] arrow = new Point[5];
+
+                arrow[0] = new Point(0, -10);
+                arrow[1] = new Point(scrollbg.Width - 10, -10);
+                arrow[2] = new Point(scrollbg.Width - 5, 0);
+                arrow[3] = new Point(scrollbg.Width - 10, 10);
+                arrow[4] = new Point(0, 10);
+
+                graphicsObject.TranslateTransform(0, this.Height / 2);
+
+                int viewrange = 26;
+
+                float speed = _airspeed;
+                if (speed == 0)
+                    speed = _groundspeed;
+
+                space = (scrollbg.Height) / (float)viewrange;
+                start = ((int)speed - viewrange / 2);
+
+                if (start > _targetspeed)
+                {
+                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
+                    greenPen.Width = 6;
+                    graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top);
+                    greenPen.Color = Color.FromArgb(255, greenPen.Color);
+                }
+                if ((speed + viewrange / 2) < _targetspeed)
+                {
+                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
+                    greenPen.Width = 6;
+                    graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * viewrange, scrollbg.Left + scrollbg.Width, scrollbg.Top - space * viewrange);
+                    greenPen.Color = Color.FromArgb(255, greenPen.Color);
+                }
+
+                for (int a = (int)start; a <= (speed + viewrange / 2); a += 1)
+                {
+                    if (a == (int)_targetspeed && _targetspeed != 0)
+                    {
+                        greenPen.Width = 6;
+                        graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start));
+                    }
+                    if (a % 5 == 0)
+                    {
+                        //Console.WriteLine(a + " " + scrollbg.Right + " " + (scrollbg.Top - space * (a - start)) + " " + (scrollbg.Right - 20) + " " + (scrollbg.Top - space * (a - start)));
+                        graphicsObject.DrawLine(whitePen, scrollbg.Right, scrollbg.Top - space * (a - start), scrollbg.Right - 10, scrollbg.Top - space * (a - start));
+                        drawstring(graphicsObject, a.ToString().PadLeft(5), font, fontsize, whiteBrush, scrollbg.Right - 50 - 4 * fontoffset, scrollbg.Top - space * (a - start) - 6 - fontoffset);
+                    }
+                }
+
+                graphicsObject.DrawPolygon(blackPen, arrow);
+                graphicsObject.FillPolygon(Brushes.Black, arrow);
+                drawstring(graphicsObject, ((int)speed).ToString("0"), font, 10, Brushes.AliceBlue, 0, -9);
+
+                graphicsObject.ResetTransform();
+
+                // extra text data
+
+                drawstring(graphicsObject, "AS " + _airspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + 5);
+                drawstring(graphicsObject, "GS " + _groundspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10);
+
+                //drawstring(e,, new Font("Arial", fontsize + 2), whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10);
+
+                // right scroller
+
+                scrollbg = new Rectangle(this.Width - this.Width / 10, halfheight - halfheight / 2, this.Width / 10, this.Height / 2);
+
+                graphicsObject.DrawRectangle(whitePen, scrollbg);
+
+                graphicsObject.FillRectangle(solidBrush, scrollbg);
+
+                arrow = new Point[5];
+
+                arrow[0] = new Point(0, -10);
+                arrow[1] = new Point(scrollbg.Width - 10, -10);
+                arrow[2] = new Point(scrollbg.Width - 5, 0);
+                arrow[3] = new Point(scrollbg.Width - 10, 10);
+                arrow[4] = new Point(0, 10);
+
+
+
+                graphicsObject.TranslateTransform(0, this.Height / 2);
+
+
+
+
+                viewrange = 26;
+
+                space = (scrollbg.Height) / (float)viewrange;
+                start = ((int)_alt - viewrange / 2);
+
+                if (start > _targetalt)
+                {
+                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
+                    greenPen.Width = 6;
+                    graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top);
+                    greenPen.Color = Color.FromArgb(255, greenPen.Color);
+                }
+                if ((_alt + viewrange / 2) < _targetalt)
+                {
+                    greenPen.Color = Color.FromArgb(128, greenPen.Color);
+                    greenPen.Width = 6;
+                    graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * viewrange, scrollbg.Left + scrollbg.Width, scrollbg.Top - space * viewrange);
+                    greenPen.Color = Color.FromArgb(255, greenPen.Color);
+                }
+
+                for (int a = (int)start; a <= (_alt + viewrange / 2); a += 1)
+                {
+                    if (a == Math.Round(_targetalt) && _targetalt != 0)
+                    {
+                        greenPen.Width = 6;
+                        graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start));
+                    }
+                    if (a % 5 == 0)
+                    {
+                        //Console.WriteLine(a + " " + scrollbg.Left + " " + (scrollbg.Top - space * (a - start)) + " " + (scrollbg.Left + 20) + " " + (scrollbg.Top - space * (a - start)));
+                        graphicsObject.DrawLine(whitePen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + 10, scrollbg.Top - space * (a - start));
+                        drawstring(graphicsObject, a.ToString().PadLeft(5), font, fontsize, whiteBrush, scrollbg.Left + 7 + (int)(0 * fontoffset), scrollbg.Top - space * (a - start) - 6 - fontoffset);
+                    }
+                }
+
+                greenPen.Width = 4;
+
+                // vsi
+
+                graphicsObject.ResetTransform();
+
+                PointF[] poly = new PointF[4];
+
+                poly[0] = new PointF(scrollbg.Left, scrollbg.Top);
+                poly[1] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + scrollbg.Width / 4);
+                poly[2] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Bottom - scrollbg.Width / 4);
+                poly[3] = new PointF(scrollbg.Left, scrollbg.Bottom);
+
+                //verticalspeed
+
+                viewrange = 12;
+
+                _verticalspeed = Math.Min(viewrange / 2, _verticalspeed);
+                _verticalspeed = Math.Max(viewrange / -2, _verticalspeed);
+
+                float scaledvalue = _verticalspeed / -viewrange * (scrollbg.Bottom - scrollbg.Top);
+
+                float linespace = (float)1 / -viewrange * (scrollbg.Bottom - scrollbg.Top);
+
+                PointF[] polyn = new PointF[4];
+
+                polyn[0] = new PointF(scrollbg.Left, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2);
+                polyn[1] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2);
+                polyn[2] = polyn[1];
+                float peak = 0;
+                if (scaledvalue > 0)
+                {
+                    peak = -scrollbg.Width / 4;
+                    if (scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak < scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2)
+                        peak = -scaledvalue;
+                }
+                else if (scaledvalue < 0)
+                {
+                    peak = +scrollbg.Width / 4;
+                    if (scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak > scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2)
+                        peak = -scaledvalue;
+                }
+                
+                polyn[2] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak);
+                polyn[3] = new PointF(scrollbg.Left, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue);
+
+                //graphicsObject.DrawPolygon(redPen, poly);
+                graphicsObject.FillPolygon(Brushes.Blue, polyn);
+
+                // draw outsidebox
+                graphicsObject.DrawPolygon(whitePen, poly);
+
+                for (int a = 1; a < viewrange; a++)
+                {
+                    graphicsObject.DrawLine(whitePen, scrollbg.Left - scrollbg.Width / 4, scrollbg.Top - linespace * a, scrollbg.Left - scrollbg.Width / 8, scrollbg.Top - linespace * a);
+                }
+
+                // draw arrow and text
+                
+                graphicsObject.ResetTransform();
+                graphicsObject.TranslateTransform(this.Width, this.Height / 2);
+                graphicsObject.RotateTransform(180);
+
+                graphicsObject.DrawPolygon(blackPen, arrow);
+                graphicsObject.FillPolygon(Brushes.Black, arrow);
+                graphicsObject.ResetTransform();
+                graphicsObject.TranslateTransform(0, this.Height / 2);
+
+                drawstring(graphicsObject, ((int)_alt).ToString("0"), font, 10, Brushes.AliceBlue, scrollbg.Left + 10, -9);
+                graphicsObject.ResetTransform();
+
+                // mode and wp dist and wp
+
+                drawstring(graphicsObject, _mode, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + 5);
+                drawstring(graphicsObject, (int)_disttowp + ">" + _wpno, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + fontsize + 2 + 10);
+
+                graphicsObject.DrawLine(greenPen, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize) - 2 - 20);
+                graphicsObject.DrawLine(greenPen, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 15, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize) - 2 - 20);
+                graphicsObject.DrawLine(greenPen, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 10, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize ) - 2 - 20);
+
+                drawstring(graphicsObject, _linkqualitygcs.ToString("0") + "%", font, fontsize, whiteBrush, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20);
+                if (_linkqualitygcs == 0)
+                {
+                    graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2);
+
+                    graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20);
+                }
+                drawstring(graphicsObject, _datetime.ToString("HH:mm:ss"), font, fontsize, whiteBrush, scrollbg.Left - 20, scrollbg.Top - fontsize - 2 - 20);
+
+
+                // battery
+
+                graphicsObject.ResetTransform();
+
+                drawstring(graphicsObject, "Bat", font, fontsize + 2, whiteBrush, fontsize, this.Height - 30 - fontoffset);
+                drawstring(graphicsObject, _batterylevel.ToString("0.00v"), font, fontsize + 2, whiteBrush, fontsize * 4, this.Height - 30 - fontoffset);
+                drawstring(graphicsObject, _batteryremaining.ToString("0%"), font, fontsize + 2, whiteBrush, fontsize * 9, this.Height - 30 - fontoffset);
+
+                // gps
+
+                string gps = "";
+
+                if (_gpsfix == 0)
+                {
+                    gps = ("GPS: No GPS");
+                }
+                else if (_gpsfix == 1)
+                {
+                    gps = ("GPS: No Fix");
+                }
+                else if (_gpsfix == 2)
+                {
+                    gps = ("GPS: 3D Fix");
+                }
+                else if (_gpsfix == 3)
+                {
+                    gps = ("GPS: 3D Fix");
+                }
+
+                drawstring(graphicsObject, gps, font, fontsize + 2, whiteBrush, this.Width - 10 * fontsize, this.Height - 30 - fontoffset);
+
+
+                if (isNaN)
+                    drawstring(graphicsObject, "NaN Error " + DateTime.Now, font, this.Height / 30 + 10, Brushes.Red, 50, 50);
+
+
+                if (!opengl)
+                {
+                    e.Graphics.DrawImageUnscaled(objBitmap, 0, 0);
+                }
+
+                if (DesignMode)
+                {
+                    return;
+                }
+
+                //                Console.WriteLine("HUD 1 " + (DateTime.Now - starttime).TotalMilliseconds + " " + DateTime.Now.Millisecond);
+
+                ImageCodecInfo ici = GetImageCodec("image/jpeg");
+                EncoderParameters eps = new EncoderParameters(1);
+                eps.Param[0] = new EncoderParameter(System.Drawing.Imaging.Encoder.Quality, 50L); // or whatever other quality value you want
+
+                lock (streamlock)
+                {
+                    if (streamjpgenable || streamjpg == null) // init image and only update when needed
+                    {
+                        if (opengl)
+                        {
+                            objBitmap = GrabScreenshot();
+                        }
+                        streamjpg = new MemoryStream();
+                        objBitmap.Save(streamjpg, ici, eps);
+                        //objBitmap.Save(streamjpg,ImageFormat.Bmp);
+                    }
+                }
+            }
+            catch (Exception ex)
+            {
+                log.Info("hud error "+ex.ToString());
+            }
+        }
+
+        protected override void OnPaintBackground(PaintEventArgs e)
+        {
+            //base.OnPaintBackground(e);
+        }
+
+        ImageCodecInfo GetImageCodec(string mimetype)
+        {
+            foreach (ImageCodecInfo ici in ImageCodecInfo.GetImageEncoders())
+            {
+                if (ici.MimeType == mimetype) return ici;
+            }
+            return null;
+        }
+
+        // Returns a System.Drawing.Bitmap with the contents of the current framebuffer
+        public new Bitmap GrabScreenshot()
+        {
+            if (GraphicsContext.CurrentContext == null)
+                throw new GraphicsContextMissingException();
+
+            Bitmap bmp = new Bitmap(this.ClientSize.Width, this.ClientSize.Height);
+            System.Drawing.Imaging.BitmapData data =
+                bmp.LockBits(this.ClientRectangle, System.Drawing.Imaging.ImageLockMode.WriteOnly, System.Drawing.Imaging.PixelFormat.Format24bppRgb);
+            GL.ReadPixels(0, 0, this.ClientSize.Width, this.ClientSize.Height,OpenTK.Graphics.OpenGL.PixelFormat.Bgr, PixelType.UnsignedByte, data.Scan0);
+            bmp.UnlockBits(data);
+
+            bmp.RotateFlip(RotateFlipType.RotateNoneFlipY);
+            return bmp;
+        }
+
+
+        float wrap360(float noin)
+        {
+            if (noin < 0)
+                return noin + 360;
+            return noin;
+        }
+
+        /// <summary>
+        /// pen for drawstring
+        /// </summary>
+        Pen P = new Pen(Color.FromArgb(0x26, 0x27, 0x28), 2f);
+        /// <summary>
+        /// pth for drawstring
+        /// </summary>
+        GraphicsPath pth = new GraphicsPath();
+
+        void drawstring(HUD e, string text, Font font, float fontsize, Brush brush, float x, float y)
+        {
+            if (!opengl)
+            {
+                drawstring(graphicsObjectGDIP, text, font, fontsize, brush, x, y);
+                return;
+            }
+
+            if (text == null || text == "")
+                return;
+            /*
+            OpenTK.Graphics.Begin(); 
+            GL.PushMatrix(); 
+            GL.Translate(x, y, 0);
+            printer.Print(text, font, c); 
+            GL.PopMatrix(); printer.End();
+            */
+
+            char[] chars = text.ToCharArray();
+
+            float maxy = 1;
+
+            foreach (char cha in chars)
+            {
+                int charno = (int)cha;
+
+                int charid = charno  + (128 * (int)fontsize); // 128 * 40 * 5;128
+
+                if (charbitmaps[charid] == null)
+                {
+                    charbitmaps[charid] = new Bitmap(128, 128, System.Drawing.Imaging.PixelFormat.Format32bppArgb);
+
+                    charbitmaps[charid].MakeTransparent(Color.Transparent);
+
+                    //charbitmaptexid
+
+                    float maxx = this.Width / 150; // for space
+
+
+                    // create bitmap
+                    using (Graphics gfx = Graphics.FromImage(charbitmaps[charid]))
+                    {
+                        pth.Reset();
+
+                        if (text != null)
+                            pth.AddString(cha + "", font.FontFamily, 0, fontsize + 5, new Point((int)0, (int)0), StringFormat.GenericTypographic);
+
+                        gfx.SmoothingMode = System.Drawing.Drawing2D.SmoothingMode.AntiAlias;
+
+                        gfx.DrawPath(P, pth);
+
+                        //Draw the face
+
+                        gfx.FillPath(brush, pth);
+
+
+                        if (pth.PointCount > 0)
+                        {
+                            foreach (PointF pnt in pth.PathPoints)
+                            {
+                                if (pnt.X > maxx)
+                                    maxx = pnt.X;
+
+                                if (pnt.Y > maxy)
+                                    maxy = pnt.Y;
+                            }
+                        }
+                    }
+
+                    charwidth[charid] = (int)(maxx + 2);
+
+                    //charbitmaps[charid] = charbitmaps[charid].Clone(new RectangleF(0, 0, maxx + 2, maxy + 2), charbitmaps[charid].PixelFormat);
+
+                    //charbitmaps[charno * (int)fontsize].Save(charno + " " + (int)fontsize + ".png");
+
+                    // create texture
+                    int textureId;
+                    GL.TexEnv(TextureEnvTarget.TextureEnv, TextureEnvParameter.TextureEnvMode, (float)TextureEnvModeCombine.Replace);//Important, or wrong color on some computers
+
+                    Bitmap bitmap = charbitmaps[charid];
+                    GL.GenTextures(1, out textureId);
+                    GL.BindTexture(TextureTarget.Texture2D, textureId);
+
+                    BitmapData data = bitmap.LockBits(new System.Drawing.Rectangle(0, 0, bitmap.Width, bitmap.Height), ImageLockMode.ReadOnly, System.Drawing.Imaging.PixelFormat.Format32bppArgb);
+
+                    GL.TexImage2D(TextureTarget.Texture2D, 0, PixelInternalFormat.Rgba, data.Width, data.Height, 0, OpenTK.Graphics.OpenGL.PixelFormat.Bgra, PixelType.UnsignedByte, data.Scan0);
+
+                    GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear);
+                    GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)TextureMagFilter.Linear);
+
+                    //    GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)All.Nearest);
+                    //GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)All.Nearest);
+                    GL.Finish();
+                    bitmap.UnlockBits(data);
+
+                    charbitmaptexid[charid] = textureId;
+                }
+
+                //GL.Enable(EnableCap.Blend);
+                GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha);
+
+                GL.Enable(EnableCap.Texture2D);
+                GL.BindTexture(TextureTarget.Texture2D, charbitmaptexid[charid]);
+
+                float scale = 1.0f;
+
+                GL.Begin(BeginMode.Quads);
+                GL.TexCoord2(0, 0); GL.Vertex2(x, y);
+                GL.TexCoord2(1, 0); GL.Vertex2(x + charbitmaps[charid].Width * scale, y);
+                GL.TexCoord2(1, 1); GL.Vertex2(x + charbitmaps[charid].Width * scale, y + charbitmaps[charid].Height * scale);
+                GL.TexCoord2(0, 1); GL.Vertex2(x + 0, y + charbitmaps[charid].Height * scale);
+                GL.End();
+
+                //GL.Disable(EnableCap.Blend);
+                GL.Disable(EnableCap.Texture2D);
+
+                x += charwidth[charid] * scale;
+            }
+        }
+		
+		void drawstring(Graphics e, string text, Font font, float fontsize, Brush brush, float x, float y)
+        {
+            if (text == null || text == "")
+                return;
+
+            pth.Reset();
+            
+            if (text != null)
+                pth.AddString(text, font.FontFamily, 0, fontsize + 5, new Point((int)x, (int)y), StringFormat.GenericTypographic);
+
+            //Draw the edge
+            // this uses lots of cpu time
+
+            //e.SmoothingMode = SmoothingMode.HighSpeed;
+
+            if (e == null || P == null || pth == null || pth.PointCount == 0)
+                return;
+            
+            //if (!ArdupilotMega.MainV2.MONO)
+                e.DrawPath(P, pth);
+
+            //Draw the face
+
+            e.FillPath(brush, pth);
+
+            //pth.Dispose();
+        }
+
+        protected override void OnHandleCreated(EventArgs e)
+        {
+            try
+            {
+                if (opengl)
+                {
+                    base.OnHandleCreated(e);
+                }
+            }
+            catch (Exception ex) { log.Info(ex.ToString()); opengl = false; } // macs fail here
+        }
+
+        protected override void OnHandleDestroyed(EventArgs e)
+        {
+            try
+            {
+                if (opengl)
+                {
+                    base.OnHandleDestroyed(e);
+                }
+            }
+            catch (Exception ex) { log.Info(ex.ToString()); opengl = false; }
+        }
+
+        protected override void OnResize(EventArgs e)
+        {
+            if (DesignMode || !started)
+                return;
+
+           
+            if (SixteenXNine)
+            {
+                this.Height = (int)(this.Width / 1.777f);
+            }
+            else
+            {
+                // 4x3
+                this.Height = (int)(this.Width / 1.333f);
+            }
+
+            base.OnResize(e);
+
+            graphicsObjectGDIP = Graphics.FromImage(objBitmap);
+
+            charbitmaps = new Bitmap[charbitmaps.Length];
+
+            try
+            {
+                if (opengl)
+                {
+                    foreach (int texid in charbitmaptexid)
+                    {
+                        if (texid != 0)
+                            GL.DeleteTexture(texid);
+                    }
+                }
+            }
+            catch { }
+
+            GC.Collect();
+            
+            try
+            {
+                if (opengl)
+                {
+                    GL.MatrixMode(MatrixMode.Projection);
+                    GL.LoadIdentity();
+                    GL.Ortho(0, Width, Height, 0, -1, 1);
+                    GL.MatrixMode(MatrixMode.Modelview);
+                    GL.LoadIdentity();
+
+                    GL.Viewport(0, 0, Width, Height);
+                }
+            }
+            catch { }
+             
+        }
+    }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.Designer.cs b/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.Designer.cs
index dfa1e43a2..fa42576c8 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.Designer.cs
@@ -1,4 +1,4 @@
-namespace ArdupilotMega
+namespace ArdupilotMega.Controls
 {
     partial class ImageLabel
     {
diff --git a/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs b/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs
index 2b16d6337..1cd32b95c 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs
@@ -7,7 +7,7 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 
-namespace ArdupilotMega
+namespace ArdupilotMega.Controls
 {
     public partial class ImageLabel : UserControl //ContainerControl
     {
diff --git a/Tools/ArdupilotMegaPlanner/Controls/LineSeparator.cs b/Tools/ArdupilotMegaPlanner/Controls/LineSeparator.cs
index 9e9002a87..5c96aff3e 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/LineSeparator.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/LineSeparator.cs
@@ -7,46 +7,45 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 
-
-public partial class LineSeparator : UserControl
+namespace ArdupilotMega.Controls
 {
 
-
-
-
-    public LineSeparator()
+    public partial class LineSeparator : UserControl
     {
-        this.Height = 2;
+        public LineSeparator()
+        {
+            this.Height = 2;
 
-        this.Paint += new PaintEventHandler(LineSeparator_Paint);
+            this.Paint += new PaintEventHandler(LineSeparator_Paint);
 
 
-        this.MaximumSize = new Size(2000, 2);
+            this.MaximumSize = new Size(2000, 2);
 
 
-        this.MinimumSize = new Size(0, 2);
+            this.MinimumSize = new Size(0, 2);
 
-        //this.Width = 350;
+            //this.Width = 350;
 
-    }
+        }
 
 
-    private void LineSeparator_Paint(object sender, PaintEventArgs e)
-    {
+        private void LineSeparator_Paint(object sender, PaintEventArgs e)
+        {
 
 
 
 
-        Graphics g = e.Graphics;
+            Graphics g = e.Graphics;
 
-        g.DrawLine(
+            g.DrawLine(
 
-        Pens.DarkGray, new Point(0, 0), new Point(this.Width, 0));
+            Pens.DarkGray, new Point(0, 0), new Point(this.Width, 0));
 
-        g.DrawLine(
+            g.DrawLine(
 
-        Pens.White, new Point(0, 1), new Point(this.Width, 1));
+            Pens.White, new Point(0, 1), new Point(this.Width, 1));
 
-    }
+        }
 
-}
+    }
+}
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs b/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs
index 9faaeb844..051670564 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs
@@ -10,7 +10,7 @@ using System.Windows.Forms;
 
 using System.Drawing.Drawing2D;
 
-namespace ArdupilotMega
+namespace ArdupilotMega.Controls
 {
     class MyButton : Button
     {
diff --git a/Tools/ArdupilotMegaPlanner/Controls/MyLabel.cs b/Tools/ArdupilotMegaPlanner/Controls/MyLabel.cs
index cc18c0b72..b2a931d4b 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/MyLabel.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/MyLabel.cs
@@ -7,10 +7,10 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 
-namespace ArdupilotMega
+namespace ArdupilotMega.Controls
 {
     /// <summary>
-    /// profiling showed that the built in Label function was using alot ot call time.
+    /// profiling showed that the built in Label function was using alot of call time.
     /// </summary>
     public partial class MyLabel : Control //: Label
     {
diff --git a/Tools/ArdupilotMegaPlanner/Controls/MyTrackBar.cs b/Tools/ArdupilotMegaPlanner/Controls/MyTrackBar.cs
index 1e010c806..bf4536df0 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/MyTrackBar.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/MyTrackBar.cs
@@ -4,7 +4,7 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 
-namespace ArdupilotMega
+namespace ArdupilotMega.Controls
 {
     class MyTrackBar : TrackBar
     {
diff --git a/Tools/ArdupilotMegaPlanner/Controls/MyUserControl.cs b/Tools/ArdupilotMegaPlanner/Controls/MyUserControl.cs
index 0a7a76479..58260f138 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/MyUserControl.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/MyUserControl.cs
@@ -5,6 +5,9 @@ using System.Text;
 
 namespace System.Windows.Forms
 {
+    /// <summary>
+    /// This is a mono fix, windows handles this error, mono crashs
+    /// </summary>
     public class MyUserControl : System.Windows.Forms.UserControl
     {
         protected override void WndProc(ref Message m)
diff --git a/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs b/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs
index 683b99500..ff11f878d 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs
@@ -5,8 +5,6 @@ using System.Windows.Forms;
 
 namespace ArdupilotMega.Controls
 {
-
-
     /// <summary>
     /// Form that is shown to the user during a background operation
     /// </summary>
diff --git a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.Designer.cs b/Tools/ArdupilotMegaPlanner/Controls/XorPlus.Designer.cs
deleted file mode 100644
index 2a14e1fe1..000000000
--- a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.Designer.cs
+++ /dev/null
@@ -1,112 +0,0 @@
-namespace ArdupilotMega
-{
-    partial class XorPlus
-    {
-        /// <summary> 
-        /// Required designer variable.
-        /// </summary>
-        private System.ComponentModel.IContainer components = null;
-
-        /// <summary> 
-        /// Clean up any resources being used.
-        /// </summary>
-        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
-        protected override void Dispose(bool disposing)
-        {
-            if (disposing && (components != null))
-            {
-                components.Dispose();
-            }
-            base.Dispose(disposing);
-        }
-
-        #region Component Designer generated code
-
-        /// <summary> 
-        /// Required method for Designer support - do not modify 
-        /// the contents of this method with the code editor.
-        /// </summary>
-        private void InitializeComponent()
-        {
-            this.label16 = new System.Windows.Forms.Label();
-            this.label15 = new System.Windows.Forms.Label();
-            this.pictureBoxQuadX = new System.Windows.Forms.PictureBox();
-            this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
-            ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit();
-            ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).BeginInit();
-            this.SuspendLayout();
-            // 
-            // label16
-            // 
-            this.label16.AutoSize = true;
-            this.label16.ImeMode = System.Windows.Forms.ImeMode.NoControl;
-            this.label16.Location = new System.Drawing.Point(108, 211);
-            this.label16.Name = "label16";
-            this.label16.Size = new System.Drawing.Size(192, 26);
-            this.label16.TabIndex = 11;
-            this.label16.Text = "NOTE: images are for presentation only\r\nwill work with hexa\'s etc";
-            // 
-            // label15
-            // 
-            this.label15.AutoSize = true;
-            this.label15.ImeMode = System.Windows.Forms.ImeMode.NoControl;
-            this.label15.Location = new System.Drawing.Point(151, 2);
-            this.label15.Name = "label15";
-            this.label15.Size = new System.Drawing.Size(102, 13);
-            this.label15.TabIndex = 10;
-            this.label15.Text = "Frame Setup (+ or x)";
-            // 
-            // pictureBoxQuadX
-            // 
-            this.pictureBoxQuadX.Cursor = System.Windows.Forms.Cursors.Hand;
-            this.pictureBoxQuadX.Image = global::ArdupilotMega.Properties.Resources.quadx;
-            this.pictureBoxQuadX.ImeMode = System.Windows.Forms.ImeMode.NoControl;
-            this.pictureBoxQuadX.Location = new System.Drawing.Point(210, 18);
-            this.pictureBoxQuadX.Name = "pictureBoxQuadX";
-            this.pictureBoxQuadX.Size = new System.Drawing.Size(190, 190);
-            this.pictureBoxQuadX.SizeMode = System.Windows.Forms.PictureBoxSizeMode.Zoom;
-            this.pictureBoxQuadX.TabIndex = 9;
-            this.pictureBoxQuadX.TabStop = false;
-            this.pictureBoxQuadX.Click += new System.EventHandler(this.pictureBoxQuadX_Click);
-            // 
-            // pictureBoxQuad
-            // 
-            this.pictureBoxQuad.Cursor = System.Windows.Forms.Cursors.Hand;
-            this.pictureBoxQuad.Image = global::ArdupilotMega.Properties.Resources.quad;
-            this.pictureBoxQuad.ImeMode = System.Windows.Forms.ImeMode.NoControl;
-            this.pictureBoxQuad.Location = new System.Drawing.Point(3, 18);
-            this.pictureBoxQuad.Name = "pictureBoxQuad";
-            this.pictureBoxQuad.Size = new System.Drawing.Size(190, 190);
-            this.pictureBoxQuad.SizeMode = System.Windows.Forms.PictureBoxSizeMode.Zoom;
-            this.pictureBoxQuad.TabIndex = 8;
-            this.pictureBoxQuad.TabStop = false;
-            this.pictureBoxQuad.Click += new System.EventHandler(this.pictureBoxQuad_Click);
-            // 
-            // XorPlus
-            // 
-            this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
-            this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
-            this.ClientSize = new System.Drawing.Size(404, 242);
-            this.Controls.Add(this.label16);
-            this.Controls.Add(this.label15);
-            this.Controls.Add(this.pictureBoxQuadX);
-            this.Controls.Add(this.pictureBoxQuad);
-            this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.FixedToolWindow;
-            this.Name = "XorPlus";
-            this.StartPosition = System.Windows.Forms.FormStartPosition.CenterParent;
-            this.Text = "Frame Type";
-            ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).EndInit();
-            ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).EndInit();
-            this.ResumeLayout(false);
-            this.PerformLayout();
-
-        }
-
-        #endregion
-
-        private System.Windows.Forms.Label label16;
-        private System.Windows.Forms.Label label15;
-        private System.Windows.Forms.PictureBox pictureBoxQuadX;
-        private System.Windows.Forms.PictureBox pictureBoxQuad;
-    }
-}
diff --git a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.cs b/Tools/ArdupilotMegaPlanner/Controls/XorPlus.cs
deleted file mode 100644
index 98808fe43..000000000
--- a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.cs
+++ /dev/null
@@ -1,48 +0,0 @@
-using System;
-using System.Collections.Generic;
-using System.ComponentModel;
-using System.Drawing;
-using System.Data;
-using System.Linq;
-using System.Text;
-using System.Windows.Forms;
-
-namespace ArdupilotMega
-{
-    public partial class XorPlus : Form
-    {
-        public new event EventHandler Click;
-
-        /// <summary>
-        /// either X or +
-        /// </summary>
-        public string frame = "";
-
-        public XorPlus()
-        {
-            InitializeComponent();
-        }
-
-        private void pictureBoxQuad_Click(object sender, EventArgs e)
-        {
-            frame = "+";
-            if (Click != null)
-            {
-                Click(sender, new EventArgs());
-            }
-
-            this.Close();
-        }
-
-        private void pictureBoxQuadX_Click(object sender, EventArgs e)
-        {
-            frame = "X";
-            if (Click != null)
-            {
-                Click(sender, new EventArgs());
-            }
-
-            this.Close();
-        }
-    }
-}
diff --git a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.resx b/Tools/ArdupilotMegaPlanner/Controls/XorPlus.resx
deleted file mode 100644
index 7080a7d11..000000000
--- a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.resx
+++ /dev/null
@@ -1,120 +0,0 @@
-<?xml version="1.0" encoding="utf-8"?>
-<root>
-  <!-- 
-    Microsoft ResX Schema 
-    
-    Version 2.0
-    
-    The primary goals of this format is to allow a simple XML format 
-    that is mostly human readable. The generation and parsing of the 
-    various data types are done through the TypeConverter classes 
-    associated with the data types.
-    
-    Example:
-    
-    ... ado.net/XML headers & schema ...
-    <resheader name="resmimetype">text/microsoft-resx</resheader>
-    <resheader name="version">2.0</resheader>
-    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
-    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
-    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
-    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
-    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
-        <value>[base64 mime encoded serialized .NET Framework object]</value>
-    </data>
-    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
-        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
-        <comment>This is a comment</comment>
-    </data>
-                
-    There are any number of "resheader" rows that contain simple 
-    name/value pairs.
-    
-    Each data row contains a name, and value. The row also contains a 
-    type or mimetype. Type corresponds to a .NET class that support 
-    text/value conversion through the TypeConverter architecture. 
-    Classes that don't support this are serialized and stored with the 
-    mimetype set.
-    
-    The mimetype is used for serialized objects, and tells the 
-    ResXResourceReader how to depersist the object. This is currently not 
-    extensible. For a given mimetype the value must be set accordingly:
-    
-    Note - application/x-microsoft.net.object.binary.base64 is the format 
-    that the ResXResourceWriter will generate, however the reader can 
-    read any of the formats listed below.
-    
-    mimetype: application/x-microsoft.net.object.binary.base64
-    value   : The object must be serialized with 
-            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
-            : and then encoded with base64 encoding.
-    
-    mimetype: application/x-microsoft.net.object.soap.base64
-    value   : The object must be serialized with 
-            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
-            : and then encoded with base64 encoding.
-
-    mimetype: application/x-microsoft.net.object.bytearray.base64
-    value   : The object must be serialized into a byte array 
-            : using a System.ComponentModel.TypeConverter
-            : and then encoded with base64 encoding.
-    -->
-  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
-    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
-    <xsd:element name="root" msdata:IsDataSet="true">
-      <xsd:complexType>
-        <xsd:choice maxOccurs="unbounded">
-          <xsd:element name="metadata">
-            <xsd:complexType>
-              <xsd:sequence>
-                <xsd:element name="value" type="xsd:string" minOccurs="0" />
-              </xsd:sequence>
-              <xsd:attribute name="name" use="required" type="xsd:string" />
-              <xsd:attribute name="type" type="xsd:string" />
-              <xsd:attribute name="mimetype" type="xsd:string" />
-              <xsd:attribute ref="xml:space" />
-            </xsd:complexType>
-          </xsd:element>
-          <xsd:element name="assembly">
-            <xsd:complexType>
-              <xsd:attribute name="alias" type="xsd:string" />
-              <xsd:attribute name="name" type="xsd:string" />
-            </xsd:complexType>
-          </xsd:element>
-          <xsd:element name="data">
-            <xsd:complexType>
-              <xsd:sequence>
-                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
-                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
-              </xsd:sequence>
-              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
-              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
-              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
-              <xsd:attribute ref="xml:space" />
-            </xsd:complexType>
-          </xsd:element>
-          <xsd:element name="resheader">
-            <xsd:complexType>
-              <xsd:sequence>
-                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
-              </xsd:sequence>
-              <xsd:attribute name="name" type="xsd:string" use="required" />
-            </xsd:complexType>
-          </xsd:element>
-        </xsd:choice>
-      </xsd:complexType>
-    </xsd:element>
-  </xsd:schema>
-  <resheader name="resmimetype">
-    <value>text/microsoft-resx</value>
-  </resheader>
-  <resheader name="version">
-    <value>2.0</value>
-  </resheader>
-  <resheader name="reader">
-    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </resheader>
-  <resheader name="writer">
-    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </resheader>
-</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs b/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs
index 38e37a84b..f24440fb5 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs
@@ -3,8 +3,11 @@ using System.Collections.Generic;
 using System.Linq;
 using System.Text;
 
-namespace ArdupilotMega
+namespace ArdupilotMega.Controls
 {
+    /// <summary>
+    /// Mono handles calls from other thread difrently - this prevents those crashs
+    /// </summary>
     class myGMAP : GMap.NET.WindowsForms.GMapControl
     {
         public bool inOnPaint = false;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs
index 50e01de71..a9966cb92 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs
@@ -141,13 +141,13 @@
             this.RLL2SRV_P = new System.Windows.Forms.NumericUpDown();
             this.label52 = new System.Windows.Forms.Label();
             this.TabAC = new System.Windows.Forms.TabPage();
-            this.myLabel4 = new ArdupilotMega.MyLabel();
-            this.myLabel3 = new ArdupilotMega.MyLabel();
+            this.myLabel4 = new ArdupilotMega.Controls.MyLabel();
+            this.myLabel3 = new ArdupilotMega.Controls.MyLabel();
             this.TUNE_LOW = new System.Windows.Forms.NumericUpDown();
             this.TUNE_HIGH = new System.Windows.Forms.NumericUpDown();
-            this.myLabel2 = new ArdupilotMega.MyLabel();
+            this.myLabel2 = new ArdupilotMega.Controls.MyLabel();
             this.TUNE = new System.Windows.Forms.ComboBox();
-            this.myLabel1 = new ArdupilotMega.MyLabel();
+            this.myLabel1 = new ArdupilotMega.Controls.MyLabel();
             this.CH7_OPT = new System.Windows.Forms.ComboBox();
             this.groupBox5 = new System.Windows.Forms.GroupBox();
             this.THR_RATE_D = new System.Windows.Forms.NumericUpDown();
@@ -276,17 +276,17 @@
             this.CHK_hudshow = new System.Windows.Forms.CheckBox();
             this.label92 = new System.Windows.Forms.Label();
             this.CMB_videosources = new System.Windows.Forms.ComboBox();
-            this.BUT_Joystick = new ArdupilotMega.MyButton();
-            this.BUT_videostop = new ArdupilotMega.MyButton();
-            this.BUT_videostart = new ArdupilotMega.MyButton();
+            this.BUT_Joystick = new ArdupilotMega.Controls.MyButton();
+            this.BUT_videostop = new ArdupilotMega.Controls.MyButton();
+            this.BUT_videostart = new ArdupilotMega.Controls.MyButton();
             this.TabSetup = new System.Windows.Forms.TabPage();
             this.label109 = new System.Windows.Forms.Label();
-            this.BUT_rerequestparams = new ArdupilotMega.MyButton();
-            this.BUT_writePIDS = new ArdupilotMega.MyButton();
-            this.BUT_save = new ArdupilotMega.MyButton();
-            this.BUT_load = new ArdupilotMega.MyButton();
+            this.BUT_rerequestparams = new ArdupilotMega.Controls.MyButton();
+            this.BUT_writePIDS = new ArdupilotMega.Controls.MyButton();
+            this.BUT_save = new ArdupilotMega.Controls.MyButton();
+            this.BUT_load = new ArdupilotMega.Controls.MyButton();
             this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
-            this.BUT_compare = new ArdupilotMega.MyButton();
+            this.BUT_compare = new ArdupilotMega.Controls.MyButton();
             this.groupBox17 = new System.Windows.Forms.GroupBox();
             this.LOITER_LAT_D = new System.Windows.Forms.NumericUpDown();
             this.label28 = new System.Windows.Forms.Label();
@@ -2333,10 +2333,10 @@
 
         #endregion
 
-        private MyButton BUT_save;
-        private MyButton BUT_load;
+        private ArdupilotMega.Controls.MyButton BUT_save;
+        private ArdupilotMega.Controls.MyButton BUT_load;
         private System.Windows.Forms.DataGridView Params;
-        private MyButton BUT_writePIDS;
+        private ArdupilotMega.Controls.MyButton BUT_writePIDS;
         private System.Windows.Forms.TabControl ConfigTabs;
         private System.Windows.Forms.TabPage TabAP;
         private System.Windows.Forms.TabPage TabAC;
@@ -2505,8 +2505,8 @@
         private System.Windows.Forms.TabPage TabPlanner;
         private System.Windows.Forms.Label label92;
         private System.Windows.Forms.ComboBox CMB_videosources;
-        private MyButton BUT_videostop;
-        private MyButton BUT_videostart;
+        private ArdupilotMega.Controls.MyButton BUT_videostop;
+        private ArdupilotMega.Controls.MyButton BUT_videostart;
         private System.Windows.Forms.CheckBox CHK_hudshow;
         private System.Windows.Forms.CheckBox CHK_enablespeech;
         private System.Windows.Forms.ComboBox CMB_language;
@@ -2516,9 +2516,9 @@
         private System.Windows.Forms.CheckBox CHK_speechwaypoint;
         private System.Windows.Forms.CheckBox CHK_speechmode;
         private System.Windows.Forms.CheckBox CHK_speechcustom;
-        private MyButton BUT_rerequestparams;
+        private ArdupilotMega.Controls.MyButton BUT_rerequestparams;
         private System.Windows.Forms.CheckBox CHK_speechbattery;
-        private MyButton BUT_Joystick;
+        private ArdupilotMega.Controls.MyButton BUT_Joystick;
         private System.Windows.Forms.Label label96;
         private System.Windows.Forms.Label label95;
         private System.Windows.Forms.ComboBox CMB_speedunits;
@@ -2553,7 +2553,7 @@
         private System.Windows.Forms.DataGridViewTextBoxColumn Default;
         private System.Windows.Forms.DataGridViewTextBoxColumn mavScale;
         private System.Windows.Forms.DataGridViewTextBoxColumn RawValue;
-        private MyButton BUT_compare;
+        private ArdupilotMega.Controls.MyButton BUT_compare;
         private System.Windows.Forms.Label label12;
         private System.Windows.Forms.CheckBox CHK_GDIPlus;
         private System.Windows.Forms.GroupBox groupBox5;
@@ -2566,9 +2566,9 @@
         private System.Windows.Forms.Label label109;
         private System.Windows.Forms.Label label14;
         private System.Windows.Forms.Label label26;
-        private MyLabel myLabel1;
+        private ArdupilotMega.Controls.MyLabel myLabel1;
         private System.Windows.Forms.ComboBox CH7_OPT;
-        private MyLabel myLabel2;
+        private ArdupilotMega.Controls.MyLabel myLabel2;
         private System.Windows.Forms.ComboBox TUNE;
         private System.Windows.Forms.NumericUpDown RATE_YAW_D;
         private System.Windows.Forms.Label label10;
@@ -2586,8 +2586,8 @@
         private System.Windows.Forms.NumericUpDown TUNE_HIGH;
         private System.Windows.Forms.Label label33;
         private System.Windows.Forms.ComboBox CMB_ratesensors;
-        private MyLabel myLabel4;
-        private MyLabel myLabel3;
+        private ArdupilotMega.Controls.MyLabel myLabel4;
+        private ArdupilotMega.Controls.MyLabel myLabel3;
         private System.Windows.Forms.GroupBox groupBox17;
         private System.Windows.Forms.NumericUpDown LOITER_LAT_D;
         private System.Windows.Forms.Label label28;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
index fd5a942cd..6d3ff562e 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
@@ -13,6 +13,7 @@ using System.Globalization;
 using System.Threading;
 using DirectShowLib;
 using System.Runtime.InteropServices;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx
index 7f73de58f..8aed12b21 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx
@@ -367,7 +367,7 @@
     <value>myLabel2</value>
   </data>
   <data name="&gt;&gt;myLabel2.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;myLabel2.Parent" xml:space="preserve">
     <value>groupBox17</value>
@@ -379,7 +379,7 @@
     <value>myLabel4</value>
   </data>
   <data name="&gt;&gt;myLabel4.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;myLabel4.Parent" xml:space="preserve">
     <value>groupBox17</value>
@@ -403,7 +403,7 @@
     <value>myLabel3</value>
   </data>
   <data name="&gt;&gt;myLabel3.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;myLabel3.Parent" xml:space="preserve">
     <value>groupBox17</value>
@@ -415,7 +415,7 @@
     <value>myLabel1</value>
   </data>
   <data name="&gt;&gt;myLabel1.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;myLabel1.Parent" xml:space="preserve">
     <value>groupBox17</value>
@@ -2341,7 +2341,7 @@
     <value>BUT_Joystick</value>
   </data>
   <data name="&gt;&gt;BUT_Joystick.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_Joystick.Parent" xml:space="preserve">
     <value>TabPlanner</value>
@@ -2353,7 +2353,7 @@
     <value>BUT_videostop</value>
   </data>
   <data name="&gt;&gt;BUT_videostop.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_videostop.Parent" xml:space="preserve">
     <value>TabPlanner</value>
@@ -2365,7 +2365,7 @@
     <value>BUT_videostart</value>
   </data>
   <data name="&gt;&gt;BUT_videostart.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_videostart.Parent" xml:space="preserve">
     <value>TabPlanner</value>
@@ -5926,7 +5926,7 @@
     <value>myLabel4</value>
   </data>
   <data name="&gt;&gt;myLabel4.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;myLabel4.Parent" xml:space="preserve">
     <value>groupBox17</value>
@@ -5950,7 +5950,7 @@
     <value>myLabel3</value>
   </data>
   <data name="&gt;&gt;myLabel3.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;myLabel3.Parent" xml:space="preserve">
     <value>groupBox17</value>
@@ -6016,7 +6016,7 @@
     <value>myLabel2</value>
   </data>
   <data name="&gt;&gt;myLabel2.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;myLabel2.Parent" xml:space="preserve">
     <value>groupBox17</value>
@@ -6127,7 +6127,7 @@
     <value>myLabel1</value>
   </data>
   <data name="&gt;&gt;myLabel1.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;myLabel1.Parent" xml:space="preserve">
     <value>groupBox17</value>
@@ -9018,7 +9018,7 @@ GDI+ = Enabled</value>
     <value>BUT_Joystick</value>
   </data>
   <data name="&gt;&gt;BUT_Joystick.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_Joystick.Parent" xml:space="preserve">
     <value>TabPlanner</value>
@@ -9045,7 +9045,7 @@ GDI+ = Enabled</value>
     <value>BUT_videostop</value>
   </data>
   <data name="&gt;&gt;BUT_videostop.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_videostop.Parent" xml:space="preserve">
     <value>TabPlanner</value>
@@ -9072,7 +9072,7 @@ GDI+ = Enabled</value>
     <value>BUT_videostart</value>
   </data>
   <data name="&gt;&gt;BUT_videostart.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_videostart.Parent" xml:space="preserve">
     <value>TabPlanner</value>
@@ -9120,7 +9120,7 @@ GDI+ = Enabled</value>
     <value>BUT_rerequestparams</value>
   </data>
   <data name="&gt;&gt;BUT_rerequestparams.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_rerequestparams.Parent" xml:space="preserve">
     <value>$this</value>
@@ -9153,7 +9153,7 @@ GDI+ = Enabled</value>
     <value>BUT_writePIDS</value>
   </data>
   <data name="&gt;&gt;BUT_writePIDS.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_writePIDS.Parent" xml:space="preserve">
     <value>$this</value>
@@ -9189,7 +9189,7 @@ GDI+ = Enabled</value>
     <value>BUT_save</value>
   </data>
   <data name="&gt;&gt;BUT_save.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_save.Parent" xml:space="preserve">
     <value>$this</value>
@@ -9225,7 +9225,7 @@ GDI+ = Enabled</value>
     <value>BUT_load</value>
   </data>
   <data name="&gt;&gt;BUT_load.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_load.Parent" xml:space="preserve">
     <value>$this</value>
@@ -9258,7 +9258,7 @@ GDI+ = Enabled</value>
     <value>BUT_compare</value>
   </data>
   <data name="&gt;&gt;BUT_compare.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_compare.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.Designer.cs
index e674259f9..c3ddcee8a 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.Designer.cs
@@ -31,7 +31,7 @@
             this.components = new System.ComponentModel.Container();
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigAccelerometerCalibrationPlane));
             this.label28 = new System.Windows.Forms.Label();
-            this.BUT_levelplane = new ArdupilotMega.MyButton();
+            this.BUT_levelplane = new ArdupilotMega.Controls.MyButton();
             this.CHK_manuallevel = new System.Windows.Forms.CheckBox();
             this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
             this.label1 = new System.Windows.Forms.Label();
@@ -88,7 +88,7 @@
         #endregion
 
         private System.Windows.Forms.Label label28;
-        private MyButton BUT_levelplane;
+        private ArdupilotMega.Controls.MyButton BUT_levelplane;
         private System.Windows.Forms.CheckBox CHK_manuallevel;
         private System.Windows.Forms.ToolTip toolTip1;
         private System.Windows.Forms.Label label1;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs
index 6837cc9ce..5c08a8ab7 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs
@@ -7,6 +7,7 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega.Controls.BackstageView;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews.ConfigurationView
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.resx
index a4f728808..062a6b34a 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.resx
@@ -175,7 +175,7 @@
     <value>BUT_levelplane</value>
   </data>
   <data name="&gt;&gt;BUT_levelplane.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4492.39671, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4492.39671, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_levelplane.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.Designer.cs
index 823abeb9a..b9e95dff5 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.Designer.cs
@@ -33,7 +33,7 @@
             this.label15 = new System.Windows.Forms.Label();
             this.pictureBoxQuadX = new System.Windows.Forms.PictureBox();
             this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
-            this.BUT_levelac2 = new ArdupilotMega.MyButton();
+            this.BUT_levelac2 = new ArdupilotMega.Controls.MyButton();
             this.pictureBox1 = new System.Windows.Forms.PictureBox();
             this.pictureBox2 = new System.Windows.Forms.PictureBox();
             this.pictureBox3 = new System.Windows.Forms.PictureBox();
@@ -149,7 +149,7 @@
         private System.Windows.Forms.Label label15;
         private System.Windows.Forms.PictureBox pictureBoxQuadX;
         private System.Windows.Forms.PictureBox pictureBoxQuad;
-        private MyButton BUT_levelac2;
+        private ArdupilotMega.Controls.MyButton BUT_levelac2;
         private System.Windows.Forms.PictureBox pictureBox1;
         private System.Windows.Forms.PictureBox pictureBox2;
         private System.Windows.Forms.PictureBox pictureBox3;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs
index 5da92ae68..7cc693578 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs
@@ -7,6 +7,7 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega.Controls.BackstageView;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews.ConfigurationView
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.resx
index fafc62b41..d21598f12 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.resx
@@ -250,7 +250,7 @@
     <value>BUT_levelac2</value>
   </data>
   <data name="&gt;&gt;BUT_levelac2.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4496.35237, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4496.35237, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_levelac2.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
index a67ec30bd..ec5d7ca2c 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
@@ -30,12 +30,12 @@
         {
             this.components = new System.ComponentModel.Container();
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigArducopter));
-            this.myLabel3 = new ArdupilotMega.MyLabel();
+            this.myLabel3 = new ArdupilotMega.Controls.MyLabel();
             this.TUNE_LOW = new System.Windows.Forms.NumericUpDown();
             this.TUNE_HIGH = new System.Windows.Forms.NumericUpDown();
-            this.myLabel2 = new ArdupilotMega.MyLabel();
+            this.myLabel2 = new ArdupilotMega.Controls.MyLabel();
             this.TUNE = new System.Windows.Forms.ComboBox();
-            this.myLabel1 = new ArdupilotMega.MyLabel();
+            this.myLabel1 = new ArdupilotMega.Controls.MyLabel();
             this.CH7_OPT = new System.Windows.Forms.ComboBox();
             this.groupBox5 = new System.Windows.Forms.GroupBox();
             this.THR_RATE_D = new System.Windows.Forms.NumericUpDown();
@@ -868,12 +868,12 @@
 
         #endregion
 
-        private MyLabel myLabel3;
+        private ArdupilotMega.Controls.MyLabel myLabel3;
         private System.Windows.Forms.NumericUpDown TUNE_LOW;
         private System.Windows.Forms.NumericUpDown TUNE_HIGH;
-        private MyLabel myLabel2;
+        private ArdupilotMega.Controls.MyLabel myLabel2;
         private System.Windows.Forms.ComboBox TUNE;
-        private MyLabel myLabel1;
+        private ArdupilotMega.Controls.MyLabel myLabel1;
         private System.Windows.Forms.ComboBox CH7_OPT;
         private System.Windows.Forms.GroupBox groupBox5;
         private System.Windows.Forms.NumericUpDown THR_RATE_D;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs
index 606a5f34d..ce263e44c 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs
@@ -8,6 +8,7 @@ using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega.Controls.BackstageView;
 using System.Collections;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews.ConfigurationView
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx
index 1be2fe2b2..c404907f7 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx
@@ -135,7 +135,7 @@
     <value>myLabel3</value>
   </data>
   <data name="&gt;&gt;myLabel3.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;myLabel3.Parent" xml:space="preserve">
     <value>$this</value>
@@ -201,7 +201,7 @@
     <value>myLabel2</value>
   </data>
   <data name="&gt;&gt;myLabel2.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;myLabel2.Parent" xml:space="preserve">
     <value>$this</value>
@@ -312,7 +312,7 @@
     <value>myLabel1</value>
   </data>
   <data name="&gt;&gt;myLabel1.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;myLabel1.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs
index 34afb1dc4..11bbb4fb8 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs
@@ -8,6 +8,7 @@ using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega.Controls.BackstageView;
 using System.Collections;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews.ConfigurationView
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs
index d84fe9af3..404f48b84 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs
@@ -7,6 +7,7 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega.Controls.BackstageView;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews.ConfigurationView
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs
index ed3be8b22..a9c3c3d32 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs
@@ -59,7 +59,7 @@
             this.CMB_fmode2 = new System.Windows.Forms.ComboBox();
             this.label1 = new System.Windows.Forms.Label();
             this.CMB_fmode1 = new System.Windows.Forms.ComboBox();
-            this.BUT_SaveModes = new ArdupilotMega.MyButton();
+            this.BUT_SaveModes = new ArdupilotMega.Controls.MyButton();
             ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
             this.SuspendLayout();
             // 
@@ -312,7 +312,7 @@
         private System.Windows.Forms.ComboBox CMB_fmode2;
         private System.Windows.Forms.Label label1;
         private System.Windows.Forms.ComboBox CMB_fmode1;
-        private MyButton BUT_SaveModes;
+        private ArdupilotMega.Controls.MyButton BUT_SaveModes;
         private System.Windows.Forms.BindingSource currentStateBindingSource;
     }
 }
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs
index a19aa5c25..3e89a1328 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs
@@ -8,6 +8,7 @@ using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega.Controls.BackstageView;
 using ArdupilotMega.Utilities;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews.ConfigurationView
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx
index 7f2a0fb98..5fe9928d4 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx
@@ -946,7 +946,7 @@
     <value>BUT_SaveModes</value>
   </data>
   <data name="&gt;&gt;BUT_SaveModes.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_SaveModes.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs
index e5a2e07ea..dedab86cf 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs
@@ -29,7 +29,7 @@
         private void InitializeComponent()
         {
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigHardwareOptions));
-            this.BUT_MagCalibrationLive = new ArdupilotMega.MyButton();
+            this.BUT_MagCalibrationLive = new ArdupilotMega.Controls.MyButton();
             this.label27 = new System.Windows.Forms.Label();
             this.CMB_sonartype = new System.Windows.Forms.ComboBox();
             this.CHK_enableoptflow = new System.Windows.Forms.CheckBox();
@@ -43,7 +43,7 @@
             this.pictureBox4 = new System.Windows.Forms.PictureBox();
             this.pictureBox3 = new System.Windows.Forms.PictureBox();
             this.pictureBox1 = new System.Windows.Forms.PictureBox();
-            this.BUT_MagCalibrationLog = new ArdupilotMega.MyButton();
+            this.BUT_MagCalibrationLog = new ArdupilotMega.Controls.MyButton();
             this.CHK_autodec = new System.Windows.Forms.CheckBox();
             ((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit();
             ((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).BeginInit();
@@ -202,7 +202,7 @@
 
         #endregion
 
-        private MyButton BUT_MagCalibrationLive;
+        private ArdupilotMega.Controls.MyButton BUT_MagCalibrationLive;
         private System.Windows.Forms.Label label27;
         private System.Windows.Forms.ComboBox CMB_sonartype;
         private System.Windows.Forms.CheckBox CHK_enableoptflow;
@@ -216,7 +216,7 @@
         private System.Windows.Forms.PictureBox pictureBox4;
         private System.Windows.Forms.PictureBox pictureBox3;
         private System.Windows.Forms.PictureBox pictureBox1;
-        private MyButton BUT_MagCalibrationLog;
+        private ArdupilotMega.Controls.MyButton BUT_MagCalibrationLog;
         private System.Windows.Forms.CheckBox CHK_autodec;
     }
 }
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs
index e804b8052..b9795fb11 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs
@@ -7,6 +7,7 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega.Controls.BackstageView;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews.ConfigurationView
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx
index b15fe2836..64dab98e7 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx
@@ -139,7 +139,7 @@
     <value>BUT_MagCalibrationLive</value>
   </data>
   <data name="&gt;&gt;BUT_MagCalibrationLive.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_MagCalibrationLive.Parent" xml:space="preserve">
     <value>$this</value>
@@ -526,7 +526,7 @@
     <value>BUT_MagCalibrationLog</value>
   </data>
   <data name="&gt;&gt;BUT_MagCalibrationLog.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_MagCalibrationLog.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs
index 3b6108454..2bd405121 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs
@@ -71,9 +71,9 @@
             this.CHK_hudshow = new System.Windows.Forms.CheckBox();
             this.label92 = new System.Windows.Forms.Label();
             this.CMB_videosources = new System.Windows.Forms.ComboBox();
-            this.BUT_Joystick = new ArdupilotMega.MyButton();
-            this.BUT_videostop = new ArdupilotMega.MyButton();
-            this.BUT_videostart = new ArdupilotMega.MyButton();
+            this.BUT_Joystick = new ArdupilotMega.Controls.MyButton();
+            this.BUT_videostop = new ArdupilotMega.Controls.MyButton();
+            this.BUT_videostart = new ArdupilotMega.Controls.MyButton();
             ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).BeginInit();
             this.SuspendLayout();
             // 
@@ -512,8 +512,8 @@
         private System.Windows.Forms.CheckBox CHK_hudshow;
         private System.Windows.Forms.Label label92;
         private System.Windows.Forms.ComboBox CMB_videosources;
-        private MyButton BUT_Joystick;
-        private MyButton BUT_videostop;
-        private MyButton BUT_videostart;
+        private ArdupilotMega.Controls.MyButton BUT_Joystick;
+        private ArdupilotMega.Controls.MyButton BUT_videostop;
+        private ArdupilotMega.Controls.MyButton BUT_videostart;
     }
 }
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
index 3e35ec89c..11e3e4a01 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
@@ -10,6 +10,7 @@ using System.Text;
 using System.Windows.Forms;
 using DirectShowLib;
 using ArdupilotMega.Controls.BackstageView;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews.ConfigurationView
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx
index 6e7580407..8e15fbeac 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx
@@ -1268,7 +1268,7 @@
     <value>BUT_Joystick</value>
   </data>
   <data name="&gt;&gt;BUT_Joystick.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_Joystick.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1295,7 +1295,7 @@
     <value>BUT_videostop</value>
   </data>
   <data name="&gt;&gt;BUT_videostop.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_videostop.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1322,7 +1322,7 @@
     <value>BUT_videostart</value>
   </data>
   <data name="&gt;&gt;BUT_videostart.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_videostart.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs
index f3e54cffe..2ef80c22a 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs
@@ -39,7 +39,7 @@
             this.CHK_revch4 = new System.Windows.Forms.CheckBox();
             this.CHK_revch2 = new System.Windows.Forms.CheckBox();
             this.CHK_revch1 = new System.Windows.Forms.CheckBox();
-            this.BUT_Calibrateradio = new ArdupilotMega.MyButton();
+            this.BUT_Calibrateradio = new ArdupilotMega.Controls.MyButton();
             this.BAR8 = new ArdupilotMega.HorizontalProgressBar2();
             this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
             this.BAR7 = new ArdupilotMega.HorizontalProgressBar2();
@@ -289,7 +289,7 @@
         private System.Windows.Forms.CheckBox CHK_revch4;
         private System.Windows.Forms.CheckBox CHK_revch2;
         private System.Windows.Forms.CheckBox CHK_revch1;
-        private MyButton BUT_Calibrateradio;
+        private ArdupilotMega.Controls.MyButton BUT_Calibrateradio;
         private HorizontalProgressBar2 BAR8;
         private HorizontalProgressBar2 BAR7;
         private HorizontalProgressBar2 BAR6;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs
index 91e6716fe..1cf26eaca 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs
@@ -7,6 +7,7 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega.Controls.BackstageView;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews.ConfigurationView
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx
index f4c0f26f3..55749712e 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx
@@ -403,7 +403,7 @@
     <value>BUT_Calibrateradio</value>
   </data>
   <data name="&gt;&gt;BUT_Calibrateradio.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_Calibrateradio.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
index 389ce857b..6b072f30b 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
@@ -32,11 +32,11 @@
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigRawParams));
             System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
             System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
-            this.BUT_compare = new ArdupilotMega.MyButton();
-            this.BUT_rerequestparams = new ArdupilotMega.MyButton();
-            this.BUT_writePIDS = new ArdupilotMega.MyButton();
-            this.BUT_save = new ArdupilotMega.MyButton();
-            this.BUT_load = new ArdupilotMega.MyButton();
+            this.BUT_compare = new ArdupilotMega.Controls.MyButton();
+            this.BUT_rerequestparams = new ArdupilotMega.Controls.MyButton();
+            this.BUT_writePIDS = new ArdupilotMega.Controls.MyButton();
+            this.BUT_save = new ArdupilotMega.Controls.MyButton();
+            this.BUT_load = new ArdupilotMega.Controls.MyButton();
             this.Params = new System.Windows.Forms.DataGridView();
             this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
             this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn();
@@ -159,11 +159,11 @@
 
         #endregion
 
-        private MyButton BUT_compare;
-        private MyButton BUT_rerequestparams;
-        private MyButton BUT_writePIDS;
-        private MyButton BUT_save;
-        private MyButton BUT_load;
+        private ArdupilotMega.Controls.MyButton BUT_compare;
+        private ArdupilotMega.Controls.MyButton BUT_rerequestparams;
+        private ArdupilotMega.Controls.MyButton BUT_writePIDS;
+        private ArdupilotMega.Controls.MyButton BUT_save;
+        private ArdupilotMega.Controls.MyButton BUT_load;
         private System.Windows.Forms.DataGridView Params;
         private System.Windows.Forms.DataGridViewTextBoxColumn Command;
         private System.Windows.Forms.DataGridViewTextBoxColumn Value;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
index a131ea1b1..a831f31c1 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
@@ -10,6 +10,7 @@ using System.Text;
 using System.Windows.Forms;
 using log4net;
 using ArdupilotMega.Controls.BackstageView;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews.ConfigurationView
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx
index 3a3f70f56..e4bef97a5 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx
@@ -142,7 +142,7 @@
     <value>BUT_compare</value>
   </data>
   <data name="&gt;&gt;BUT_compare.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_compare.Parent" xml:space="preserve">
     <value>$this</value>
@@ -172,7 +172,7 @@
     <value>BUT_rerequestparams</value>
   </data>
   <data name="&gt;&gt;BUT_rerequestparams.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_rerequestparams.Parent" xml:space="preserve">
     <value>$this</value>
@@ -202,7 +202,7 @@
     <value>BUT_writePIDS</value>
   </data>
   <data name="&gt;&gt;BUT_writePIDS.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_writePIDS.Parent" xml:space="preserve">
     <value>$this</value>
@@ -235,7 +235,7 @@
     <value>BUT_save</value>
   </data>
   <data name="&gt;&gt;BUT_save.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_save.Parent" xml:space="preserve">
     <value>$this</value>
@@ -268,7 +268,7 @@
     <value>BUT_load</value>
   </data>
   <data name="&gt;&gt;BUT_load.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_load.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs
index 211699c11..7a4c66226 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs
@@ -33,20 +33,20 @@
             this.groupBox5 = new System.Windows.Forms.GroupBox();
             this.H_SWASH_TYPE = new System.Windows.Forms.RadioButton();
             this.CCPM = new System.Windows.Forms.RadioButton();
-            this.BUT_swash_manual = new ArdupilotMega.MyButton();
+            this.BUT_swash_manual = new ArdupilotMega.Controls.MyButton();
             this.label41 = new System.Windows.Forms.Label();
             this.groupBox3 = new System.Windows.Forms.GroupBox();
             this.label46 = new System.Windows.Forms.Label();
             this.label45 = new System.Windows.Forms.Label();
             this.H_GYR_ENABLE = new System.Windows.Forms.CheckBox();
             this.H_GYR_GAIN = new System.Windows.Forms.TextBox();
-            this.BUT_HS4save = new ArdupilotMega.MyButton();
+            this.BUT_HS4save = new ArdupilotMega.Controls.MyButton();
             this.label21 = new System.Windows.Forms.Label();
             this.H_COL_MIN = new System.Windows.Forms.TextBox();
             this.groupBox1 = new System.Windows.Forms.GroupBox();
             this.H_COL_MID = new System.Windows.Forms.TextBox();
             this.H_COL_MAX = new System.Windows.Forms.TextBox();
-            this.BUT_0collective = new ArdupilotMega.MyButton();
+            this.BUT_0collective = new ArdupilotMega.Controls.MyButton();
             this.groupBox2 = new System.Windows.Forms.GroupBox();
             this.label24 = new System.Windows.Forms.Label();
             this.HS4_MIN = new System.Windows.Forms.TextBox();
@@ -709,20 +709,20 @@
         private System.Windows.Forms.GroupBox groupBox5;
         private System.Windows.Forms.RadioButton H_SWASH_TYPE;
         private System.Windows.Forms.RadioButton CCPM;
-        private MyButton BUT_swash_manual;
+        private ArdupilotMega.Controls.MyButton BUT_swash_manual;
         private System.Windows.Forms.Label label41;
         private System.Windows.Forms.GroupBox groupBox3;
         private System.Windows.Forms.Label label46;
         private System.Windows.Forms.Label label45;
         private System.Windows.Forms.CheckBox H_GYR_ENABLE;
         private System.Windows.Forms.TextBox H_GYR_GAIN;
-        private MyButton BUT_HS4save;
+        private ArdupilotMega.Controls.MyButton BUT_HS4save;
         private System.Windows.Forms.Label label21;
         private System.Windows.Forms.TextBox H_COL_MIN;
         private System.Windows.Forms.GroupBox groupBox1;
         private System.Windows.Forms.TextBox H_COL_MID;
         private System.Windows.Forms.TextBox H_COL_MAX;
-        private MyButton BUT_0collective;
+        private ArdupilotMega.Controls.MyButton BUT_0collective;
         private System.Windows.Forms.GroupBox groupBox2;
         private System.Windows.Forms.Label label24;
         private System.Windows.Forms.TextBox HS4_MIN;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs
index c4d3effe1..6f99332ff 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs
@@ -7,6 +7,7 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega.Controls.BackstageView;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega.GCSViews.ConfigurationView
 {
@@ -428,7 +429,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
                         }
                         if (control[0].GetType() == typeof(MyTrackBar))
                         {
-                            MyTrackBar temp = (MyTrackBar)control[0];
+                            ArdupilotMega.Controls.MyTrackBar temp = (MyTrackBar)control[0];
                             string option = MainV2.comPort.param[value].ToString();
                             temp.Value = int.Parse(option);
                         }
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx
index 133ab792d..56cc3b35a 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx
@@ -217,7 +217,7 @@
     <value>BUT_swash_manual</value>
   </data>
   <data name="&gt;&gt;BUT_swash_manual.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_swash_manual.Parent" xml:space="preserve">
     <value>$this</value>
@@ -409,7 +409,7 @@
     <value>BUT_HS4save</value>
   </data>
   <data name="&gt;&gt;BUT_HS4save.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_HS4save.Parent" xml:space="preserve">
     <value>$this</value>
@@ -550,7 +550,7 @@
     <value>BUT_0collective</value>
   </data>
   <data name="&gt;&gt;BUT_0collective.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_0collective.Parent" xml:space="preserve">
     <value>groupBox1</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs
index 780efaf1c..60cc50f7b 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs
@@ -20,7 +20,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
             this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigFlightModes(), "Flight Modes"));
             this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigHardwareOptions(), "Hardware Options"));
             this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigBatteryMonitoring(), "Battery Monitor"));
-            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibrationQuad(), "Level Calibration"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibrationQuad(), "ArduCopter"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibrationPlane(), "ArduPlane"));
             this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigArducopter(), "Arducopter Setup"));
             this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigArduplane(), "Arduplane Setup"));
             this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigTradHeli(), "Heli Setup"));
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
index fbd2dcbc8..9b1340816 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
@@ -24,6 +24,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
             this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibrationPlane(), "ArduPlane Level"));
             this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigTradHeli(), "Heli Setup"));
 
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigRawParams(), "Raw params (Advanced)"));
+
             this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ArdupilotMega._3DRradio(), "3DR Radio"));
 
             this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ArdupilotMega.Antenna.Tracker(), "Antenna Tracker"));
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.Designer.cs
index fa56951ee..8dd501436 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.Designer.cs
@@ -36,43 +36,43 @@ namespace ArdupilotMega.GCSViews
         }
         
         
-        private ImageLabel pictureBoxAPM;
-        private ImageLabel pictureBoxQuad;
-        private ImageLabel pictureBoxHexa;
-        private ImageLabel pictureBoxTri;
-        private ImageLabel pictureBoxY6;
+        private ArdupilotMega.Controls.ImageLabel pictureBoxAPM;
+        private ArdupilotMega.Controls.ImageLabel pictureBoxQuad;
+        private ArdupilotMega.Controls.ImageLabel pictureBoxHexa;
+        private ArdupilotMega.Controls.ImageLabel pictureBoxTri;
+        private ArdupilotMega.Controls.ImageLabel pictureBoxY6;
         private System.Windows.Forms.Label lbl_status;
         private System.Windows.Forms.ProgressBar progress;
         private System.Windows.Forms.Label label2;
-        private ImageLabel pictureBoxHeli;
-        private MyButton BUT_setup;
+        private ArdupilotMega.Controls.ImageLabel pictureBoxHeli;
+        private ArdupilotMega.Controls.MyButton BUT_setup;
         private PictureBox pictureBoxHilimage;
         private PictureBox pictureBoxAPHil;
         private PictureBox pictureBoxACHil;
         private PictureBox pictureBoxACHHil;
-        private ImageLabel pictureBoxOcta;
+        private ArdupilotMega.Controls.ImageLabel pictureBoxOcta;
         private Label label1;
-        private ImageLabel pictureBoxOctav;
+        private ArdupilotMega.Controls.ImageLabel pictureBoxOctav;
 
         private void InitializeComponent()
         {
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Firmware));
-            this.pictureBoxAPM = new ArdupilotMega.ImageLabel();
-            this.pictureBoxQuad = new ArdupilotMega.ImageLabel();
-            this.pictureBoxHexa = new ArdupilotMega.ImageLabel();
-            this.pictureBoxTri = new ArdupilotMega.ImageLabel();
-            this.pictureBoxY6 = new ArdupilotMega.ImageLabel();
+            this.pictureBoxAPM = new ArdupilotMega.Controls.ImageLabel();
+            this.pictureBoxQuad = new ArdupilotMega.Controls.ImageLabel();
+            this.pictureBoxHexa = new ArdupilotMega.Controls.ImageLabel();
+            this.pictureBoxTri = new ArdupilotMega.Controls.ImageLabel();
+            this.pictureBoxY6 = new ArdupilotMega.Controls.ImageLabel();
             this.lbl_status = new System.Windows.Forms.Label();
             this.progress = new System.Windows.Forms.ProgressBar();
             this.label2 = new System.Windows.Forms.Label();
-            this.pictureBoxHeli = new ArdupilotMega.ImageLabel();
-            this.BUT_setup = new ArdupilotMega.MyButton();
+            this.pictureBoxHeli = new ArdupilotMega.Controls.ImageLabel();
+            this.BUT_setup = new ArdupilotMega.Controls.MyButton();
             this.pictureBoxHilimage = new System.Windows.Forms.PictureBox();
             this.pictureBoxAPHil = new System.Windows.Forms.PictureBox();
             this.pictureBoxACHil = new System.Windows.Forms.PictureBox();
             this.pictureBoxACHHil = new System.Windows.Forms.PictureBox();
-            this.pictureBoxOcta = new ArdupilotMega.ImageLabel();
-            this.pictureBoxOctav = new ArdupilotMega.ImageLabel();
+            this.pictureBoxOcta = new ArdupilotMega.Controls.ImageLabel();
+            this.pictureBoxOctav = new ArdupilotMega.Controls.ImageLabel();
             this.label1 = new System.Windows.Forms.Label();
             ((System.ComponentModel.ISupportInitialize)(this.pictureBoxHilimage)).BeginInit();
             ((System.ComponentModel.ISupportInitialize)(this.pictureBoxAPHil)).BeginInit();
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
index 8971889c8..cc696b674 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
@@ -7,6 +7,7 @@ using System.IO;
 using System.Xml;
 using System.Net;
 using log4net;
+using ArdupilotMega.Arduino;
 
 namespace ArdupilotMega.GCSViews
 {
@@ -223,42 +224,6 @@ namespace ArdupilotMega.GCSViews
                 }
                 return;
             }
-            else if (items.Count == 2 && false)
-            {
-                XorPlus select = new XorPlus();
-                ThemeManager.ApplyThemeTo(select);
-                select.ShowDialog();
-                int a = 0;
-
-                if (select.frame == "")
-                {
-                    return;
-                }
-
-                foreach (software temp in items)
-                {
-                    if (select.frame == "+" && temp.name.Contains("Plus"))
-                    {
-                        DialogResult dr = CustomMessageBox.Show("Are you sure you want to upload " + items[a].name + "?", "Continue", MessageBoxButtons.YesNo);
-                        if (dr == System.Windows.Forms.DialogResult.Yes)
-                        {
-                            update(items[a]);
-                            return;
-                        }
-                    }
-                    else if (select.frame == "X" && temp.name.Contains("X"))
-                    {
-                        DialogResult dr = CustomMessageBox.Show("Are you sure you want to upload " + items[a].name + "?", "Continue", MessageBoxButtons.YesNo);
-                        if (dr == System.Windows.Forms.DialogResult.Yes)
-                        {
-                            update(items[a]);
-                            return;
-                        }
-                    }
-
-                    a++;
-                }
-            }
             else
             {
                 CustomMessageBox.Show("Something has gone wrong, to many firmware choices");
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx
index 2f436fe28..be5eb92e0 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx
@@ -367,7 +367,7 @@
     <value>BUT_setup</value>
   </data>
   <data name="&gt;&gt;BUT_setup.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_setup.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs
index 9b17adaae..87435b07a 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs
@@ -15,28 +15,28 @@
             this.pointCameraHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
             this.MainH = new System.Windows.Forms.SplitContainer();
             this.SubMainLeft = new System.Windows.Forms.SplitContainer();
-            this.hud1 = new hud.HUD();
+            this.hud1 = new ArdupilotMega.Controls.HUD();
             this.contextMenuStrip2 = new System.Windows.Forms.ContextMenuStrip(this.components);
             this.recordHudToAVIToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
             this.stopRecordToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
             this.bindingSource1 = new System.Windows.Forms.BindingSource(this.components);
             this.tabControl1 = new System.Windows.Forms.TabControl();
             this.tabActions = new System.Windows.Forms.TabPage();
-            this.BUT_script = new ArdupilotMega.MyButton();
-            this.BUT_joystick = new ArdupilotMega.MyButton();
-            this.BUT_quickmanual = new ArdupilotMega.MyButton();
-            this.BUT_quickrtl = new ArdupilotMega.MyButton();
-            this.BUT_quickauto = new ArdupilotMega.MyButton();
+            this.BUT_script = new ArdupilotMega.Controls.MyButton();
+            this.BUT_joystick = new ArdupilotMega.Controls.MyButton();
+            this.BUT_quickmanual = new ArdupilotMega.Controls.MyButton();
+            this.BUT_quickrtl = new ArdupilotMega.Controls.MyButton();
+            this.BUT_quickauto = new ArdupilotMega.Controls.MyButton();
             this.CMB_setwp = new System.Windows.Forms.ComboBox();
-            this.BUT_setwp = new ArdupilotMega.MyButton();
+            this.BUT_setwp = new ArdupilotMega.Controls.MyButton();
             this.CMB_modes = new System.Windows.Forms.ComboBox();
-            this.BUT_setmode = new ArdupilotMega.MyButton();
-            this.BUT_clear_track = new ArdupilotMega.MyButton();
+            this.BUT_setmode = new ArdupilotMega.Controls.MyButton();
+            this.BUT_clear_track = new ArdupilotMega.Controls.MyButton();
             this.CMB_action = new System.Windows.Forms.ComboBox();
-            this.BUT_Homealt = new ArdupilotMega.MyButton();
-            this.BUT_RAWSensor = new ArdupilotMega.MyButton();
-            this.BUTrestartmission = new ArdupilotMega.MyButton();
-            this.BUTactiondo = new ArdupilotMega.MyButton();
+            this.BUT_Homealt = new ArdupilotMega.Controls.MyButton();
+            this.BUT_RAWSensor = new ArdupilotMega.Controls.MyButton();
+            this.BUTrestartmission = new ArdupilotMega.Controls.MyButton();
+            this.BUTactiondo = new ArdupilotMega.Controls.MyButton();
             this.tabGauges = new System.Windows.Forms.TabPage();
             this.Gvspeed = new AGaugeApp.AGauge();
             this.Gheading = new AGaugeApp.AGauge();
@@ -44,33 +44,33 @@
             this.Gspeed = new AGaugeApp.AGauge();
             this.tabStatus = new System.Windows.Forms.TabPage();
             this.tabTLogs = new System.Windows.Forms.TabPage();
-            this.lbl_logpercent = new ArdupilotMega.MyLabel();
+            this.lbl_logpercent = new ArdupilotMega.Controls.MyLabel();
             this.NUM_playbackspeed = new System.Windows.Forms.NumericUpDown();
-            this.BUT_log2kml = new ArdupilotMega.MyButton();
+            this.BUT_log2kml = new ArdupilotMega.Controls.MyButton();
             this.tracklog = new System.Windows.Forms.TrackBar();
-            this.BUT_playlog = new ArdupilotMega.MyButton();
-            this.BUT_loadtelem = new ArdupilotMega.MyButton();
+            this.BUT_playlog = new ArdupilotMega.Controls.MyButton();
+            this.BUT_loadtelem = new ArdupilotMega.Controls.MyButton();
             this.tableMap = new System.Windows.Forms.TableLayoutPanel();
             this.splitContainer1 = new System.Windows.Forms.SplitContainer();
             this.zg1 = new ZedGraph.ZedGraphControl();
-            this.lbl_hdop = new ArdupilotMega.MyLabel();
-            this.lbl_sats = new ArdupilotMega.MyLabel();
-            this.lbl_winddir = new ArdupilotMega.MyLabel();
-            this.lbl_windvel = new ArdupilotMega.MyLabel();
-            this.gMapControl1 = new ArdupilotMega.myGMAP();
+            this.lbl_hdop = new ArdupilotMega.Controls.MyLabel();
+            this.lbl_sats = new ArdupilotMega.Controls.MyLabel();
+            this.lbl_winddir = new ArdupilotMega.Controls.MyLabel();
+            this.lbl_windvel = new ArdupilotMega.Controls.MyLabel();
+            this.gMapControl1 = new ArdupilotMega.Controls.myGMAP();
             this.panel1 = new System.Windows.Forms.Panel();
-            this.TXT_lat = new ArdupilotMega.MyLabel();
+            this.TXT_lat = new ArdupilotMega.Controls.MyLabel();
             this.Zoomlevel = new System.Windows.Forms.NumericUpDown();
-            this.label1 = new ArdupilotMega.MyLabel();
-            this.TXT_long = new ArdupilotMega.MyLabel();
-            this.TXT_alt = new ArdupilotMega.MyLabel();
+            this.label1 = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_long = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_alt = new ArdupilotMega.Controls.MyLabel();
             this.CHK_autopan = new System.Windows.Forms.CheckBox();
             this.CB_tuning = new System.Windows.Forms.CheckBox();
             this.dataGridViewImageColumn1 = new System.Windows.Forms.DataGridViewImageColumn();
             this.dataGridViewImageColumn2 = new System.Windows.Forms.DataGridViewImageColumn();
             this.ZedGraphTimer = new System.Windows.Forms.Timer(this.components);
             this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
-            this.label6 = new ArdupilotMega.MyLabel();
+            this.label6 = new ArdupilotMega.Controls.MyLabel();
             this.contextMenuStrip1.SuspendLayout();
             this.MainH.Panel1.SuspendLayout();
             this.MainH.Panel2.SuspendLayout();
@@ -1311,37 +1311,37 @@
 
         private System.Windows.Forms.DataGridViewImageColumn dataGridViewImageColumn1;
         private System.Windows.Forms.DataGridViewImageColumn dataGridViewImageColumn2;
-        private ArdupilotMega.MyLabel label6;
+        private ArdupilotMega.Controls.MyLabel label6;
         private System.Windows.Forms.BindingSource bindingSource1;
         private System.Windows.Forms.Timer ZedGraphTimer;
         private System.Windows.Forms.SplitContainer MainH;
         private System.Windows.Forms.SplitContainer SubMainLeft;
         private System.Windows.Forms.ContextMenuStrip contextMenuStrip1;
         private System.Windows.Forms.ToolStripMenuItem goHereToolStripMenuItem;
-        private hud.HUD hud1;
-        private MyButton BUT_clear_track;
+        private ArdupilotMega.Controls.HUD hud1;
+        private ArdupilotMega.Controls.MyButton BUT_clear_track;
         private System.Windows.Forms.CheckBox CB_tuning;
-        private MyButton BUT_RAWSensor;
-        private MyButton BUTactiondo;
-        private MyButton BUTrestartmission;
+        private ArdupilotMega.Controls.MyButton BUT_RAWSensor;
+        private ArdupilotMega.Controls.MyButton BUTactiondo;
+        private ArdupilotMega.Controls.MyButton BUTrestartmission;
         private System.Windows.Forms.ComboBox CMB_action;
-        private MyButton BUT_Homealt;
+        private ArdupilotMega.Controls.MyButton BUT_Homealt;
         private System.Windows.Forms.TrackBar tracklog;
-        private MyButton BUT_playlog;
-        private MyButton BUT_loadtelem;
+        private ArdupilotMega.Controls.MyButton BUT_playlog;
+        private ArdupilotMega.Controls.MyButton BUT_loadtelem;
         private AGaugeApp.AGauge Gheading;
         private AGaugeApp.AGauge Galt;
         private AGaugeApp.AGauge Gspeed;
         private AGaugeApp.AGauge Gvspeed;
         private System.Windows.Forms.TableLayoutPanel tableMap;
         private System.Windows.Forms.Panel panel1;
-        private ArdupilotMega.MyLabel TXT_lat;
+        private ArdupilotMega.Controls.MyLabel TXT_lat;
         private System.Windows.Forms.NumericUpDown Zoomlevel;
-        private ArdupilotMega.MyLabel label1;
-        private ArdupilotMega.MyLabel TXT_long;
-        private ArdupilotMega.MyLabel TXT_alt;
+        private ArdupilotMega.Controls.MyLabel label1;
+        private ArdupilotMega.Controls.MyLabel TXT_long;
+        private ArdupilotMega.Controls.MyLabel TXT_alt;
         private System.Windows.Forms.CheckBox CHK_autopan;
-        private myGMAP gMapControl1;
+        private ArdupilotMega.Controls.myGMAP gMapControl1;
         private ZedGraph.ZedGraphControl zg1;
         private System.Windows.Forms.TabControl tabControl1;
         private System.Windows.Forms.TabPage tabGauges;
@@ -1349,26 +1349,26 @@
         private System.Windows.Forms.TabPage tabActions;
         private System.Windows.Forms.TabPage tabTLogs;
         private System.Windows.Forms.ComboBox CMB_modes;
-        private MyButton BUT_setmode;
+        private ArdupilotMega.Controls.MyButton BUT_setmode;
         private System.Windows.Forms.ComboBox CMB_setwp;
-        private MyButton BUT_setwp;
-        private MyButton BUT_quickmanual;
-        private MyButton BUT_quickrtl;
-        private MyButton BUT_quickauto;
-        private MyButton BUT_log2kml;
-        private ArdupilotMega.MyLabel lbl_windvel;
-        private ArdupilotMega.MyLabel lbl_winddir;
-        private MyButton BUT_joystick;
+        private ArdupilotMega.Controls.MyButton BUT_setwp;
+        private ArdupilotMega.Controls.MyButton BUT_quickmanual;
+        private ArdupilotMega.Controls.MyButton BUT_quickrtl;
+        private ArdupilotMega.Controls.MyButton BUT_quickauto;
+        private ArdupilotMega.Controls.MyButton BUT_log2kml;
+        private ArdupilotMega.Controls.MyLabel lbl_windvel;
+        private ArdupilotMega.Controls.MyLabel lbl_winddir;
+        private ArdupilotMega.Controls.MyButton BUT_joystick;
         private System.Windows.Forms.ToolTip toolTip1;
         private System.Windows.Forms.NumericUpDown NUM_playbackspeed;
         private System.Windows.Forms.ContextMenuStrip contextMenuStrip2;
         private System.Windows.Forms.ToolStripMenuItem recordHudToAVIToolStripMenuItem;
         private System.Windows.Forms.ToolStripMenuItem stopRecordToolStripMenuItem;
-        private MyLabel lbl_logpercent;
+        private ArdupilotMega.Controls.MyLabel lbl_logpercent;
         private System.Windows.Forms.ToolStripMenuItem pointCameraHereToolStripMenuItem;
         private System.Windows.Forms.SplitContainer splitContainer1;
-        private MyButton BUT_script;
-        private MyLabel lbl_hdop;
-        private MyLabel lbl_sats;
+        private ArdupilotMega.Controls.MyButton BUT_script;
+        private ArdupilotMega.Controls.MyLabel lbl_hdop;
+        private ArdupilotMega.Controls.MyLabel lbl_sats;
     }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
index 11e610087..da690be45 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
@@ -16,6 +16,8 @@ using System.Globalization; // language
 using GMap.NET.WindowsForms.Markers;
 using ZedGraph; // Graphs
 using System.Drawing.Drawing2D;
+using ArdupilotMega.Controls;
+using ArdupilotMega.Utilities;
 
 // written by michael oborne
 namespace ArdupilotMega.GCSViews
@@ -71,7 +73,7 @@ namespace ArdupilotMega.GCSViews
 
         const float deg2rad = (float)(1.0 / rad2deg);
 
-        public static hud.HUD myhud = null;
+        public static ArdupilotMega.Controls.HUD myhud = null;
         public static GMapControl mymap = null;
 
         bool playingLog = false;
@@ -1224,7 +1226,9 @@ namespace ArdupilotMega.GCSViews
 
         private void CMB_modes_Click(object sender, EventArgs e)
         {
-            CMB_modes.DataSource = Enum.GetNames(Common.getModes());
+            CMB_modes.DataSource = Common.getModesList();
+            CMB_modes.ValueMember = "Key";
+            CMB_modes.DisplayMember = "Value";
         }
 
         private void hud1_DoubleClick(object sender, EventArgs e)
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
index 2cbf5522e..8921faf5e 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
@@ -208,7 +208,7 @@
     <value>hud1</value>
   </data>
   <data name="&gt;&gt;hud1.Type" xml:space="preserve">
-    <value>hud.HUD, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>hud.HUD, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;hud1.Parent" xml:space="preserve">
     <value>SubMainLeft.Panel1</value>
@@ -247,7 +247,7 @@
     <value>BUT_script</value>
   </data>
   <data name="&gt;&gt;BUT_script.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_script.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -280,7 +280,7 @@
     <value>BUT_joystick</value>
   </data>
   <data name="&gt;&gt;BUT_joystick.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_joystick.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -310,7 +310,7 @@
     <value>BUT_quickmanual</value>
   </data>
   <data name="&gt;&gt;BUT_quickmanual.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_quickmanual.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -340,7 +340,7 @@
     <value>BUT_quickrtl</value>
   </data>
   <data name="&gt;&gt;BUT_quickrtl.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_quickrtl.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -370,7 +370,7 @@
     <value>BUT_quickauto</value>
   </data>
   <data name="&gt;&gt;BUT_quickauto.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_quickauto.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -424,7 +424,7 @@
     <value>BUT_setwp</value>
   </data>
   <data name="&gt;&gt;BUT_setwp.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_setwp.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -475,7 +475,7 @@
     <value>BUT_setmode</value>
   </data>
   <data name="&gt;&gt;BUT_setmode.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_setmode.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -505,7 +505,7 @@
     <value>BUT_clear_track</value>
   </data>
   <data name="&gt;&gt;BUT_clear_track.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_clear_track.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -556,7 +556,7 @@
     <value>BUT_Homealt</value>
   </data>
   <data name="&gt;&gt;BUT_Homealt.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_Homealt.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -586,7 +586,7 @@
     <value>BUT_RAWSensor</value>
   </data>
   <data name="&gt;&gt;BUT_RAWSensor.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_RAWSensor.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -616,7 +616,7 @@
     <value>BUTrestartmission</value>
   </data>
   <data name="&gt;&gt;BUTrestartmission.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUTrestartmission.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -646,7 +646,7 @@
     <value>BUTactiondo</value>
   </data>
   <data name="&gt;&gt;BUTactiondo.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUTactiondo.Parent" xml:space="preserve">
     <value>tabActions</value>
@@ -700,7 +700,7 @@
     <value>Gvspeed</value>
   </data>
   <data name="&gt;&gt;Gvspeed.Type" xml:space="preserve">
-    <value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;Gvspeed.Parent" xml:space="preserve">
     <value>tabGauges</value>
@@ -730,7 +730,7 @@
     <value>Gheading</value>
   </data>
   <data name="&gt;&gt;Gheading.Type" xml:space="preserve">
-    <value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;Gheading.Parent" xml:space="preserve">
     <value>tabGauges</value>
@@ -760,7 +760,7 @@
     <value>Galt</value>
   </data>
   <data name="&gt;&gt;Galt.Type" xml:space="preserve">
-    <value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;Galt.Parent" xml:space="preserve">
     <value>tabGauges</value>
@@ -793,7 +793,7 @@
     <value>Gspeed</value>
   </data>
   <data name="&gt;&gt;Gspeed.Type" xml:space="preserve">
-    <value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;Gspeed.Parent" xml:space="preserve">
     <value>tabGauges</value>
@@ -874,7 +874,7 @@
     <value>lbl_logpercent</value>
   </data>
   <data name="&gt;&gt;lbl_logpercent.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;lbl_logpercent.Parent" xml:space="preserve">
     <value>tabTLogs</value>
@@ -925,7 +925,7 @@
     <value>BUT_log2kml</value>
   </data>
   <data name="&gt;&gt;BUT_log2kml.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_log2kml.Parent" xml:space="preserve">
     <value>tabTLogs</value>
@@ -976,7 +976,7 @@
     <value>BUT_playlog</value>
   </data>
   <data name="&gt;&gt;BUT_playlog.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_playlog.Parent" xml:space="preserve">
     <value>tabTLogs</value>
@@ -1003,7 +1003,7 @@
     <value>BUT_loadtelem</value>
   </data>
   <data name="&gt;&gt;BUT_loadtelem.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_loadtelem.Parent" xml:space="preserve">
     <value>tabTLogs</value>
@@ -1192,7 +1192,7 @@
     <value>lbl_hdop</value>
   </data>
   <data name="&gt;&gt;lbl_hdop.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;lbl_hdop.Parent" xml:space="preserve">
     <value>splitContainer1.Panel2</value>
@@ -1225,7 +1225,7 @@
     <value>lbl_sats</value>
   </data>
   <data name="&gt;&gt;lbl_sats.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;lbl_sats.Parent" xml:space="preserve">
     <value>splitContainer1.Panel2</value>
@@ -1255,7 +1255,7 @@
     <value>lbl_winddir</value>
   </data>
   <data name="&gt;&gt;lbl_winddir.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;lbl_winddir.Parent" xml:space="preserve">
     <value>splitContainer1.Panel2</value>
@@ -1285,7 +1285,7 @@
     <value>lbl_windvel</value>
   </data>
   <data name="&gt;&gt;lbl_windvel.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;lbl_windvel.Parent" xml:space="preserve">
     <value>splitContainer1.Panel2</value>
@@ -1457,7 +1457,7 @@
     <value>gMapControl1</value>
   </data>
   <data name="&gt;&gt;gMapControl1.Type" xml:space="preserve">
-    <value>ArdupilotMega.myGMAP, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;gMapControl1.Parent" xml:space="preserve">
     <value>splitContainer1.Panel2</value>
@@ -1520,7 +1520,7 @@
     <value>TXT_lat</value>
   </data>
   <data name="&gt;&gt;TXT_lat.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;TXT_lat.Parent" xml:space="preserve">
     <value>panel1</value>
@@ -1577,7 +1577,7 @@
     <value>label1</value>
   </data>
   <data name="&gt;&gt;label1.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;label1.Parent" xml:space="preserve">
     <value>panel1</value>
@@ -1607,7 +1607,7 @@
     <value>TXT_long</value>
   </data>
   <data name="&gt;&gt;TXT_long.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;TXT_long.Parent" xml:space="preserve">
     <value>panel1</value>
@@ -1637,7 +1637,7 @@
     <value>TXT_alt</value>
   </data>
   <data name="&gt;&gt;TXT_alt.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;TXT_alt.Parent" xml:space="preserve">
     <value>panel1</value>
@@ -1838,7 +1838,7 @@
     <value>label6</value>
   </data>
   <data name="&gt;&gt;label6.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;label6.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1916,6 +1916,6 @@
     <value>FlightData</value>
   </data>
   <data name="&gt;&gt;$this.Type" xml:space="preserve">
-    <value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
+    <value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
   </data>
 </root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs
index acadb4b90..524e96127 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs
@@ -61,10 +61,10 @@
             this.TXT_loiterrad = new System.Windows.Forms.TextBox();
             this.label5 = new System.Windows.Forms.Label();
             this.panel5 = new System.Windows.Forms.Panel();
-            this.BUT_write = new ArdupilotMega.MyButton();
-            this.BUT_read = new ArdupilotMega.MyButton();
-            this.SaveFile = new ArdupilotMega.MyButton();
-            this.BUT_loadwpfile = new ArdupilotMega.MyButton();
+            this.BUT_write = new ArdupilotMega.Controls.MyButton();
+            this.BUT_read = new ArdupilotMega.Controls.MyButton();
+            this.SaveFile = new ArdupilotMega.Controls.MyButton();
+            this.BUT_loadwpfile = new ArdupilotMega.Controls.MyButton();
             this.panel1 = new System.Windows.Forms.Panel();
             this.label4 = new System.Windows.Forms.LinkLabel();
             this.label3 = new System.Windows.Forms.Label();
@@ -89,19 +89,19 @@
             this.textBox1 = new System.Windows.Forms.TextBox();
             this.panelWaypoints = new BSE.Windows.Forms.Panel();
             this.splitter1 = new BSE.Windows.Forms.Splitter();
-            this.BUT_loadkml = new ArdupilotMega.MyButton();
-            this.BUT_zoomto = new ArdupilotMega.MyButton();
-            this.BUT_Camera = new ArdupilotMega.MyButton();
-            this.BUT_grid = new ArdupilotMega.MyButton();
-            this.BUT_Prefetch = new ArdupilotMega.MyButton();
-            this.button1 = new ArdupilotMega.MyButton();
-            this.BUT_Add = new ArdupilotMega.MyButton();
+            this.BUT_loadkml = new ArdupilotMega.Controls.MyButton();
+            this.BUT_zoomto = new ArdupilotMega.Controls.MyButton();
+            this.BUT_Camera = new ArdupilotMega.Controls.MyButton();
+            this.BUT_grid = new ArdupilotMega.Controls.MyButton();
+            this.BUT_Prefetch = new ArdupilotMega.Controls.MyButton();
+            this.button1 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_Add = new ArdupilotMega.Controls.MyButton();
             this.panelAction = new BSE.Windows.Forms.Panel();
             this.panelMap = new System.Windows.Forms.Panel();
             this.lbl_distance = new System.Windows.Forms.Label();
             this.lbl_homedist = new System.Windows.Forms.Label();
             this.lbl_prevdist = new System.Windows.Forms.Label();
-            this.MainMap = new myGMAP();
+            this.MainMap = new ArdupilotMega.Controls.myGMAP();
             this.contextMenuStrip1 = new System.Windows.Forms.ContextMenuStrip(this.components);
             this.deleteWPToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
             this.loiterToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
@@ -123,7 +123,7 @@
             this.GeoFencedownloadToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
             this.setReturnLocationToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
             this.loadFromFileToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
-            this.trackBar1 = new ArdupilotMega.MyTrackBar();
+            this.trackBar1 = new ArdupilotMega.Controls.MyTrackBar();
             this.label11 = new System.Windows.Forms.Label();
             this.panelBASE = new System.Windows.Forms.Panel();
             this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
@@ -932,9 +932,9 @@
 
         #endregion
 
-        private MyButton SaveFile;
-        private MyButton BUT_read;
-        private MyButton BUT_write;
+        private ArdupilotMega.Controls.MyButton SaveFile;
+        private ArdupilotMega.Controls.MyButton BUT_read;
+        private ArdupilotMega.Controls.MyButton BUT_write;
         private System.Windows.Forms.Panel panel5;
         private System.Windows.Forms.Panel panel1;
         private System.Windows.Forms.LinkLabel label4;
@@ -955,12 +955,12 @@
         private System.Windows.Forms.TextBox TXT_mousealt;
         private System.Windows.Forms.TextBox TXT_mouselong;
         private System.Windows.Forms.TextBox TXT_mouselat;
-        private MyButton BUT_loadwpfile;
+        private ArdupilotMega.Controls.MyButton BUT_loadwpfile;
         private System.Windows.Forms.ComboBox comboBoxMapType;
         private System.Windows.Forms.Label lbl_status;
         private System.Windows.Forms.DataGridView Commands;
         private System.Windows.Forms.CheckBox CHK_geheight;
-        private MyButton BUT_Add;
+        private ArdupilotMega.Controls.MyButton BUT_Add;
         private System.Windows.Forms.TextBox TXT_WPRad;
         private System.Windows.Forms.TextBox TXT_DefaultAlt;
         private System.Windows.Forms.Label LBL_WPRad;
@@ -968,21 +968,21 @@
         private System.Windows.Forms.TextBox TXT_loiterrad;
         private System.Windows.Forms.Label label5;
         private System.Windows.Forms.CheckBox CHK_holdalt;
-        private MyButton button1;
+        private ArdupilotMega.Controls.MyButton button1;
         private System.Windows.Forms.CheckBox CHK_altmode;
         private BSE.Windows.Forms.Panel panelWaypoints;
         private BSE.Windows.Forms.Panel panelAction;
         private System.Windows.Forms.Panel panelMap;
-        private myGMAP MainMap;
-        private MyTrackBar trackBar1;
+        private ArdupilotMega.Controls.myGMAP MainMap;
+        private ArdupilotMega.Controls.MyTrackBar trackBar1;
         private System.Windows.Forms.Label label11;
         private System.Windows.Forms.Label lbl_distance;
         private System.Windows.Forms.Label lbl_prevdist;
         private BSE.Windows.Forms.Splitter splitter1;
         private System.Windows.Forms.Panel panelBASE;
         private System.Windows.Forms.Label lbl_homedist;
-        private MyButton BUT_Prefetch;
-        private MyButton BUT_grid;
+        private ArdupilotMega.Controls.MyButton BUT_Prefetch;
+        private ArdupilotMega.Controls.MyButton BUT_grid;
         private System.Windows.Forms.ContextMenuStrip contextMenuStrip1;
         private System.Windows.Forms.ToolStripMenuItem ContextMeasure;
         private System.Windows.Forms.ToolTip toolTip1;
@@ -1000,7 +1000,7 @@
         private System.Windows.Forms.ToolStripMenuItem jumpwPToolStripMenuItem;
         private System.Windows.Forms.ToolStripSeparator toolStripSeparator1;
         private System.Windows.Forms.ToolStripMenuItem deleteWPToolStripMenuItem;
-        private MyButton BUT_Camera;
+        private ArdupilotMega.Controls.MyButton BUT_Camera;
         private System.Windows.Forms.DataGridViewComboBoxColumn Command;
         private System.Windows.Forms.DataGridViewTextBoxColumn Param1;
         private System.Windows.Forms.DataGridViewTextBoxColumn Param2;
@@ -1012,8 +1012,8 @@
         private System.Windows.Forms.DataGridViewButtonColumn Delete;
         private System.Windows.Forms.DataGridViewImageColumn Up;
         private System.Windows.Forms.DataGridViewImageColumn Down;
-        private MyButton BUT_zoomto;
-        private MyButton BUT_loadkml;
+        private ArdupilotMega.Controls.MyButton BUT_zoomto;
+        private ArdupilotMega.Controls.MyButton BUT_loadkml;
         private System.Windows.Forms.Timer timer1;
         private System.Windows.Forms.ToolStripMenuItem geoFenceToolStripMenuItem;
         private System.Windows.Forms.ToolStripMenuItem GeoFenceuploadToolStripMenuItem;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
index 5e3863185..bdf89907b 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
@@ -21,6 +21,7 @@ using System.Threading;
 using log4net;
 using SharpKml.Base;
 using SharpKml.Dom;
+using ArdupilotMega.Controls;
 
 
 
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx
index 8db443f0a..f70e995ea 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx
@@ -556,7 +556,7 @@
     <value>BUT_write</value>
   </data>
   <data name="&gt;&gt;BUT_write.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_write.Parent" xml:space="preserve">
     <value>panel5</value>
@@ -583,7 +583,7 @@
     <value>BUT_read</value>
   </data>
   <data name="&gt;&gt;BUT_read.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_read.Parent" xml:space="preserve">
     <value>panel5</value>
@@ -610,7 +610,7 @@
     <value>SaveFile</value>
   </data>
   <data name="&gt;&gt;SaveFile.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;SaveFile.Parent" xml:space="preserve">
     <value>panel5</value>
@@ -637,7 +637,7 @@
     <value>BUT_loadwpfile</value>
   </data>
   <data name="&gt;&gt;BUT_loadwpfile.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_loadwpfile.Parent" xml:space="preserve">
     <value>panel5</value>
@@ -1261,7 +1261,7 @@
     <value>BUT_loadkml</value>
   </data>
   <data name="&gt;&gt;BUT_loadkml.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_loadkml.Parent" xml:space="preserve">
     <value>panelWaypoints</value>
@@ -1291,7 +1291,7 @@
     <value>BUT_zoomto</value>
   </data>
   <data name="&gt;&gt;BUT_zoomto.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_zoomto.Parent" xml:space="preserve">
     <value>panelWaypoints</value>
@@ -1321,7 +1321,7 @@
     <value>BUT_Camera</value>
   </data>
   <data name="&gt;&gt;BUT_Camera.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_Camera.Parent" xml:space="preserve">
     <value>panelWaypoints</value>
@@ -1351,7 +1351,7 @@
     <value>BUT_grid</value>
   </data>
   <data name="&gt;&gt;BUT_grid.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_grid.Parent" xml:space="preserve">
     <value>panelWaypoints</value>
@@ -1381,7 +1381,7 @@
     <value>BUT_Prefetch</value>
   </data>
   <data name="&gt;&gt;BUT_Prefetch.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_Prefetch.Parent" xml:space="preserve">
     <value>panelWaypoints</value>
@@ -1411,7 +1411,7 @@
     <value>button1</value>
   </data>
   <data name="&gt;&gt;button1.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;button1.Parent" xml:space="preserve">
     <value>panelWaypoints</value>
@@ -1441,7 +1441,7 @@
     <value>BUT_Add</value>
   </data>
   <data name="&gt;&gt;BUT_Add.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_Add.Parent" xml:space="preserve">
     <value>panelWaypoints</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Help.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Help.Designer.cs
index 965140d1d..9151f64fd 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Help.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Help.Designer.cs
@@ -31,7 +31,7 @@
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Help));
             this.richTextBox1 = new System.Windows.Forms.RichTextBox();
             this.CHK_showconsole = new System.Windows.Forms.CheckBox();
-            this.BUT_updatecheck = new ArdupilotMega.MyButton();
+            this.BUT_updatecheck = new ArdupilotMega.Controls.MyButton();
             this.SuspendLayout();
             // 
             // richTextBox1
@@ -71,7 +71,7 @@
         #endregion
 
         private System.Windows.Forms.RichTextBox richTextBox1;
-        private MyButton BUT_updatecheck;
+        private ArdupilotMega.Controls.MyButton BUT_updatecheck;
         private System.Windows.Forms.CheckBox CHK_showconsole;
 
     }
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Help.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Help.resx
index 8d7938a05..f5e2d6cd4 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Help.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Help.resx
@@ -196,7 +196,7 @@
     <value>BUT_updatecheck</value>
   </data>
   <data name="&gt;&gt;BUT_updatecheck.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_updatecheck.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs
index 45318952a..54ae0bb1a 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs
@@ -34,81 +34,81 @@
             this.CHKREV_pitch = new System.Windows.Forms.CheckBox();
             this.CHKREV_rudder = new System.Windows.Forms.CheckBox();
             this.GPSrate = new System.Windows.Forms.ComboBox();
-            this.ConnectComPort = new ArdupilotMega.MyButton();
+            this.ConnectComPort = new ArdupilotMega.Controls.MyButton();
             this.OutputLog = new System.Windows.Forms.RichTextBox();
-            this.TXT_roll = new ArdupilotMega.MyLabel();
-            this.TXT_pitch = new ArdupilotMega.MyLabel();
-            this.TXT_heading = new ArdupilotMega.MyLabel();
-            this.TXT_wpdist = new ArdupilotMega.MyLabel();
+            this.TXT_roll = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_pitch = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_heading = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_wpdist = new ArdupilotMega.Controls.MyLabel();
             this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
-            this.TXT_bererror = new ArdupilotMega.MyLabel();
-            this.TXT_alterror = new ArdupilotMega.MyLabel();
-            this.TXT_lat = new ArdupilotMega.MyLabel();
-            this.TXT_long = new ArdupilotMega.MyLabel();
-            this.TXT_alt = new ArdupilotMega.MyLabel();
-            this.SaveSettings = new ArdupilotMega.MyButton();
+            this.TXT_bererror = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_alterror = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_lat = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_long = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_alt = new ArdupilotMega.Controls.MyLabel();
+            this.SaveSettings = new ArdupilotMega.Controls.MyButton();
             this.RAD_softXplanes = new System.Windows.Forms.RadioButton();
             this.RAD_softFlightGear = new System.Windows.Forms.RadioButton();
-            this.TXT_servoroll = new ArdupilotMega.MyLabel();
-            this.TXT_servopitch = new ArdupilotMega.MyLabel();
-            this.TXT_servorudder = new ArdupilotMega.MyLabel();
-            this.TXT_servothrottle = new ArdupilotMega.MyLabel();
+            this.TXT_servoroll = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_servopitch = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_servorudder = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_servothrottle = new ArdupilotMega.Controls.MyLabel();
             this.panel1 = new System.Windows.Forms.Panel();
-            this.label4 = new ArdupilotMega.MyLabel();
-            this.label3 = new ArdupilotMega.MyLabel();
-            this.label2 = new ArdupilotMega.MyLabel();
-            this.label1 = new ArdupilotMega.MyLabel();
+            this.label4 = new ArdupilotMega.Controls.MyLabel();
+            this.label3 = new ArdupilotMega.Controls.MyLabel();
+            this.label2 = new ArdupilotMega.Controls.MyLabel();
+            this.label1 = new ArdupilotMega.Controls.MyLabel();
             this.panel2 = new System.Windows.Forms.Panel();
-            this.label30 = new ArdupilotMega.MyLabel();
-            this.TXT_yaw = new ArdupilotMega.MyLabel();
-            this.label11 = new ArdupilotMega.MyLabel();
-            this.label7 = new ArdupilotMega.MyLabel();
-            this.label6 = new ArdupilotMega.MyLabel();
-            this.label5 = new ArdupilotMega.MyLabel();
-            this.label8 = new ArdupilotMega.MyLabel();
-            this.label9 = new ArdupilotMega.MyLabel();
-            this.label10 = new ArdupilotMega.MyLabel();
+            this.label30 = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_yaw = new ArdupilotMega.Controls.MyLabel();
+            this.label11 = new ArdupilotMega.Controls.MyLabel();
+            this.label7 = new ArdupilotMega.Controls.MyLabel();
+            this.label6 = new ArdupilotMega.Controls.MyLabel();
+            this.label5 = new ArdupilotMega.Controls.MyLabel();
+            this.label8 = new ArdupilotMega.Controls.MyLabel();
+            this.label9 = new ArdupilotMega.Controls.MyLabel();
+            this.label10 = new ArdupilotMega.Controls.MyLabel();
             this.panel3 = new System.Windows.Forms.Panel();
-            this.label16 = new ArdupilotMega.MyLabel();
-            this.label15 = new ArdupilotMega.MyLabel();
-            this.label14 = new ArdupilotMega.MyLabel();
-            this.label13 = new ArdupilotMega.MyLabel();
-            this.label12 = new ArdupilotMega.MyLabel();
+            this.label16 = new ArdupilotMega.Controls.MyLabel();
+            this.label15 = new ArdupilotMega.Controls.MyLabel();
+            this.label14 = new ArdupilotMega.Controls.MyLabel();
+            this.label13 = new ArdupilotMega.Controls.MyLabel();
+            this.label12 = new ArdupilotMega.Controls.MyLabel();
             this.panel4 = new System.Windows.Forms.Panel();
-            this.label20 = new ArdupilotMega.MyLabel();
-            this.label19 = new ArdupilotMega.MyLabel();
-            this.TXT_control_mode = new ArdupilotMega.MyLabel();
-            this.TXT_WP = new ArdupilotMega.MyLabel();
-            this.label18 = new ArdupilotMega.MyLabel();
-            this.label17 = new ArdupilotMega.MyLabel();
+            this.label20 = new ArdupilotMega.Controls.MyLabel();
+            this.label19 = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_control_mode = new ArdupilotMega.Controls.MyLabel();
+            this.TXT_WP = new ArdupilotMega.Controls.MyLabel();
+            this.label18 = new ArdupilotMega.Controls.MyLabel();
+            this.label17 = new ArdupilotMega.Controls.MyLabel();
             this.panel5 = new System.Windows.Forms.Panel();
             this.zg1 = new ZedGraph.ZedGraphControl();
             this.timer_servo_graph = new System.Windows.Forms.Timer(this.components);
             this.panel6 = new System.Windows.Forms.Panel();
-            this.label28 = new ArdupilotMega.MyLabel();
-            this.label29 = new ArdupilotMega.MyLabel();
-            this.label27 = new ArdupilotMega.MyLabel();
-            this.label25 = new ArdupilotMega.MyLabel();
+            this.label28 = new ArdupilotMega.Controls.MyLabel();
+            this.label29 = new ArdupilotMega.Controls.MyLabel();
+            this.label27 = new ArdupilotMega.Controls.MyLabel();
+            this.label25 = new ArdupilotMega.Controls.MyLabel();
             this.TXT_throttlegain = new System.Windows.Forms.TextBox();
-            this.label24 = new ArdupilotMega.MyLabel();
-            this.label23 = new ArdupilotMega.MyLabel();
-            this.label22 = new ArdupilotMega.MyLabel();
-            this.label21 = new ArdupilotMega.MyLabel();
+            this.label24 = new ArdupilotMega.Controls.MyLabel();
+            this.label23 = new ArdupilotMega.Controls.MyLabel();
+            this.label22 = new ArdupilotMega.Controls.MyLabel();
+            this.label21 = new ArdupilotMega.Controls.MyLabel();
             this.TXT_ruddergain = new System.Windows.Forms.TextBox();
             this.TXT_pitchgain = new System.Windows.Forms.TextBox();
             this.TXT_rollgain = new System.Windows.Forms.TextBox();
-            this.label26 = new ArdupilotMega.MyLabel();
+            this.label26 = new ArdupilotMega.Controls.MyLabel();
             this.CHKdisplayall = new System.Windows.Forms.CheckBox();
             this.CHKgraphroll = new System.Windows.Forms.CheckBox();
             this.CHKgraphpitch = new System.Windows.Forms.CheckBox();
             this.CHKgraphrudder = new System.Windows.Forms.CheckBox();
             this.CHKgraphthrottle = new System.Windows.Forms.CheckBox();
-            this.but_advsettings = new ArdupilotMega.MyButton();
+            this.but_advsettings = new ArdupilotMega.Controls.MyButton();
             this.chkSensor = new System.Windows.Forms.CheckBox();
             this.CHK_quad = new System.Windows.Forms.CheckBox();
-            this.BUT_startfgquad = new ArdupilotMega.MyButton();
-            this.BUT_startfgplane = new ArdupilotMega.MyButton();
-            this.BUT_startxplane = new ArdupilotMega.MyButton();
+            this.BUT_startfgquad = new ArdupilotMega.Controls.MyButton();
+            this.BUT_startfgplane = new ArdupilotMega.Controls.MyButton();
+            this.BUT_startxplane = new ArdupilotMega.Controls.MyButton();
             this.CHK_heli = new System.Windows.Forms.CheckBox();
             this.RAD_aerosimrc = new System.Windows.Forms.RadioButton();
             this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
@@ -763,81 +763,81 @@
         private System.Windows.Forms.CheckBox CHKREV_pitch;
         private System.Windows.Forms.CheckBox CHKREV_rudder;
         private System.Windows.Forms.ComboBox GPSrate;
-        private MyButton ConnectComPort;
+        private ArdupilotMega.Controls.MyButton ConnectComPort;
         private System.Windows.Forms.RichTextBox OutputLog;
-        private ArdupilotMega.MyLabel TXT_roll;
-        private ArdupilotMega.MyLabel TXT_pitch;
-        private ArdupilotMega.MyLabel TXT_heading;
-        private ArdupilotMega.MyLabel TXT_wpdist;
-        private ArdupilotMega.MyLabel TXT_bererror;
-        private ArdupilotMega.MyLabel TXT_alterror;
-        private ArdupilotMega.MyLabel TXT_lat;
-        private ArdupilotMega.MyLabel TXT_long;
-        private ArdupilotMega.MyLabel TXT_alt;
-        private MyButton SaveSettings;
+        private ArdupilotMega.Controls.MyLabel TXT_roll;
+        private ArdupilotMega.Controls.MyLabel TXT_pitch;
+        private ArdupilotMega.Controls.MyLabel TXT_heading;
+        private ArdupilotMega.Controls.MyLabel TXT_wpdist;
+        private ArdupilotMega.Controls.MyLabel TXT_bererror;
+        private ArdupilotMega.Controls.MyLabel TXT_alterror;
+        private ArdupilotMega.Controls.MyLabel TXT_lat;
+        private ArdupilotMega.Controls.MyLabel TXT_long;
+        private ArdupilotMega.Controls.MyLabel TXT_alt;
+        private ArdupilotMega.Controls.MyButton SaveSettings;
         private System.Windows.Forms.RadioButton RAD_softXplanes;
         private System.Windows.Forms.RadioButton RAD_softFlightGear;
-        private ArdupilotMega.MyLabel TXT_servoroll;
-        private ArdupilotMega.MyLabel TXT_servopitch;
-        private ArdupilotMega.MyLabel TXT_servorudder;
-        private ArdupilotMega.MyLabel TXT_servothrottle;
+        private ArdupilotMega.Controls.MyLabel TXT_servoroll;
+        private ArdupilotMega.Controls.MyLabel TXT_servopitch;
+        private ArdupilotMega.Controls.MyLabel TXT_servorudder;
+        private ArdupilotMega.Controls.MyLabel TXT_servothrottle;
         private System.Windows.Forms.Panel panel1;
-        private ArdupilotMega.MyLabel label3;
-        private ArdupilotMega.MyLabel label2;
-        private ArdupilotMega.MyLabel label1;
+        private ArdupilotMega.Controls.MyLabel label3;
+        private ArdupilotMega.Controls.MyLabel label2;
+        private ArdupilotMega.Controls.MyLabel label1;
         private System.Windows.Forms.Panel panel2;
-        private ArdupilotMega.MyLabel label4;
-        private ArdupilotMega.MyLabel label10;
-        private ArdupilotMega.MyLabel label9;
-        private ArdupilotMega.MyLabel label8;
-        private ArdupilotMega.MyLabel label7;
-        private ArdupilotMega.MyLabel label6;
-        private ArdupilotMega.MyLabel label5;
-        private ArdupilotMega.MyLabel label11;
+        private ArdupilotMega.Controls.MyLabel label4;
+        private ArdupilotMega.Controls.MyLabel label10;
+        private ArdupilotMega.Controls.MyLabel label9;
+        private ArdupilotMega.Controls.MyLabel label8;
+        private ArdupilotMega.Controls.MyLabel label7;
+        private ArdupilotMega.Controls.MyLabel label6;
+        private ArdupilotMega.Controls.MyLabel label5;
+        private ArdupilotMega.Controls.MyLabel label11;
         private System.Windows.Forms.Panel panel3;
-        private ArdupilotMega.MyLabel label16;
-        private ArdupilotMega.MyLabel label15;
-        private ArdupilotMega.MyLabel label14;
-        private ArdupilotMega.MyLabel label13;
-        private ArdupilotMega.MyLabel label12;
+        private ArdupilotMega.Controls.MyLabel label16;
+        private ArdupilotMega.Controls.MyLabel label15;
+        private ArdupilotMega.Controls.MyLabel label14;
+        private ArdupilotMega.Controls.MyLabel label13;
+        private ArdupilotMega.Controls.MyLabel label12;
         private System.Windows.Forms.Panel panel4;
-        private ArdupilotMega.MyLabel label17;
-        private ArdupilotMega.MyLabel TXT_WP;
-        private ArdupilotMega.MyLabel label18;
+        private ArdupilotMega.Controls.MyLabel label17;
+        private ArdupilotMega.Controls.MyLabel TXT_WP;
+        private ArdupilotMega.Controls.MyLabel label18;
         private System.Windows.Forms.Panel panel5;
-        private ArdupilotMega.MyLabel label20;
-        private ArdupilotMega.MyLabel label19;
-        private ArdupilotMega.MyLabel TXT_control_mode;
+        private ArdupilotMega.Controls.MyLabel label20;
+        private ArdupilotMega.Controls.MyLabel label19;
+        private ArdupilotMega.Controls.MyLabel TXT_control_mode;
         private ZedGraph.ZedGraphControl zg1;
         private System.Windows.Forms.Timer timer_servo_graph;
         private System.Windows.Forms.Panel panel6;
         private System.Windows.Forms.TextBox TXT_ruddergain;
         private System.Windows.Forms.TextBox TXT_pitchgain;
         private System.Windows.Forms.TextBox TXT_rollgain;
-        private ArdupilotMega.MyLabel label24;
-        private ArdupilotMega.MyLabel label23;
-        private ArdupilotMega.MyLabel label22;
-        private ArdupilotMega.MyLabel label21;
-        private ArdupilotMega.MyLabel label25;
+        private ArdupilotMega.Controls.MyLabel label24;
+        private ArdupilotMega.Controls.MyLabel label23;
+        private ArdupilotMega.Controls.MyLabel label22;
+        private ArdupilotMega.Controls.MyLabel label21;
+        private ArdupilotMega.Controls.MyLabel label25;
         private System.Windows.Forms.TextBox TXT_throttlegain;
-        private ArdupilotMega.MyLabel label28;
-        private ArdupilotMega.MyLabel label29;
-        private ArdupilotMega.MyLabel label27;
-        private ArdupilotMega.MyLabel label26;
+        private ArdupilotMega.Controls.MyLabel label28;
+        private ArdupilotMega.Controls.MyLabel label29;
+        private ArdupilotMega.Controls.MyLabel label27;
+        private ArdupilotMega.Controls.MyLabel label26;
         private System.Windows.Forms.CheckBox CHKdisplayall;
         private System.Windows.Forms.CheckBox CHKgraphroll;
         private System.Windows.Forms.CheckBox CHKgraphpitch;
         private System.Windows.Forms.CheckBox CHKgraphrudder;
         private System.Windows.Forms.CheckBox CHKgraphthrottle;
-        private ArdupilotMega.MyLabel label30;
-        private ArdupilotMega.MyLabel TXT_yaw;
-        private MyButton but_advsettings;
+        private ArdupilotMega.Controls.MyLabel label30;
+        private ArdupilotMega.Controls.MyLabel TXT_yaw;
+        private ArdupilotMega.Controls.MyButton but_advsettings;
         private System.Windows.Forms.CheckBox chkSensor;
         private System.Windows.Forms.BindingSource currentStateBindingSource;
         private System.Windows.Forms.CheckBox CHK_quad;
-        private MyButton BUT_startfgquad;
-        private MyButton BUT_startfgplane;
-        private MyButton BUT_startxplane;
+        private ArdupilotMega.Controls.MyButton BUT_startfgquad;
+        private ArdupilotMega.Controls.MyButton BUT_startfgplane;
+        private ArdupilotMega.Controls.MyButton BUT_startxplane;
         private System.Windows.Forms.CheckBox CHK_heli;
         private System.Windows.Forms.RadioButton RAD_aerosimrc;
         private System.Windows.Forms.ToolTip toolTip1;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
index fca568395..307090fb1 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
@@ -13,7 +13,7 @@ using log4net;
 using ZedGraph; // Graphs
 using ArdupilotMega;
 using System.Reflection;
-
+using ArdupilotMega.Controls;
 using System.Drawing.Drawing2D;
 
 // Written by Michael Oborne
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx
index b78bdb87c..0b480ae37 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx
@@ -261,7 +261,7 @@
     <value>ConnectComPort</value>
   </data>
   <data name="&gt;&gt;ConnectComPort.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;ConnectComPort.Parent" xml:space="preserve">
     <value>panel5</value>
@@ -309,7 +309,7 @@
     <value>TXT_roll</value>
   </data>
   <data name="&gt;&gt;TXT_roll.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_roll.Parent" xml:space="preserve">
     <value>panel2</value>
@@ -330,7 +330,7 @@
     <value>TXT_pitch</value>
   </data>
   <data name="&gt;&gt;TXT_pitch.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_pitch.Parent" xml:space="preserve">
     <value>panel2</value>
@@ -351,7 +351,7 @@
     <value>TXT_heading</value>
   </data>
   <data name="&gt;&gt;TXT_heading.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_heading.Parent" xml:space="preserve">
     <value>panel2</value>
@@ -372,7 +372,7 @@
     <value>TXT_wpdist</value>
   </data>
   <data name="&gt;&gt;TXT_wpdist.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_wpdist.Parent" xml:space="preserve">
     <value>panel4</value>
@@ -396,7 +396,7 @@
     <value>TXT_bererror</value>
   </data>
   <data name="&gt;&gt;TXT_bererror.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_bererror.Parent" xml:space="preserve">
     <value>panel4</value>
@@ -417,7 +417,7 @@
     <value>TXT_alterror</value>
   </data>
   <data name="&gt;&gt;TXT_alterror.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_alterror.Parent" xml:space="preserve">
     <value>panel4</value>
@@ -438,7 +438,7 @@
     <value>TXT_lat</value>
   </data>
   <data name="&gt;&gt;TXT_lat.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_lat.Parent" xml:space="preserve">
     <value>panel1</value>
@@ -459,7 +459,7 @@
     <value>TXT_long</value>
   </data>
   <data name="&gt;&gt;TXT_long.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_long.Parent" xml:space="preserve">
     <value>panel1</value>
@@ -480,7 +480,7 @@
     <value>TXT_alt</value>
   </data>
   <data name="&gt;&gt;TXT_alt.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_alt.Parent" xml:space="preserve">
     <value>panel1</value>
@@ -504,7 +504,7 @@
     <value>SaveSettings</value>
   </data>
   <data name="&gt;&gt;SaveSettings.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;SaveSettings.Parent" xml:space="preserve">
     <value>$this</value>
@@ -588,7 +588,7 @@
     <value>TXT_servoroll</value>
   </data>
   <data name="&gt;&gt;TXT_servoroll.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_servoroll.Parent" xml:space="preserve">
     <value>panel3</value>
@@ -609,7 +609,7 @@
     <value>TXT_servopitch</value>
   </data>
   <data name="&gt;&gt;TXT_servopitch.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_servopitch.Parent" xml:space="preserve">
     <value>panel3</value>
@@ -630,7 +630,7 @@
     <value>TXT_servorudder</value>
   </data>
   <data name="&gt;&gt;TXT_servorudder.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_servorudder.Parent" xml:space="preserve">
     <value>panel3</value>
@@ -651,7 +651,7 @@
     <value>TXT_servothrottle</value>
   </data>
   <data name="&gt;&gt;TXT_servothrottle.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_servothrottle.Parent" xml:space="preserve">
     <value>panel3</value>
@@ -675,7 +675,7 @@
     <value>label4</value>
   </data>
   <data name="&gt;&gt;label4.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label4.Parent" xml:space="preserve">
     <value>panel1</value>
@@ -699,7 +699,7 @@
     <value>label3</value>
   </data>
   <data name="&gt;&gt;label3.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label3.Parent" xml:space="preserve">
     <value>panel1</value>
@@ -723,7 +723,7 @@
     <value>label2</value>
   </data>
   <data name="&gt;&gt;label2.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label2.Parent" xml:space="preserve">
     <value>panel1</value>
@@ -747,7 +747,7 @@
     <value>label1</value>
   </data>
   <data name="&gt;&gt;label1.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label1.Parent" xml:space="preserve">
     <value>panel1</value>
@@ -792,7 +792,7 @@
     <value>label30</value>
   </data>
   <data name="&gt;&gt;label30.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label30.Parent" xml:space="preserve">
     <value>panel2</value>
@@ -813,7 +813,7 @@
     <value>TXT_yaw</value>
   </data>
   <data name="&gt;&gt;TXT_yaw.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_yaw.Parent" xml:space="preserve">
     <value>panel2</value>
@@ -837,7 +837,7 @@
     <value>label11</value>
   </data>
   <data name="&gt;&gt;label11.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label11.Parent" xml:space="preserve">
     <value>panel2</value>
@@ -861,7 +861,7 @@
     <value>label7</value>
   </data>
   <data name="&gt;&gt;label7.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label7.Parent" xml:space="preserve">
     <value>panel2</value>
@@ -885,7 +885,7 @@
     <value>label6</value>
   </data>
   <data name="&gt;&gt;label6.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label6.Parent" xml:space="preserve">
     <value>panel2</value>
@@ -909,7 +909,7 @@
     <value>label5</value>
   </data>
   <data name="&gt;&gt;label5.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label5.Parent" xml:space="preserve">
     <value>panel2</value>
@@ -954,7 +954,7 @@
     <value>label8</value>
   </data>
   <data name="&gt;&gt;label8.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label8.Parent" xml:space="preserve">
     <value>panel4</value>
@@ -978,7 +978,7 @@
     <value>label9</value>
   </data>
   <data name="&gt;&gt;label9.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label9.Parent" xml:space="preserve">
     <value>panel4</value>
@@ -1002,7 +1002,7 @@
     <value>label10</value>
   </data>
   <data name="&gt;&gt;label10.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label10.Parent" xml:space="preserve">
     <value>panel4</value>
@@ -1026,7 +1026,7 @@
     <value>label16</value>
   </data>
   <data name="&gt;&gt;label16.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label16.Parent" xml:space="preserve">
     <value>panel3</value>
@@ -1050,7 +1050,7 @@
     <value>label15</value>
   </data>
   <data name="&gt;&gt;label15.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label15.Parent" xml:space="preserve">
     <value>panel3</value>
@@ -1074,7 +1074,7 @@
     <value>label14</value>
   </data>
   <data name="&gt;&gt;label14.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label14.Parent" xml:space="preserve">
     <value>panel3</value>
@@ -1098,7 +1098,7 @@
     <value>label13</value>
   </data>
   <data name="&gt;&gt;label13.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label13.Parent" xml:space="preserve">
     <value>panel3</value>
@@ -1122,7 +1122,7 @@
     <value>label12</value>
   </data>
   <data name="&gt;&gt;label12.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label12.Parent" xml:space="preserve">
     <value>panel3</value>
@@ -1167,7 +1167,7 @@
     <value>label20</value>
   </data>
   <data name="&gt;&gt;label20.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label20.Parent" xml:space="preserve">
     <value>panel4</value>
@@ -1191,7 +1191,7 @@
     <value>label19</value>
   </data>
   <data name="&gt;&gt;label19.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label19.Parent" xml:space="preserve">
     <value>panel4</value>
@@ -1212,7 +1212,7 @@
     <value>TXT_control_mode</value>
   </data>
   <data name="&gt;&gt;TXT_control_mode.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_control_mode.Parent" xml:space="preserve">
     <value>panel4</value>
@@ -1233,7 +1233,7 @@
     <value>TXT_WP</value>
   </data>
   <data name="&gt;&gt;TXT_WP.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;TXT_WP.Parent" xml:space="preserve">
     <value>panel4</value>
@@ -1257,7 +1257,7 @@
     <value>label18</value>
   </data>
   <data name="&gt;&gt;label18.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label18.Parent" xml:space="preserve">
     <value>panel4</value>
@@ -1302,7 +1302,7 @@
     <value>label17</value>
   </data>
   <data name="&gt;&gt;label17.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label17.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1375,7 +1375,7 @@
     <value>label28</value>
   </data>
   <data name="&gt;&gt;label28.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label28.Parent" xml:space="preserve">
     <value>panel6</value>
@@ -1399,7 +1399,7 @@
     <value>label29</value>
   </data>
   <data name="&gt;&gt;label29.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label29.Parent" xml:space="preserve">
     <value>panel6</value>
@@ -1423,7 +1423,7 @@
     <value>label27</value>
   </data>
   <data name="&gt;&gt;label27.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label27.Parent" xml:space="preserve">
     <value>panel6</value>
@@ -1447,7 +1447,7 @@
     <value>label25</value>
   </data>
   <data name="&gt;&gt;label25.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label25.Parent" xml:space="preserve">
     <value>panel6</value>
@@ -1495,7 +1495,7 @@
     <value>label24</value>
   </data>
   <data name="&gt;&gt;label24.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label24.Parent" xml:space="preserve">
     <value>panel6</value>
@@ -1519,7 +1519,7 @@
     <value>label23</value>
   </data>
   <data name="&gt;&gt;label23.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label23.Parent" xml:space="preserve">
     <value>panel6</value>
@@ -1543,7 +1543,7 @@
     <value>label22</value>
   </data>
   <data name="&gt;&gt;label22.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label22.Parent" xml:space="preserve">
     <value>panel6</value>
@@ -1567,7 +1567,7 @@
     <value>label21</value>
   </data>
   <data name="&gt;&gt;label21.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label21.Parent" xml:space="preserve">
     <value>panel6</value>
@@ -1684,7 +1684,7 @@
     <value>label26</value>
   </data>
   <data name="&gt;&gt;label26.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;label26.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1855,7 +1855,7 @@
     <value>but_advsettings</value>
   </data>
   <data name="&gt;&gt;but_advsettings.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;but_advsettings.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1939,7 +1939,7 @@
     <value>BUT_startfgquad</value>
   </data>
   <data name="&gt;&gt;BUT_startfgquad.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_startfgquad.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1966,7 +1966,7 @@
     <value>BUT_startfgplane</value>
   </data>
   <data name="&gt;&gt;BUT_startfgplane.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_startfgplane.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1993,7 +1993,7 @@
     <value>BUT_startxplane</value>
   </data>
   <data name="&gt;&gt;BUT_startxplane.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_startxplane.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.Designer.cs
index 29b1c3207..eacae4685 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.Designer.cs
@@ -30,11 +30,11 @@
         {
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Terminal));
             this.TXT_terminal = new System.Windows.Forms.RichTextBox();
-            this.BUTsetupshow = new ArdupilotMega.MyButton();
-            this.BUTradiosetup = new ArdupilotMega.MyButton();
-            this.BUTtests = new ArdupilotMega.MyButton();
-            this.Logs = new ArdupilotMega.MyButton();
-            this.BUT_logbrowse = new ArdupilotMega.MyButton();
+            this.BUTsetupshow = new ArdupilotMega.Controls.MyButton();
+            this.BUTradiosetup = new ArdupilotMega.Controls.MyButton();
+            this.BUTtests = new ArdupilotMega.Controls.MyButton();
+            this.Logs = new ArdupilotMega.Controls.MyButton();
+            this.BUT_logbrowse = new ArdupilotMega.Controls.MyButton();
             this.SuspendLayout();
             // 
             // TXT_terminal
@@ -101,10 +101,10 @@
         #endregion
 
         private System.Windows.Forms.RichTextBox TXT_terminal;
-        private MyButton BUTsetupshow;
-        private MyButton BUTradiosetup;
-        private MyButton BUTtests;
-        private MyButton Logs;
-        private MyButton BUT_logbrowse;
+        private ArdupilotMega.Controls.MyButton BUTsetupshow;
+        private ArdupilotMega.Controls.MyButton BUTradiosetup;
+        private ArdupilotMega.Controls.MyButton BUTtests;
+        private ArdupilotMega.Controls.MyButton Logs;
+        private ArdupilotMega.Controls.MyButton BUT_logbrowse;
     }
 }
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs
index 2c4897ace..9dbeb0d32 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs
@@ -8,6 +8,8 @@ using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega;
 using System.IO.Ports;
+using ArdupilotMega.Comms;
+
 
 namespace ArdupilotMega.GCSViews
 {
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.resx
index 4da6d80a1..af41b2749 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.resx
@@ -166,7 +166,7 @@
     <value>BUTsetupshow</value>
   </data>
   <data name="&gt;&gt;BUTsetupshow.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUTsetupshow.Parent" xml:space="preserve">
     <value>$this</value>
@@ -190,7 +190,7 @@
     <value>BUTradiosetup</value>
   </data>
   <data name="&gt;&gt;BUTradiosetup.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUTradiosetup.Parent" xml:space="preserve">
     <value>$this</value>
@@ -214,7 +214,7 @@
     <value>BUTtests</value>
   </data>
   <data name="&gt;&gt;BUTtests.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUTtests.Parent" xml:space="preserve">
     <value>$this</value>
@@ -238,7 +238,7 @@
     <value>Logs</value>
   </data>
   <data name="&gt;&gt;Logs.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;Logs.Parent" xml:space="preserve">
     <value>$this</value>
@@ -262,7 +262,7 @@
     <value>BUT_logbrowse</value>
   </data>
   <data name="&gt;&gt;BUT_logbrowse.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
   </data>
   <data name="&gt;&gt;BUT_logbrowse.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs b/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs
index 567ecfd7c..6b6ab46c6 100644
--- a/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs
@@ -70,23 +70,23 @@
             this.label13 = new System.Windows.Forms.Label();
             this.expo_ch8 = new System.Windows.Forms.TextBox();
             this.CMB_CH8 = new System.Windows.Forms.ComboBox();
-            this.BUT_detch8 = new ArdupilotMega.MyButton();
+            this.BUT_detch8 = new ArdupilotMega.Controls.MyButton();
             this.horizontalProgressBar4 = new ArdupilotMega.HorizontalProgressBar();
-            this.BUT_detch4 = new ArdupilotMega.MyButton();
-            this.BUT_detch3 = new ArdupilotMega.MyButton();
-            this.BUT_detch2 = new ArdupilotMega.MyButton();
-            this.BUT_detch1 = new ArdupilotMega.MyButton();
-            this.BUT_enable = new ArdupilotMega.MyButton();
-            this.BUT_save = new ArdupilotMega.MyButton();
+            this.BUT_detch4 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_detch3 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_detch2 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_detch1 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_enable = new ArdupilotMega.Controls.MyButton();
+            this.BUT_save = new ArdupilotMega.Controls.MyButton();
             this.progressBar4 = new ArdupilotMega.HorizontalProgressBar();
             this.progressBar3 = new ArdupilotMega.HorizontalProgressBar();
             this.progressBar2 = new ArdupilotMega.HorizontalProgressBar();
             this.progressBar1 = new ArdupilotMega.HorizontalProgressBar();
-            this.BUT_detch5 = new ArdupilotMega.MyButton();
+            this.BUT_detch5 = new ArdupilotMega.Controls.MyButton();
             this.horizontalProgressBar1 = new ArdupilotMega.HorizontalProgressBar();
-            this.BUT_detch6 = new ArdupilotMega.MyButton();
+            this.BUT_detch6 = new ArdupilotMega.Controls.MyButton();
             this.horizontalProgressBar2 = new ArdupilotMega.HorizontalProgressBar();
-            this.BUT_detch7 = new ArdupilotMega.MyButton();
+            this.BUT_detch7 = new ArdupilotMega.Controls.MyButton();
             this.horizontalProgressBar3 = new ArdupilotMega.HorizontalProgressBar();
             this.SuspendLayout();
             // 
@@ -625,38 +625,38 @@
         private System.Windows.Forms.CheckBox revCH2;
         private System.Windows.Forms.CheckBox revCH3;
         private System.Windows.Forms.CheckBox revCH4;
-        private MyButton BUT_save;
-        private MyButton BUT_enable;
+        private ArdupilotMega.Controls.MyButton BUT_save;
+        private ArdupilotMega.Controls.MyButton BUT_enable;
         private System.Windows.Forms.Label label5;
         private System.Windows.Forms.Label label6;
         private System.Windows.Forms.Label label7;
         private System.Windows.Forms.Label label8;
         private System.Windows.Forms.Label label9;
         private System.Windows.Forms.Timer timer1;
-        private MyButton BUT_detch1;
-        private MyButton BUT_detch2;
-        private MyButton BUT_detch3;
-        private MyButton BUT_detch4;
+        private ArdupilotMega.Controls.MyButton BUT_detch1;
+        private ArdupilotMega.Controls.MyButton BUT_detch2;
+        private ArdupilotMega.Controls.MyButton BUT_detch3;
+        private ArdupilotMega.Controls.MyButton BUT_detch4;
         private System.Windows.Forms.CheckBox CHK_elevons;
-        private MyButton BUT_detch5;
+        private ArdupilotMega.Controls.MyButton BUT_detch5;
         private System.Windows.Forms.CheckBox revCH5;
         private System.Windows.Forms.Label label10;
         private System.Windows.Forms.TextBox expo_ch5;
         private HorizontalProgressBar horizontalProgressBar1;
         private System.Windows.Forms.ComboBox CMB_CH5;
-        private MyButton BUT_detch6;
+        private ArdupilotMega.Controls.MyButton BUT_detch6;
         private System.Windows.Forms.CheckBox revCH6;
         private System.Windows.Forms.Label label11;
         private System.Windows.Forms.TextBox expo_ch6;
         private HorizontalProgressBar horizontalProgressBar2;
         private System.Windows.Forms.ComboBox CMB_CH6;
-        private MyButton BUT_detch7;
+        private ArdupilotMega.Controls.MyButton BUT_detch7;
         private System.Windows.Forms.CheckBox revCH7;
         private System.Windows.Forms.Label label12;
         private System.Windows.Forms.TextBox expo_ch7;
         private HorizontalProgressBar horizontalProgressBar3;
         private System.Windows.Forms.ComboBox CMB_CH7;
-        private MyButton BUT_detch8;
+        private ArdupilotMega.Controls.MyButton BUT_detch8;
         private System.Windows.Forms.CheckBox revCH8;
         private System.Windows.Forms.Label label13;
         private System.Windows.Forms.TextBox expo_ch8;
diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
index 92e7c613d..c750515d5 100644
--- a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
+++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
@@ -7,7 +7,8 @@ using System.Linq;
 using System.Text;
 using System.Windows.Forms;
 using Microsoft.DirectX.DirectInput;
-
+using ArdupilotMega.Controls;
+using ArdupilotMega.Utilities;
 
 
 namespace ArdupilotMega
@@ -408,7 +409,7 @@ namespace ArdupilotMega
         {
             MyLabel lbl = new MyLabel();
             ComboBox cmbbutton = new ComboBox();
-            MyButton mybut = new MyButton();
+            ArdupilotMega.Controls.MyButton mybut = new ArdupilotMega.Controls.MyButton();
             HorizontalProgressBar hbar = new HorizontalProgressBar();
             ComboBox cmbaction = new ComboBox();
 
@@ -440,7 +441,11 @@ namespace ArdupilotMega
 
             cmbaction.Location = new Point(hbar.Right + 5, y);
             cmbaction.Size = new Size(100, 21);
-            cmbaction.DataSource = (Enum.GetValues(Common.getModes()));
+
+            cmbaction.DataSource = Common.getModesList();
+            cmbaction.ValueMember = "Key";
+            cmbaction.DisplayMember = "Value";
+
             cmbaction.DropDownStyle = ComboBoxStyle.DropDownList;
             cmbaction.Name = "cmbaction" + name;
             if (MainV2.config["butaction" + name] != null)
diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.resx b/Tools/ArdupilotMegaPlanner/JoystickSetup.resx
index 9b3814704..1912c313d 100644
--- a/Tools/ArdupilotMegaPlanner/JoystickSetup.resx
+++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.resx
@@ -1258,7 +1258,7 @@
     <value>BUT_detch8</value>
   </data>
   <data name="&gt;&gt;BUT_detch8.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_detch8.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1309,7 +1309,7 @@
     <value>BUT_detch4</value>
   </data>
   <data name="&gt;&gt;BUT_detch4.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_detch4.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1336,7 +1336,7 @@
     <value>BUT_detch3</value>
   </data>
   <data name="&gt;&gt;BUT_detch3.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_detch3.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1363,7 +1363,7 @@
     <value>BUT_detch2</value>
   </data>
   <data name="&gt;&gt;BUT_detch2.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_detch2.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1390,7 +1390,7 @@
     <value>BUT_detch1</value>
   </data>
   <data name="&gt;&gt;BUT_detch1.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_detch1.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1417,7 +1417,7 @@
     <value>BUT_enable</value>
   </data>
   <data name="&gt;&gt;BUT_enable.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_enable.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1444,7 +1444,7 @@
     <value>BUT_save</value>
   </data>
   <data name="&gt;&gt;BUT_save.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_save.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1567,7 +1567,7 @@
     <value>BUT_detch5</value>
   </data>
   <data name="&gt;&gt;BUT_detch5.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_detch5.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1618,7 +1618,7 @@
     <value>BUT_detch6</value>
   </data>
   <data name="&gt;&gt;BUT_detch6.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_detch6.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1669,7 +1669,7 @@
     <value>BUT_detch7</value>
   </data>
   <data name="&gt;&gt;BUT_detch7.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_detch7.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/Log.Designer.cs b/Tools/ArdupilotMegaPlanner/Log.Designer.cs
index 97aeebba0..5268c07d9 100644
--- a/Tools/ArdupilotMegaPlanner/Log.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/Log.Designer.cs
@@ -30,13 +30,13 @@
         {
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Log));
             this.TXT_seriallog = new System.Windows.Forms.TextBox();
-            this.BUT_DLall = new ArdupilotMega.MyButton();
-            this.BUT_DLthese = new ArdupilotMega.MyButton();
-            this.BUT_clearlogs = new ArdupilotMega.MyButton();
+            this.BUT_DLall = new ArdupilotMega.Controls.MyButton();
+            this.BUT_DLthese = new ArdupilotMega.Controls.MyButton();
+            this.BUT_clearlogs = new ArdupilotMega.Controls.MyButton();
             this.CHK_logs = new System.Windows.Forms.CheckedListBox();
             this.TXT_status = new System.Windows.Forms.TextBox();
-            this.BUT_redokml = new ArdupilotMega.MyButton();
-            this.BUT_firstperson = new ArdupilotMega.MyButton();
+            this.BUT_redokml = new ArdupilotMega.Controls.MyButton();
+            this.BUT_firstperson = new ArdupilotMega.Controls.MyButton();
             this.SuspendLayout();
             // 
             // TXT_seriallog
@@ -114,13 +114,13 @@
 
         #endregion
 
-        private MyButton BUT_DLall;
-        private MyButton BUT_DLthese;
-        private MyButton BUT_clearlogs;
+        private ArdupilotMega.Controls.MyButton BUT_DLall;
+        private ArdupilotMega.Controls.MyButton BUT_DLthese;
+        private ArdupilotMega.Controls.MyButton BUT_clearlogs;
         private System.Windows.Forms.CheckedListBox CHK_logs;
         private System.Windows.Forms.TextBox TXT_status;
-        private MyButton BUT_redokml;
+        private ArdupilotMega.Controls.MyButton BUT_redokml;
         private System.Windows.Forms.TextBox TXT_seriallog;
-        private MyButton BUT_firstperson;
+        private ArdupilotMega.Controls.MyButton BUT_firstperson;
     }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Log.cs b/Tools/ArdupilotMegaPlanner/Log.cs
index 5bef471ab..520c59ac4 100644
--- a/Tools/ArdupilotMegaPlanner/Log.cs
+++ b/Tools/ArdupilotMegaPlanner/Log.cs
@@ -17,6 +17,7 @@ using ICSharpCode.SharpZipLib.Zip;
 using ICSharpCode.SharpZipLib.Checksums;
 using ICSharpCode.SharpZipLib.Core;
 using log4net;
+using ArdupilotMega.Comms;
 
 
 namespace ArdupilotMega
diff --git a/Tools/ArdupilotMegaPlanner/Log.resx b/Tools/ArdupilotMegaPlanner/Log.resx
index b1e09b2bb..cf6b03501 100644
--- a/Tools/ArdupilotMegaPlanner/Log.resx
+++ b/Tools/ArdupilotMegaPlanner/Log.resx
@@ -159,7 +159,7 @@
     <value>BUT_DLall</value>
   </data>
   <data name="&gt;&gt;BUT_DLall.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_DLall.Parent" xml:space="preserve">
     <value>$this</value>
@@ -183,7 +183,7 @@
     <value>BUT_DLthese</value>
   </data>
   <data name="&gt;&gt;BUT_DLthese.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_DLthese.Parent" xml:space="preserve">
     <value>$this</value>
@@ -207,7 +207,7 @@
     <value>BUT_clearlogs</value>
   </data>
   <data name="&gt;&gt;BUT_clearlogs.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_clearlogs.Parent" xml:space="preserve">
     <value>$this</value>
@@ -276,7 +276,7 @@
     <value>BUT_redokml</value>
   </data>
   <data name="&gt;&gt;BUT_redokml.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_redokml.Parent" xml:space="preserve">
     <value>$this</value>
@@ -300,7 +300,7 @@
     <value>BUT_firstperson</value>
   </data>
   <data name="&gt;&gt;BUT_firstperson.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_firstperson.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/LogBrowse.designer.cs b/Tools/ArdupilotMegaPlanner/LogBrowse.designer.cs
index e262c3dc0..aa1db0eff 100644
--- a/Tools/ArdupilotMegaPlanner/LogBrowse.designer.cs
+++ b/Tools/ArdupilotMegaPlanner/LogBrowse.designer.cs
@@ -32,9 +32,9 @@
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(LogBrowse));
             this.dataGridView1 = new System.Windows.Forms.DataGridView();
             this.zg1 = new ZedGraph.ZedGraphControl();
-            this.Graphit = new ArdupilotMega.MyButton();
-            this.BUT_cleargraph = new ArdupilotMega.MyButton();
-            this.BUT_loadlog = new ArdupilotMega.MyButton();
+            this.Graphit = new ArdupilotMega.Controls.MyButton();
+            this.BUT_cleargraph = new ArdupilotMega.Controls.MyButton();
+            this.BUT_loadlog = new ArdupilotMega.Controls.MyButton();
             this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
             ((System.ComponentModel.ISupportInitialize)(this.dataGridView1)).BeginInit();
             this.SuspendLayout();
@@ -107,9 +107,9 @@
 
         private System.Windows.Forms.DataGridView dataGridView1;
         private ZedGraph.ZedGraphControl zg1;
-        private MyButton Graphit;
-        private MyButton BUT_cleargraph;
-        private MyButton BUT_loadlog;
+        private ArdupilotMega.Controls.MyButton Graphit;
+        private ArdupilotMega.Controls.MyButton BUT_cleargraph;
+        private ArdupilotMega.Controls.MyButton BUT_loadlog;
         private System.Windows.Forms.ToolTip toolTip1;
     }
 }
diff --git a/Tools/ArdupilotMegaPlanner/LogBrowse.resx b/Tools/ArdupilotMegaPlanner/LogBrowse.resx
index f122be17d..93a5287ca 100644
--- a/Tools/ArdupilotMegaPlanner/LogBrowse.resx
+++ b/Tools/ArdupilotMegaPlanner/LogBrowse.resx
@@ -193,7 +193,7 @@
     <value>Graphit</value>
   </data>
   <data name="&gt;&gt;Graphit.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;Graphit.Parent" xml:space="preserve">
     <value>$this</value>
@@ -220,7 +220,7 @@
     <value>BUT_cleargraph</value>
   </data>
   <data name="&gt;&gt;BUT_cleargraph.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_cleargraph.Parent" xml:space="preserve">
     <value>$this</value>
@@ -247,7 +247,7 @@
     <value>BUT_loadlog</value>
   </data>
   <data name="&gt;&gt;BUT_loadlog.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_loadlog.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs
index b9fa51dee..485ef2a42 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLink.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs
@@ -1,7 +1,6 @@
 using System;
 using System.Collections.Generic;
 using System.Text;
-using System.IO.Ports;
 using System.Runtime.InteropServices;
 using System.Collections; // hashs
 using System.Diagnostics; // stopwatch
@@ -13,6 +12,7 @@ using System.Threading;
 using ArdupilotMega.Controls;
 using System.ComponentModel;
 using log4net;
+using ArdupilotMega.Comms;
 
 namespace ArdupilotMega
 {
@@ -1027,9 +1027,9 @@ namespace ArdupilotMega
 
         public void requestDatastream(byte id, byte hzrate)
         {
-            
-            double pps = 0;
             /*
+            double pps = 0;
+            
             switch (id)
             {
                 case (byte)MAVLink.MAV_DATA_STREAM.ALL:
@@ -1962,7 +1962,7 @@ namespace ArdupilotMega
                 // test fabs idea - http://diydrones.com/profiles/blogs/flying-with-joystick?commentId=705844%3AComment%3A818712&xg_source=msg_com_blogpost
                 if (BaseStream.IsOpen && BaseStream.BytesToWrite > 0)
                 {
-                    // slow down execution.
+                    // slow down execution. else 100% cpu
                     Thread.Sleep(1);
                     return new byte[0];
                 }
@@ -2161,8 +2161,18 @@ namespace ArdupilotMega
                 {
                     log.InfoFormat("Mavlink Bad Packet (Len Fail) len {0} pkno {1}", temp.Length, temp[5]);
 #if MAVLINK10
-                if (temp.Length == 11 && temp[0] == 'U' && temp[5] == 0)
-                    throw new Exception("Mavlink 0.9 Heartbeat, Please upgrade your AP, This planner is for Mavlink 1.0\n\n");
+                    if (temp.Length == 11 && temp[0] == 'U' && temp[5] == 0){
+                        string message ="Mavlink 0.9 Heartbeat, Please upgrade your AP, This planner is for Mavlink 1.0\n\n";
+                        System.Windows.Forms.CustomMessageBox.Show(message);
+                        throw new Exception(message);
+                    }
+#else
+                    if (temp.Length == 17 && temp[0] == 254 && temp[5] == 0)
+                    {
+                        string message = "Mavlink 1.0 Heartbeat, Please Upgrade your Mission Planner, This planner is for Mavlink 0.9\n\n";
+                        System.Windows.Forms.CustomMessageBox.Show(message);
+                        throw new Exception(message);
+                    }
 #endif
                     return new byte[0];
                 }
diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs
index 83e817b7e..be039b53e 100644
--- a/Tools/ArdupilotMegaPlanner/MainV2.cs
+++ b/Tools/ArdupilotMegaPlanner/MainV2.cs
@@ -7,7 +7,6 @@ using System.Drawing;
 using System.Linq;
 using System.Text;
 using System.Windows.Forms;
-using System.IO.Ports;
 using System.IO;
 using System.Xml;
 using System.Collections;
@@ -24,6 +23,9 @@ using IronPython.Hosting;
 using log4net;
 using ArdupilotMega.Controls;
 using System.Security.Cryptography;
+using ArdupilotMega.Comms;
+using ArdupilotMega.Arduino;
+using System.IO.Ports;
 
 namespace ArdupilotMega
 {
@@ -197,7 +199,7 @@ namespace ArdupilotMega
 //                CMB_serialport.SelectedIndex = 0;
 //            }
             // ** new
-            _connectionControl.CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
+            _connectionControl.CMB_serialport.Items.AddRange(ArdupilotMega.Comms.SerialPort.GetPortNames());
             _connectionControl.CMB_serialport.Items.Add("TCP");
             _connectionControl.CMB_serialport.Items.Add("UDP");
             if (_connectionControl.CMB_serialport.Items.Count > 0)
@@ -356,7 +358,7 @@ namespace ArdupilotMega
         {
             string oldport = _connectionControl.CMB_serialport.Text;
             _connectionControl.CMB_serialport.Items.Clear();
-            _connectionControl.CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
+            _connectionControl.CMB_serialport.Items.AddRange(ArdupilotMega.Comms.SerialPort.GetPortNames());
             _connectionControl.CMB_serialport.Items.Add("TCP");
             _connectionControl.CMB_serialport.Items.Add("UDP");
             if (_connectionControl.CMB_serialport.Items.Contains(oldport))
@@ -565,7 +567,7 @@ namespace ArdupilotMega
                 }
                 else
                 {
-                    comPort.BaseStream = new SerialPort();
+                    comPort.BaseStream = new ArdupilotMega.Comms.SerialPort();
                 }
 
                 try
@@ -700,7 +702,7 @@ namespace ArdupilotMega
             else
             {
                 _connectionControl.CMB_baudrate.Enabled = true;
-                MainV2.comPort.BaseStream = new ArdupilotMega.SerialPort();
+                MainV2.comPort.BaseStream = new ArdupilotMega.Comms.SerialPort();
             }
 
             try
diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.Designer.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.Designer.cs
index cd4e7d821..0a77c3dfc 100644
--- a/Tools/ArdupilotMegaPlanner/MavlinkLog.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.Designer.cs
@@ -29,10 +29,10 @@
         private void InitializeComponent()
         {
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MavlinkLog));
-            this.BUT_redokml = new ArdupilotMega.MyButton();
+            this.BUT_redokml = new ArdupilotMega.Controls.MyButton();
             this.progressBar1 = new System.Windows.Forms.ProgressBar();
-            this.BUT_humanreadable = new ArdupilotMega.MyButton();
-            this.BUT_graphmavlog = new ArdupilotMega.MyButton();
+            this.BUT_humanreadable = new ArdupilotMega.Controls.MyButton();
+            this.BUT_graphmavlog = new ArdupilotMega.Controls.MyButton();
             this.zg1 = new ZedGraph.ZedGraphControl();
             this.SuspendLayout();
             // 
@@ -91,10 +91,10 @@
 
         #endregion
 
-        private MyButton BUT_redokml;
+        private ArdupilotMega.Controls.MyButton BUT_redokml;
         private System.Windows.Forms.ProgressBar progressBar1;
-        private MyButton BUT_humanreadable;
-        private MyButton BUT_graphmavlog;
+        private ArdupilotMega.Controls.MyButton BUT_humanreadable;
+        private ArdupilotMega.Controls.MyButton BUT_graphmavlog;
         private ZedGraph.ZedGraphControl zg1;
     }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.resx b/Tools/ArdupilotMegaPlanner/MavlinkLog.resx
index 9406a8df5..ec4f313eb 100644
--- a/Tools/ArdupilotMegaPlanner/MavlinkLog.resx
+++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.resx
@@ -139,7 +139,7 @@
     <value>BUT_redokml</value>
   </data>
   <data name="&gt;&gt;BUT_redokml.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_redokml.Parent" xml:space="preserve">
     <value>$this</value>
@@ -193,7 +193,7 @@
     <value>BUT_humanreadable</value>
   </data>
   <data name="&gt;&gt;BUT_humanreadable.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_humanreadable.Parent" xml:space="preserve">
     <value>$this</value>
@@ -223,7 +223,7 @@
     <value>BUT_graphmavlog</value>
   </data>
   <data name="&gt;&gt;BUT_graphmavlog.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_graphmavlog.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/Msi/wix.pdb b/Tools/ArdupilotMegaPlanner/Msi/wix.pdb
index 2d3c43918b28a85dab27db8f74975b70e7568756..a80ac1fd2da69224d03866940c09c8d5d87c5271 100644
GIT binary patch
delta 485
zcmZpe!`Lu~aRUpNgwL93{)`L^3=VInye?gG&SP(qvga<n?*})_aJ>;^GmT&|msi@%
zC)2{jC^>nu+;OJeB9mj}vw)oA^4W}%n~fEw17$X!R%!<+2v*(BbU1c1kJ>sWrXq>W
zdo=WznAV6)exsEJlGIKHs@$#}%{N(IjBAn+$7U6)02Y=T);4OBE9??j9?aL#oO}n!
zxUf=QZL)*C8avQgK)^Q9QMjIw!HR(m$Pon#fe05k3*>xhAcm@E0P-7Pk{~%HAU1{y
zFfypZq(JHzLV*}$E(n15FaTml12NQ0F`%R!Ob)Ct3CL5MywE{Rsi_0V?1f4)q1i18
zH0UZwnQX%=AhQaGvdIk&Qo0Nci&+>LEU+qZVYm&H1NjmJm>9e^A9t{2#uIxkPdEX6
Cd{~PB

delta 530
zcmZpe!`Lu~aRUpNgrmz;e?|rdhLAkNjj0Pd9A-0I^*!(?_s3=#t~Y{g-)=mg<Ds~j
zPo{;5QDyREx#LU>!jog<vw)oA^4W|kn~fEw17$X!R%!<+2v*(Bq#n4LM{OMwQ<vE0
zJsNsUOs0a9-)N<QB(;-)Dz|G#^Dzo-7Pd-cVOcPpM`3b>T>{I8!UsZ=?*JJJGk_uv
z_G<N3KqoOUuz^VskpX9c919W`g^MI-!<dW=$qdp!4m(tUks%Bw#lXm*z@P-=8N=m_
zkmQOOLV-M(eT?-Cj!2T4g3&-8!cYSfm?R@Z4nq=<qXrdVLeZDQ&;b<hh08fZSqwnO
z=rM=_eR35p2bTiMF)+xy0+Lm5NzXi(G$TW9!Q=)9DP04T#ViaA7H}mn1t7B-7;XdQ
WKmh>)ObiU0k2}~h<B4jQC!7G8##873

diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
index f7879443a..9df71d799 100644
--- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
+++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
@@ -34,5 +34,5 @@ using System.Resources;
 // by using the '*' as shown below:
 // [assembly: AssemblyVersion("1.0.*")]
 [assembly: AssemblyVersion("1.1.*")]
-[assembly: AssemblyFileVersion("1.1.74")]
+[assembly: AssemblyFileVersion("1.1.75")]
 [assembly: NeutralResourcesLanguageAttribute("")]
diff --git a/Tools/ArdupilotMegaPlanner/RAW_Sensor.Designer.cs b/Tools/ArdupilotMegaPlanner/RAW_Sensor.Designer.cs
index 33fc751bc..15d24263f 100644
--- a/Tools/ArdupilotMegaPlanner/RAW_Sensor.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/RAW_Sensor.Designer.cs
@@ -53,7 +53,7 @@
             this.horizontalProgressBar2 = new ArdupilotMega.HorizontalProgressBar();
             this.horizontalProgressBar1 = new ArdupilotMega.HorizontalProgressBar();
             this.tabRawSensor = new System.Windows.Forms.TabPage();
-            this.BUT_savecsv = new ArdupilotMega.MyButton();
+            this.BUT_savecsv = new ArdupilotMega.Controls.MyButton();
             this.label3 = new System.Windows.Forms.Label();
             this.CMB_rawupdaterate = new System.Windows.Forms.ComboBox();
             this.aGauge1 = new AGaugeApp.AGauge();
@@ -1129,7 +1129,7 @@
         private VerticalProgressBar verticalProgressBar2;
         private VerticalProgressBar verticalProgressBar1;
         private System.Windows.Forms.TabControl tabControl;
-        private MyButton BUT_savecsv;
+        private ArdupilotMega.Controls.MyButton BUT_savecsv;
 
     }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/RAW_Sensor.resx b/Tools/ArdupilotMegaPlanner/RAW_Sensor.resx
index e16890666..44efc7117 100644
--- a/Tools/ArdupilotMegaPlanner/RAW_Sensor.resx
+++ b/Tools/ArdupilotMegaPlanner/RAW_Sensor.resx
@@ -558,7 +558,7 @@
     <value>BUT_savecsv</value>
   </data>
   <data name="&gt;&gt;BUT_savecsv.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
   </data>
   <data name="&gt;&gt;BUT_savecsv.Parent" xml:space="preserve">
     <value>tabRawSensor</value>
diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
index aa2773fdf..ba32270f0 100644
--- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
@@ -73,13 +73,13 @@
             this.ATI = new System.Windows.Forms.TextBox();
             this.label11 = new System.Windows.Forms.Label();
             this.label12 = new System.Windows.Forms.Label();
-            this.BUT_savesettings = new ArdupilotMega.MyButton();
-            this.BUT_getcurrent = new ArdupilotMega.MyButton();
+            this.BUT_savesettings = new ArdupilotMega.Controls.MyButton();
+            this.BUT_getcurrent = new ArdupilotMega.Controls.MyButton();
             this.lbl_status = new System.Windows.Forms.Label();
-            this.BUT_upload = new ArdupilotMega.MyButton();
-            this.BUT_syncS2 = new ArdupilotMega.MyButton();
-            this.BUT_syncS3 = new ArdupilotMega.MyButton();
-            this.BUT_syncS5 = new ArdupilotMega.MyButton();
+            this.BUT_upload = new ArdupilotMega.Controls.MyButton();
+            this.BUT_syncS2 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_syncS3 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_syncS5 = new ArdupilotMega.Controls.MyButton();
             this.label13 = new System.Windows.Forms.Label();
             this.label14 = new System.Windows.Forms.Label();
             this.label15 = new System.Windows.Forms.Label();
@@ -98,9 +98,9 @@
             this.label30 = new System.Windows.Forms.Label();
             this.label31 = new System.Windows.Forms.Label();
             this.label32 = new System.Windows.Forms.Label();
-            this.BUT_syncS8 = new ArdupilotMega.MyButton();
-            this.BUT_syncS9 = new ArdupilotMega.MyButton();
-            this.BUT_syncS10 = new ArdupilotMega.MyButton();
+            this.BUT_syncS8 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_syncS9 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_syncS10 = new ArdupilotMega.Controls.MyButton();
             this.SuspendLayout();
             // 
             // Progressbar
@@ -858,12 +858,12 @@
 
         #endregion
 
-        private MyButton BUT_upload;
+        private ArdupilotMega.Controls.MyButton BUT_upload;
         private System.Windows.Forms.ProgressBar Progressbar;
         private System.Windows.Forms.Label lbl_status;
         private System.Windows.Forms.ComboBox S1;
         private System.Windows.Forms.Label label1;
-        private MyButton BUT_getcurrent;
+        private ArdupilotMega.Controls.MyButton BUT_getcurrent;
         private System.Windows.Forms.TextBox S0;
         private System.Windows.Forms.Label label2;
         private System.Windows.Forms.Label label3;
@@ -878,7 +878,7 @@
         private System.Windows.Forms.CheckBox S6;
         private System.Windows.Forms.Label label8;
         private System.Windows.Forms.CheckBox S7;
-        private MyButton BUT_savesettings;
+        private ArdupilotMega.Controls.MyButton BUT_savesettings;
         private System.Windows.Forms.ToolTip toolTip1;
         private System.Windows.Forms.CheckBox RS7;
         private System.Windows.Forms.CheckBox RS6;
@@ -895,9 +895,9 @@
         private System.Windows.Forms.TextBox RSSI;
         private System.Windows.Forms.Label label11;
         private System.Windows.Forms.Label label12;
-        private MyButton BUT_syncS2;
-        private MyButton BUT_syncS3;
-        private MyButton BUT_syncS5;
+        private ArdupilotMega.Controls.MyButton BUT_syncS2;
+        private ArdupilotMega.Controls.MyButton BUT_syncS3;
+        private ArdupilotMega.Controls.MyButton BUT_syncS5;
         private System.Windows.Forms.ComboBox S9;
         private System.Windows.Forms.ComboBox S10;
         private System.Windows.Forms.ComboBox S11;
@@ -926,8 +926,8 @@
         private System.Windows.Forms.Label label30;
         private System.Windows.Forms.Label label31;
         private System.Windows.Forms.Label label32;
-        private MyButton BUT_syncS8;
-        private MyButton BUT_syncS9;
-        private MyButton BUT_syncS10;
+        private ArdupilotMega.Controls.MyButton BUT_syncS8;
+        private ArdupilotMega.Controls.MyButton BUT_syncS9;
+        private ArdupilotMega.Controls.MyButton BUT_syncS10;
     }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs
index d1b6f9ad9..56fdc0820 100644
--- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs
+++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs
@@ -9,6 +9,8 @@ using System.Windows.Forms;
 using System.Net;
 using System.IO;
 using ArdupilotMega.Controls.BackstageView;
+using ArdupilotMega.Arduino;
+using ArdupilotMega.Comms;
 
 namespace ArdupilotMega
 {
@@ -226,7 +228,7 @@ S13: MANCHESTER=0
 
         private void BUT_savesettings_Click(object sender, EventArgs e)
         {
-            ArdupilotMega.ICommsSerial comPort = new SerialPort();
+            ArdupilotMega.Comms.ICommsSerial comPort = new SerialPort();
 
             try
             {
@@ -402,7 +404,7 @@ S13: MANCHESTER=0
 
         private void BUT_getcurrent_Click(object sender, EventArgs e)
         {
-            ArdupilotMega.ICommsSerial comPort = new SerialPort();
+            ArdupilotMega.Comms.ICommsSerial comPort = new SerialPort();
 
             try
             {
@@ -531,7 +533,7 @@ S13: MANCHESTER=0
             BUT_savesettings.Enabled = true;
         }
 
-        string Serial_ReadLine(ArdupilotMega.ICommsSerial comPort)
+        string Serial_ReadLine(ArdupilotMega.Comms.ICommsSerial comPort)
         {
             StringBuilder sb = new StringBuilder();
             DateTime Deadline = DateTime.Now.AddMilliseconds(comPort.ReadTimeout);
@@ -550,7 +552,7 @@ S13: MANCHESTER=0
             return sb.ToString();
         }
 
-        string doCommand(ArdupilotMega.ICommsSerial comPort, string cmd, int level = 0)
+        string doCommand(ArdupilotMega.Comms.ICommsSerial comPort, string cmd, int level = 0)
         {
             if (!comPort.IsOpen)
                 return "";
@@ -602,7 +604,7 @@ S13: MANCHESTER=0
             return ans;
         }
 
-        bool doConnect(ArdupilotMega.ICommsSerial comPort)
+        bool doConnect(ArdupilotMega.Comms.ICommsSerial comPort)
         {
             // clear buffer
             comPort.DiscardInBuffer();
diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx
index 99cb96659..d13b7ec70 100644
--- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx
+++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx
@@ -1959,7 +1959,7 @@ which result in a valid packet CRC
     <value>BUT_savesettings</value>
   </data>
   <data name="&gt;&gt;BUT_savesettings.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_savesettings.Parent" xml:space="preserve">
     <value>$this</value>
@@ -1986,7 +1986,7 @@ which result in a valid packet CRC
     <value>BUT_getcurrent</value>
   </data>
   <data name="&gt;&gt;BUT_getcurrent.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_getcurrent.Parent" xml:space="preserve">
     <value>$this</value>
@@ -2037,7 +2037,7 @@ which result in a valid packet CRC
     <value>BUT_upload</value>
   </data>
   <data name="&gt;&gt;BUT_upload.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_upload.Parent" xml:space="preserve">
     <value>$this</value>
@@ -2061,7 +2061,7 @@ which result in a valid packet CRC
     <value>BUT_syncS2</value>
   </data>
   <data name="&gt;&gt;BUT_syncS2.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_syncS2.Parent" xml:space="preserve">
     <value>$this</value>
@@ -2085,7 +2085,7 @@ which result in a valid packet CRC
     <value>BUT_syncS3</value>
   </data>
   <data name="&gt;&gt;BUT_syncS3.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_syncS3.Parent" xml:space="preserve">
     <value>$this</value>
@@ -2109,7 +2109,7 @@ which result in a valid packet CRC
     <value>BUT_syncS5</value>
   </data>
   <data name="&gt;&gt;BUT_syncS5.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_syncS5.Parent" xml:space="preserve">
     <value>$this</value>
@@ -2715,7 +2715,7 @@ which result in a valid packet CRC
     <value>BUT_syncS8</value>
   </data>
   <data name="&gt;&gt;BUT_syncS8.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_syncS8.Parent" xml:space="preserve">
     <value>$this</value>
@@ -2742,7 +2742,7 @@ which result in a valid packet CRC
     <value>BUT_syncS9</value>
   </data>
   <data name="&gt;&gt;BUT_syncS9.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_syncS9.Parent" xml:space="preserve">
     <value>$this</value>
@@ -2769,7 +2769,7 @@ which result in a valid packet CRC
     <value>BUT_syncS10</value>
   </data>
   <data name="&gt;&gt;BUT_syncS10.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
+    <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value>
   </data>
   <data name="&gt;&gt;BUT_syncS10.Parent" xml:space="preserve">
     <value>$this</value>
diff --git a/Tools/ArdupilotMegaPlanner/SerialInput.Designer.cs b/Tools/ArdupilotMegaPlanner/SerialInput.Designer.cs
index babfd7e31..06d99e0a8 100644
--- a/Tools/ArdupilotMegaPlanner/SerialInput.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/SerialInput.Designer.cs
@@ -30,7 +30,7 @@
         {
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(SerialInput));
             this.CMB_serialport = new System.Windows.Forms.ComboBox();
-            this.BUT_connect = new ArdupilotMega.MyButton();
+            this.BUT_connect = new ArdupilotMega.Controls.MyButton();
             this.CMB_baudrate = new System.Windows.Forms.ComboBox();
             this.label1 = new System.Windows.Forms.Label();
             this.LBL_location = new System.Windows.Forms.Label();
@@ -125,7 +125,7 @@
         #endregion
 
         private System.Windows.Forms.ComboBox CMB_serialport;
-        private MyButton BUT_connect;
+        private ArdupilotMega.Controls.MyButton BUT_connect;
         private System.Windows.Forms.ComboBox CMB_baudrate;
         private System.Windows.Forms.Label label1;
         private System.Windows.Forms.Label LBL_location;
diff --git a/Tools/ArdupilotMegaPlanner/SerialOutput.Designer.cs b/Tools/ArdupilotMegaPlanner/SerialOutput.Designer.cs
index 099d4b32b..1f57d7eef 100644
--- a/Tools/ArdupilotMegaPlanner/SerialOutput.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/SerialOutput.Designer.cs
@@ -30,7 +30,7 @@
         {
             System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(SerialOutput));
             this.CMB_serialport = new System.Windows.Forms.ComboBox();
-            this.BUT_connect = new ArdupilotMega.MyButton();
+            this.BUT_connect = new ArdupilotMega.Controls.MyButton();
             this.CMB_baudrate = new System.Windows.Forms.ComboBox();
             this.SuspendLayout();
             // 
@@ -90,7 +90,7 @@
         #endregion
 
         private System.Windows.Forms.ComboBox CMB_serialport;
-        private MyButton BUT_connect;
+        private ArdupilotMega.Controls.MyButton BUT_connect;
         private System.Windows.Forms.ComboBox CMB_baudrate;
     }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/ThemeManager.cs b/Tools/ArdupilotMegaPlanner/ThemeManager.cs
index 859cd8e7d..c15b74ec6 100644
--- a/Tools/ArdupilotMegaPlanner/ThemeManager.cs
+++ b/Tools/ArdupilotMegaPlanner/ThemeManager.cs
@@ -3,6 +3,7 @@ using System.Drawing;
 using System.Windows.Forms;
 using ArdupilotMega.Controls.BackstageView;
 using log4net;
+using ArdupilotMega.Controls;
 
 namespace ArdupilotMega
 {
@@ -84,7 +85,7 @@ namespace ArdupilotMega
                 {
                     Color PrimeColor = Color.FromArgb(0x94, 0xc1, 0x1f);
 
-                    MyButton but = (MyButton)ctl;
+                    ArdupilotMega.Controls.MyButton but = (MyButton)ctl;
                     //but.BGGradTop = Color.FromArgb(PrimeColor.R, PrimeColor.G, PrimeColor.B);
                     //but.BGGradBot = Color.FromArgb(255 - (int)(PrimeColor.R * 0.27), 255 - (int)(PrimeColor.G * 0.14), 255 - (int)(PrimeColor.B * 0.79));
                     //but.ForeColor = Color.FromArgb(0x40, 0x57, 0x04); //Color.FromArgb(255 - (int)(PrimeColor.R * 0.7), 255 - (int)(PrimeColor.G * 0.8), 255 - (int)(PrimeColor.B * 0.1));
diff --git a/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj b/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj
index 8b7bd960d..11c4d121c 100644
--- a/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj
+++ b/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj
@@ -56,7 +56,8 @@
     <SignAssembly>false</SignAssembly>
   </PropertyGroup>
   <PropertyGroup>
-    <AssemblyOriginatorKeyFile>mykey.pfx</AssemblyOriginatorKeyFile>
+    <AssemblyOriginatorKeyFile>
+    </AssemblyOriginatorKeyFile>
   </PropertyGroup>
   <ItemGroup>
     <Reference Include="System" />
@@ -80,7 +81,6 @@
       <DesignTime>True</DesignTime>
     </Compile>
     <None Include="app.config" />
-    <None Include="mykey.pfx" />
     <None Include="Properties\Settings.settings">
       <Generator>SettingsSingleFileGenerator</Generator>
       <LastGenOutput>Settings.Designer.cs</LastGenOutput>
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skb b/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skb
deleted file mode 100644
index 700b26fc31b08bcf5a75f298ce80e6115710d7a1..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 43493
zcmeIbcT^Nh)IC}~3H6$DcElXPoUH*=L@^*{1qTHMMNmM+JZ98uK+JKBC@QF6M6Cgg
zC`u3mrZIww4C=jl5tUa}-HlFHf8Tp+y?@?Y>o<4doH<o}_O4y0s;jGe<`(@bD(eoW
z03Q$nCIDYB3`_%BFaQJsZ|w62MZbzl%>|u7YhaK6+GDE?{%=0m<#W4F@`ZbS)^B%@
zU7x$IBd!N_Xj%;{Dgxjy;56JPDA+GBV1U;&Tu{;pIDjA=-U-aW?=x{=4geaOl!V~_
zf`A_wk4r;v8F}HOD#?{OVPXNemKUxcfa?Z{wadxX9*FBr#kIUeyz)-K5&I_K22aAr
z24chjT<U^rd0~$aD8*yjIAN~*u|fD<&3j7`Zy>Hajk55eO#b4_D$12P;)uTZ_?eh(
zAjT8oRF<pT3)h`UTjht_N9qTNY-D4*;PPOqL;!A&4^Z(us_?P-vLM{P3B}QzaV^50
zbafDzjq6jLEBwz#xC$x@y(RFFi#-@eCOr}&M%9q0Vs8uFa39IFlAw^52z*qe7Rd%B
z&kw6kJ`>&qnO8<&g!_{%6IpxVR%-Ydvh{}Gp7F-<yl|Q;_<EF~6w4iRn~m!fYfNjA
zyqJZL4#0WSo0jqnLqJJBmf8vXy=hhn(M$aH48tuc9tAktdQ<I4&(9XyjgRkxF-YGE
zN?`p(&rs|Q#kGmTJ~S&yetF}lg4U%;U4E<#z)=G5AIb0H@q+uu8Gj-pV465Ou<!Rs
z5ERBfSA6VjdaTfnGJpE4qYLPmyDN?z_&YY914vCWzR6f8nwKu_8)=DbOdMgb&<ZhQ
z1de}^l0Y1h^b$WWw8L7E7oJBj+aVa$pQ7{G6O2ctALb_1z}fLX)gVlY>*0|?>X8|P
zZw2Z5LAYETufd>UF{V4N^Ly+KrubyW5;Vk|-Ra!mjhWBFx(DFV9|&yt<8eliNm=Yc
zp`BQPKc{N)NoYY?>k=}F|DM9D{=vz5q8IhFjz0~@6*FEa!3q)NKTE9pNN5%AcQG@C
zQGiFU==mL0m<REA5X<;H7Dg*Q#usPiR6Gli%=N?S2~4mu!>RftlS0MzV`YZpT0U4w
zu}wmD;aDSR&yyaTimf2r4j~rqPqs|9T@}gr^aibPZ%@Sk@(jees1?m@K1)dC6L=6%
zgd!y#jZVG%#*<O86aTFoJkYsJshZ>@Q^uuluOax|fd2-SAPsL|NQuI4s$fT#p(XHZ
zUJ36o{JG?`zN3QiJOA1>zHwV@^>pdwFf`QjW5OchPBIp_k29ATMnL}`yrz}jJqU0)
zp~>`Mm)-+=MLX&jTOUkL=cG@Co+>?<j#@ImTjx8ehyVT(RcA`^;=-3^_)r{y%tJ&q
zalF`Y_}H>?B|~v7GM^G*$V(>xm3OB@oD4uRh{@1lAj^nT4_lW4mi+CPz~n;#rt~n(
zl<*8@!<Tc#;AG^7U;;!JGS0~vjGtRn!cZvvXEidA`Sc5+6ExAR)SneZJQYb5Tv*}H
zLU#;DrXiAqUU*3OV@Pj6+frVx-k(0rfW{Fwz1uz_Ei3Cld6UCsc#{OcmCFCF^uOR@
z4S7z#YYSb~nsilVcY0o#M%4+%+KBB7rswNm+!!(+&&Kl|f#l^OXF4(ul4U44t4nH;
znxzNgqexzOv;6|d(z6n9atH|t@*6)R#K$QxAjHcrzz3i6ii$W;?vJ8@UQ>O%NnX(=
zm-{_e5?ul@J2G34EG21%asMLgmSD_`oV$L{_oZ+VDK6=P3wz<_5KX4yDiipIsYJS@
zVrg4^q!`_wc481-RNImOJQbic{QqI5C@NCp<~ccG4THS2S-FR{+dhYPLSETUj{5-r
z+iPn7apXTxSIh1~TH;O!vVAYxUGjw;JM3HZvrYz_IOovn30?0ayE{|L)p(Kvn~jL{
zTYJZhcm?tyeb=qi@zasPK}Q`%J^xNW$p6Frp<{6kAztxkVvzBP=Vt=2?b3Q8eG%YD
z?%;P^K!M4Ei?2vJgs$kwJ4vLXqN68nlbZOI3i)@l@J@qbS3ctX`G{`@3CjWBq(XXJ
zdg^(cjvSfCi&lW5X?|YBjZYSUF7(KuTv)H{e$_|Zha4`#mFWwk2v$Diwr?Y^caSd<
z{^iNz4|EPHDvgOd4e$!_3G(yu$8qpl$QvgpIRo<JkF2^$vfAQHI{GU5or^+9{Kl0w
z(1Xj8(<eFYiVHY$O=u4~{@)!=A`#+6MG8EhJGpwzrbF^qk>>Zx(w<ZzgXFhs+#d^1
zT+9^>9V$zY90|(Pe?75=1Vs&;dV5dup*}$q(!n@s@pWm455H^xg)@gBT*Y`b(nw@9
z4X%<7D;elP+MonKQU=rqX_;|SqjX%Sf`Ryi9065;P+Q;r{7726aC9Vzq+jC7)~*IB
z<Dw$m&6r&uuL+o4nc`4uqbio`KJPK=vFhTu@`G=|r@OLW?W~-OJPt*#aJhL0^73)y
zP}jgfywt$ij?<z9-_BvdI9NphYJ)lk0Pu2;H>wkZysT+g6KR`ueLGURrAJWOU`;QU
zwk@S?9YJU|;0l6BvyD6VQjyH>bj1Q1NB8n3WhRRoAN%h~Z0yFMnhd)}jIRnHz8Z!<
z6}ubkXWt_<8>#aXcF(+-4C__sSflN!*XZDvCqq02UZaZD!bfmalcs=cA&4Uw%>ZbD
zgG$8_`~P{nAw(Ku{V3WrL(NL*ko2Fm5Vkn|rNqLb?M68jM5B#2N)*%|bQ>;AIoi+E
z$bz~(*B<|An<gP<2S7VYtO4M71CPXZIH(j#OtmH7W)NM?TX*w`xpzW3Y|PYdg!gHr
z#44qn)l}a85gngZz{TB7hJOucv#_)CJv9Ey3H`DDaS~#k0O&@EH3S@QbRiz{verN#
zW_~kkGEq!7{U{}7s$MT05_PO=+X5Z-S$Ad6@Ik-cIoyLg#w|Ix<4_80^K^8LRe>K-
zR<oap>UyaXVi?4U5^DoE-f$ou@{&Rc)O6kZ>j^b&t-drD4bDT^T<lAUSw|3#*XH<A
z&Gnu;Y18zsVa0i_9X3Eu`a@^qz{kF}jE(II*dA&O`ZJ6>Q=hdsttQ9sn%mZb4wR{V
z6-~MYtAE|qY+3UdxZ*`*9Y3$#h|CPN3}T)S1e_Zcr;}(50>BMdk%}Wq<5x3;NTZ7r
zdTmChbf{x$_r+H{(q8+1x4Uxs=GSmlR)?KOZSTSk-5yk!(={7qtgLf+pv_H5uMGoW
z6eZ>YINlgRJme*-xuN}p=|opU@D8fEcIc6G=*raY4?MBYTCvSFn|+8anTvYdajtV|
z_H8)a^<bSg9*<#<kRM^I$0SG;^8omyMyAbvfa8sE#6w=P#PsFsg%ZW|H~E>txM*ZL
zB<fh#?u)MzrNj=bTj6p1!3WrV>4Myzy;EVdZ&2OWn#bs*<B<8)*2PN{!&AB+B{l+Z
zyfKM*$V&<(bf(F{(VI}y4(-Ixxr>9?TqN5J(g?!w#tAk)M04XAUUP6Vp*YXUxq_4#
zI<=*-b;~xfv4ij#TN>LHOlN$a)MwpmDboT+s}H<JSE~05os*LSZ=I_=sbk-4i0aNw
zi=BO2(rY1rn?=R(5RDlCUkZ|!wKzi4w0n-xUNe3<Ow&o%bbdNyg$Mxia0F{&^^Z+@
zVoA$`Oa9$<<WXiS9C>8M*lq8Rp-me*1g}%*CA~HmfQ6J;AmDgoKJomI#0-=B_aM5O
zC-0)f%!g9aA--UdG-Engihb6^DjIIK__yypG~|iD<>j=yFm~^A_f>;G!cV7GT-kLw
zO`_Nm09H_9c(;!?mJttm$tng^$7VoWsGWI;SM2qkbV$^(t{njW#y)Fe=d11i*S_{g
zSg8r{xY9BWwwQOW&hEbVV3m*_C6g+}ONgxoU>zkkA8@>}hIq(J3MF(VS#A+(`X;Su
zE*e*@VRLaKC1xE#%=4lV9<*r#jI?RSX}8khMh0&qUgt_V1c5D#Zz=UzOE8;DKR9^t
zF_`(Y&W|@!Q{mu(hF{&yc`(ZJsnf}0=@JRH0d6OiV2NmK=l6@G@InJjiLC-j0}QA4
z(*^*~_;g76!MeE{!CvgMCf4}Y@Qx2v+3*)?Hu-zkG`K9e$L1&VU&H)|6Q_KiaZ^If
z2*3eKY!l#kV;}L5mo?ND8K`4bO(*teX2HxkNsFHSmkRs+TYYxYjSp~k>SnjE?^7jE
z`v4b3p*D-gVF1W}m=sFXz|QE5aG_p5oY$at%i_sOcQa@_DFc2(`3|1ZnN5%rpb8Va
z3W#BRm1TTlB88rsLOC3Eqd2-z1Ja?~^7S+m^#ovjLR5o|W-#epW95;2%QiJnhjP5m
zGg0jU>l31aw)Lh_uC9alsAuqkoGcQpJF*eD#Q09j_=KqDsqK6SS5SWxAN6FrbjWhB
z2MJ76os3V2svAEskZ?7fAHeInen~o%TP|H?qFw^5Pl#%)xtER_qa)8%Z{H^!%JI6%
zL>&%TpAc2gxzZ~|L%u8Js^7IU9g;<fwXXd^3gf#f;}fEqE<Ft*y6P|TIbiNRE*-KQ
zhJ!RF>O>iz5Eb-^^B}t7MJwfMsvVOK<xbC;Ow<&>`h=+3Q+<O8S6%-Rd=Au}n-1l8
zJz}EH1FTPoYOHywIpJzNFpx$yv_F>)$w|;!*XiIX<I9xsi3*(HrW3Aa_hB@uF%&Oj
zSPt{R3nuE{GCm=y>G)!LLIOJn^IVsnNrzjQ2ur~m#`jdlCn|9BsxRTH?dHzwIy5RB
z%JF)~MBNKm-xe9)8yTN~uANzZ0@2^x<nu<t!sLfX_6Y_l23WAq`Wyoa=4iCvAET`a
z(f>U)?|{dKI@<(a$wehfT<DPPD7~J`1K=~A_@e>G8~MaTUe;Y5Bko%m&eiEhs2Qq$
zrPM%&ChYY7O@>%Pvz_*VUmv6SVI9I|KG*?0-iCb{eKi+l=)O&y<|HMS54i7?*jE5}
z<3D1s#4I8)U89lyl-QwMO3Xa0FH5XQX68Rl$yzt}Jotv8td$K)ZNBGlr5IGDf4{U+
z%AIiRl6y5XK3Y)GgCp-hR!oN+KBAUEycqlnI2Bh1e>^7|3J$199f`8%iyN?f?Euo*
z`iy^R0}SCZ+g>F(mRNt)ku9+mqR}W<*z8#B4yf;VYvSWP3mU%K-v0pJI<Y3E;JDJ1
zSP2gBMk!*j#EL{>220>HqAYNFO^F%LjAxatz_I79OLSA$T19X0A!MUd9{OIzbFu&V
zwXm?x`Z@tu?;+2J!RJHM&Pd3X=Rg%owxVcMA_gI29d`6TUWqqg9;(@Ob6P>?b+B)G
zout8!@1a+Be%d;|mxisxaW!dJ1Ox+bE7p|JAOV!bUTY}-_g97&nD4=r_Z6QF`?tWo
zX?4OD^~gi*8z7IBHKcn?B{)t?p-ez9>T*CU3ndJG^XG7SC28FIiOOv{*_xHR5yuh>
z@!fba`qMr5^yZiNfit$iSqIPL9_pHhF85Op`C3g%tS-kjrNkO?fHxWwgGg&V7AkN8
zG2KfA%>!*l7M}-U3s_>UICc$i6;xnUoPKg`qviP)<m)mi>)qH8xMJ?nR?A1nz#8AP
zeY$ksELoto<UkurwzX*35rdGm?i`1!182U#VQoCdH@NaL1lpPc|5{%d4JVfzyu@1}
z4Qt179ckF>Krkv2539jV&<K02b-7tQK9>IsAOqL9<~`L#-@$>^r8~z)XeBCZZj(*d
zG5SMkG=h2C7B&Lp*i}plXvHXd?#ZY8#DrY5t%sNXQms&Aw<Q(nD?WiuJAHV%^sq^y
zY)=k2Q3-US;Xn*l*|nuDSuXfQ(qhej&0@FDLbrRq4J=jS37qB{xiM;=G^_*1^`&9&
z0>NlaJgl;5pgYrojA4D_>s-r)6^6TQy5=<#_TR0E+zOtcpF?*}SW_BF=7??_H;_W5
z0>N<Qz(83jF_E)Z1(6Oj)p@}ua-Y$x-0mDp>{UIRR@1NNLa!mS=2xvd6XyTA*P?0R
zW3*;;!xi2dDKS@$8%~K0;Q((8B?hYj6!QSgc<V`KTHT;zJ`c*{Rfjb1#&DUqighk#
z0wRjF?-6iklyx5gt~B~&f%nhWep+(T3>5wX%&Zq1jYckZZxPpOl|<Pg9H*xZcnAc;
zlLLC020Rjng6{4=R9Rz_2YdsxGua0Ca4fOd!Eu)-VPeaZSKcgqIRkyj@$Oi8YBX}3
zuqwUpvy~EJo*d^(iFxB2d(@an3|84O#mX+J+LkD*&$>#9>9w&ev8misM%kxe45OlF
znHzVu-@b>&^nHIg$GinK?9kcxO_v9!l{+wHSEO|F$Dae!DaQcO2qXp}Ydv?3-BGS>
za@IXGKe@r`$``hvNzPGi*Y?bV8+v_D?0ZNWHjv|H(y-5gV2mXm64p8oUH~7a1?Fb~
z#x6K?C$8)8@!!^>Ug16F1iiio!xj(N72oJQB4KJ7#I=k!$IYWqW*``II51BZN*rNv
zN2lS$1?C=ic)4e<XXReRvBU<K)b+OOmIp%)=<}|PS%<bP`FZvEzxQBZ*M=o$caajC
z!*NR~F#`v913yW#REF48F%QhHt|JIBaOVo2pp#Cr#8z_bwZa=Pl~J+lmO*1{t&f2b
z%P(#kl)D3Eo%7&4KU&~gyJl0~?3Qjcg>hgFCA&&ARuhAevCf0;!PkxyR*Zp%cd7m!
zcx?x&{VZGa0*Bp@;O7tbNW-q?xD7OHHV}*e;vr$J^WYs=guPOq&|#(yw)A=jG`~)D
zF~NhZE?YS^!b)zdOw^UwXWghOPmk<fpnL+yue?3VY0nOn*lk_=Zi%^YQkzDfa#N%m
zQrkJOi#BQt$MMDv;$gJ{%R_HX*F1sYOYh%1aA*fwGSz9`qJ&)7_~rKc3z@JxIBp*e
z`w<AnD&k?a5>>HXK7h;`#@3Nk6=Ulm>5yD=S*!RBL^2wDE1nWZY;+_Ur(1BC#?a;T
zXO)fO*a(qg&T5xBk0C6;UL%cQI4*NL_c&L?@G6qwRg#NhxE|-o`pmjbjb!RI5*eA6
zT=XPu(k|K0w`n%M4<n5bClleg7(u7a9ZK3{=&_YX(4Sh!MmWon)r~c;R@`yM*PV-F
zd}lfKjOZ>?&s}7spS5T_X_H~wcD_xEr?HGK%S1RUM$k^m;HWAWH_!;iwtuq`5;$@`
zv2N2C?kwZ;;Vv`21dhx>*2gZAskcaEWO%-u?u{6hMNmfOS28z9Z^%SQ;BGKTH#jn?
zt<hI<35;*6%(23F!VfLbv7rCE<w~NI{(?*KzOi9{S31_fq-M0tSYa@$UaIUkxyx{f
z;#i-+!8ocl9ZjaR+C0uipLEFPR3w+lL`{|P2~iDBFZmI%*_KAd54)s8mO~Wxh>02}
z;}fFlM?I#a#9XR0A9W4BbH?V%aqcM-HB-hXMAePhNHZO{RNxhG3c&ktOoTY@1>?Ic
z;}fEqcaKt#KGl`rc&;T^;T>Kk!ddPO<9jOO6Lmebg=VmMyMpI>9PdWU@p{KZy}_}*
z1R38O8DC>@_QnmOFJ0C({&v^UsccqSI9puFdSuwjJa%B=`ZD!gfrVji;R2X?L9+GO
z8)u?!IWB&5Hp?l$mAsp|-*;$Cm4oR$4qeSEv`p7k%eJXNoI`Z*Z(7@Me9vwYN!!zw
ztzF3d$F!nQj9}b6l5zp_cF+h$PG&>nmrMkqE!xrNXHjH*Fg;%9wX%5D(5YAOW$y2`
z(Dnu`XW1zfLL~jV!kJW!hyq$$A1JevrBZMTX>Y2;2)fs;C?0sdgmM9+@$4b3Z6g!m
zm#Buh>rlF5Z+a2Iw`NLjHbN;8Py3-0tqqoy;QR5DBU`();uoWSX$9LOr4%+y%WM>-
z8J|kVCo1@OIej!lx1a9|!|>C^ePNp7NgvfQKABHjW(bjaOrf&aGIOF2t*vwU!uQ;?
z2)1Qa6_prv*k{0bh|koW4p1(}J~@1EzBt83s38+UI3C0{o``T9{mIAlcwNfP;<o7W
z5&t*_H<7l*eD*dQyN+CJMQw(04H;jt4%)o;ybiW2`Hb?L&LY{0ZPxbwOlzC^|Dv3=
zK7nlQhKkAzhlYx(j8D+PY#H2(=wMu$PGf>inZ-I7`(Ab=W#)Th`959vki~1JsKdmr
zqiD+bYRmYFTP8lxXc{Aoi@t+cq}Ihcj0C}impCr;z3|;%={U4k*fJdK6%84mpo12?
z8iiv3UG2NPwv#f7buhUf8%@ge%|=ljOm6pCybg+HOzdWg_KdHojIX$5hUP!$UZA<N
zFk8a*EK*ld2jjz1lZg)cgZw;i>eiO6-Cfa|;m}=S&-er#bY)vlC2ci0@cCfckyNY$
zIJbe8nFjLtpj~{8#dA<}U}ASr=onvn8DDYBOr00Hla>{qccwLDk@|=_fK5ATZSkB2
zd}Yp3eHC394t*8f8K0no>936;L<e09VSb1>T&#mpe~p$IF8lELF#jmaZh*ppiS3|p
zWqdjrUjf&bsn<tQz|8Y~6orh>RiR*xRVW59K2FB>`@Fw&p#y2XF}O5;=2<3ljW<%k
zvK%S)iT2S+H`0UVU8VSSMkv0IE*+y|WFm;;v1<-pr<yH=bUYfa<NFP4%Ul(nOv_wF
z4yH&jlC(mr5zaCbHnSYOWFm+;5WSVQ!7zC#?Pv2WuirV){Q^}8{9H!M^owM+k$q(P
zr;zhz823@IK2B_f`IYMg(hAUV2A^$57O}0EEY{W+-lT2TyZZCBdv9ZF`^&6R{AKcC
zjLi7ZDZCi|U1j+D%jEwUk)_#T_BfIqV3m?)hraqOmSu>{EM>14!=Sepqw039Xh5Qh
zs|u6bE;eeY41X_~Ia$a7y^A+xs;|VaYqZs8r$e^4x+>-|yjsin{6((#DT|tft6?4A
zPuk8#ma9QVLxarx8X|LEYpMuk7}?4&GRT~_LPVDM8Jkg5QR8?1thh>MD>qDLbx~Cj
z!l2hygfYG_8J3|kD<-iw60`X4dkAAeTetx~8_7hqRjgxtm1TSe8Q(e?J=V#ral#Ze
z7>r6X@dW1PF*E3+kGdEQKOYuMOo!|$y|iL06ICVS6Qgc_OQRZ2Eu^DeJJ~NCmSQ6O
z;&w8=oif)0TV>8MTNNXjV-+%tJY{@73KsVl=flL?shG_8Cd=|;<N3(qvYfZdV0g;-
z!esg|L}uKqlgV&{Y&NsGI7Vi^oF_B0`OD5#21YAynLhGV_%ro{tTD9DjD>jaF^yWn
zkLu%99*N(-GW>XUij<kN5iJAtwU6*;>-~-M;{0IzwuVMBsxQ&n`oZnl+VP5W43l^<
zf_CKEID)6O8$=_RS~g}QT$YI-w8d1ggC1|l8%2-T?cp9l7Vokm;eX~}NFG3A7<c;e
zF}B*X9IhxXGZ6$1+V9(_X4-FW>G6gI)r<ASYh}L7pC9+YvjQ9Yh9aJc9j~~~_|D7t
zZYa((^#oqV8ArSj)>e0{({|dYYp)isUqG9ZBWT%m=N(l4hxjQ!X+MkY+peSQAnoWD
ze4J8e(%~Hj^{yg~@rk{ZxOg=|F+5e%2;h3l3^C)hecSQ-GMi4}FRkL&(NLC2rkF3r
zbJsVJTKY$D4|z9kZJmMNt@HDN;vQx~?m?Bsw=wY&8NZs<{dMC|<5zIjmoDbV%9rT+
z8jn?hJzk<(S8t5fACZ1-Ekgma6yyo6`=arX7$lGsN@$`XM6;O^DymDHVXB?O5_>K~
zY}&GfYGaLW;F(&jX4YQy8XZf#KEc`k0aB>FDmopwB)R+jOaWd}VrJ2JsNi185EE#D
z;pf*=TK%IaJ%h`q3`o?mZpL#(HltY7r>S;ZzQ2a{`m_06SH3|9kF^_m?0qKsdHSvT
z!i0+wVs91Ty+DlPjU3|nUlcP3r}L>Nd>g=2Si~x3Q9Nget$3z_Z^plYF^Ap^EtC8j
zjj}y>LXQ=D%MH;fF0qPnpDD3C1>lW*Vz9&n#mrAP_!Gsn_cHhysod-gnQXr!W~4U8
zCYaRMUphqVgXdG(W)vvCVMJ@q#l*S1XB9oZZre@d-5jpD2ie*MiXTjbG(`d9D;_C2
zQv@AX`Y+RWk+{0|_?crV2cUd_BUq1=sZ&qbEdF;cI^C$?Lu4NdtdalnX`gbp(8r}!
zqCa-qE9v+93QnmcBL#o^mp3>iHZY*1xj-p2*tqpyI)rsYU(g|JKDmb#tb`n~SGKNo
z!%w5<noSWku2^7z_O{!M`e%^iyVhMAI!r=jpx44o_-~%tD8XNpSV_^~l-yr3#7ZbF
zj0P=jjx{<z;vD*GO6O)nFIr%!XI{hJlsto!{q8={_ns($%2RL^1Sr8Mrvw#bpo%rn
zJM>;gIt6IT(}kOE!zfmRs>%{LhIQw-Ioo;q<=;V#^S_O=FUo^nA+E!-JdeZODRutd
z*5r_cn2nOFL5WpS0^X=b3<4~liw?c${A`-GfzB4@Aq_Gin|D9N+&2gKY$MIkE_uS|
z?ywe_Opa-lb(v;-``0PfF7`RnZfrR=pzeD(Gr>IRYl#eaVQ}Tk&~QQ0j5<otfHtF^
zXw)YL+YGIkWBTw?`>DR!?sQO^C-%9|5Nj$!Ea%k3@=^ajM=vi<FLN6cvkx6sAqa09
zyh>QUwcShUGbl}zpamt?Of>2%xfU|S#JR=zmC`b=XicvIjJ0~-heRFg-e{_{XA~PZ
z>`wW9Cm*4<(RV71o01FF(HjGlk+)&F?9w+!3^*-O%uWf~3B)+wXhS^zi(*=*pnXI!
zy~h*U_4-stR<X{?rVO#0ZRQVorhJ43hi%^9{&X(<XH(3!y<?JL*DEWAoqrrFA=X66
zb)&>ODFJVEAqGoKoE=AJ9H6wugwlaxociM)B;(auF^iay`b^bcQePWo;a3wrHQ9`G
zRO*;!3|RQ+qt69|Je-@nn6n@cHhbQ*$LF{-So5!*j&s^vk~9M<L2ud&2hngM2HOlr
zF(Y*jXX#BuU2tDI#B}>gvikOuAvPxG=+Xfz5Nc}Ead(N?d9ZywZq=9PY4BNtfW=Xh
zrNms6U;ri7Uo@PQ+yEJ3g1%ap-AAcj@Gw0Yn+AN!ghU-{efuegFpAB#Kk;O5hfC<|
z;d+xI!t!8_|HX-?uwvS(H8x)#ASLFe1j7Vk9B;T2kDOv8`K{sYmHim_{inRb*0eRD
zuRV9i><Y+(3tG>~$}N))qi-7=BX&vQU6kBd3O`B-cw;m%Sa?Af{kf21L>FTj;cnrD
z_y>?B)>P@m5JUSnp6^=v5lXLieD}?dA7I$!6Q?@i9pbFTPkhdemVOIUuLRzdSQ{nB
z8{>(GCDv5TB=gHa+GXa~3-|?xSL6ds)mkw>8DcJH&Z%mxe~6Yh8uO@S&0OdfYM;Cn
z|MJA*iBr1!zLie8zDnRviA@%b@k-8LhS&`S(Lf4+gE^-bIz6s8ugoLVPPg`aYQ_f$
zmUQ#!>zDzz*1q20aEFVM5jIT;f(3YvH>ML0t4n94ANE?GC7s6mpZz)E5!x~*w#k#b
zA7HPfZKptXI-GN5&6w#sq+Q^v<YrT-E}}6@31-Vc3Atgqu0Kw4!{qRhc7XnAid=4Z
zDHkxrst+w^vz^-qFI01iOewHH*Hfc<-T$>7)n30Qa%^OTM1%QCu!s`VD>>d+NIa|t
zUP|_2@w$SAFF$_PqUrd1<f`NX|EgasuzAtl5tsipq8p{gHjaI^S^~dJ3BoA+a?x0*
z<icd&&r>Mt3~-b=xh~kj4gWUsB^vOrO-;wZY^a>JXU&Dh4`78gm3OV5iX`xMN^Tv6
zA0--Vlwh3<eDNGBE?dAZ7dn}l?~cF6jEs#k#74F_oe{a>1**0|>-ahHEu3D`%e&?B
zC-6yn{?$39k|e~|D7h_^ScDSr#wKF0-Lg?h)=t)``PROcDR;sfbnPFdvAo?YIB40N
zP>+^RVE)=q^So*$N}%c}xm^@$lW6Qvf?cvuLUQU#+*m=9)7<(HU7DFIonlv(`(%h^
z%(#DL$oMzt(5PLi2i2d!+_I?yx(B_4@89n4cC_<#39%hY?jR+$R|$AyKQUMhEQ*cT
zYpubyDF#!MsAnj7&d#`(Yu~}s1EXKNxjulqCm42o?<oB`L4=Y!N}(J?<A@R*m4Pau
zWT9$a-nAzyGz;B|Nlt2z@D5JBy~O`ukH;`ZX{>%YPb&8jC3liSl@pB^B{(SywU24l
zrz5dLs@{Bo)=eB&^Xd7wF#F%^O{U1luu|=p8*@XYP<xf!Sqc>+8mE=utPE6DB@6XW
z-oLxo?0bsd?tOfEW8iC;@!w7EW7I3?zpA<ZVYu|m<foO~B??tdG~$)uk_=R~xQa4$
zJiLY^k$&J7x~?}aC}fi;QOWMI1bugz@y7KbtUqDv#?a#*Q0LF@4kvP%sMgct;q?|u
zFU{X7xT};{f)emX5;52$N)*q1T2Gh7gqSgFHNSvP?8g#ImLukV`g5P#SD@pC+J^4&
z_$O{c6Z4)rW}?1}$2WESb{Se<J0>Z)6iV!-67a??Vz9)Lm6^;4-<`aq<b!!vV4Ta$
z6YWlXL>(^YOz9SpiB`?-W;=6)^ot@H3NC{}-BJohni6ElLJ1?>uq;PUNBF$4{494{
z=HZ!#GQ`H@1TWm${00n<8hop1@JIAv)xoLrKW3u(DLrhjL`sRJDY?g#*aIctjYq^_
zHAtkBiS_LNLy?SYT95i?w;w#H)+8P_@9w&&zhfTyTxj#jGbRI-su$hhaDQoT+*EQe
zDg1LK;0-e|Soi`NDA%|%o##zI0zcLYj~cl#51DSLbK7rDN1Z;@)Oj?MZe5v`Tn>f$
zsSu2}N{}N9^^j@R`$ZWSlKrCL&C55Z*<8p&+ismpt2!$U-BlE!v#A#(iS<Cq<x!}&
zqLHfvc`{IG3Koic+wta%DOX^nu9FXr>Xe7jq=+u|0qH1av%~s^*Q7sVldI(Zp-{gR
zg7H}i{*i&YD~@{O^p5myl4;EtdhMj2kjm~D6^KJo=U(5Fq@i|$n%36tk7jEZD(^Da
zYK2O6pSVy-nrody1<I<7ud1>T`>gXS>DUOHSB3jfRO0%kJtHje*k7Z3TlctvEQc%C
zSHwg}df>Z~Q>f^El@jm<P+^13D<A{)`d7V2`UCe-)2oB~8_#@%o?bp%!*5=M-)<{f
zotk@Ga*o7b`7J@Aswf3RqXH#lq1e`c6MID;T$X;r&=lK)UN{=R4P~divMRD4Z>>wX
zD!jo|-)yu#Qd42ik>~L2^N~#qHqYS9{5GwQO_45YzT!PBO16v&@J2aeu)360v0YkL
zRls!1f_`u2TrK$+`8Mm`<*@w+*!ybs2bVVYU_`^pbz4M8ug|Kexat(XstWMNe@g6O
z;eRN~Vy|^ewF`8gKJLpx(|g73^7efVAJ&VhH|^4E=o`0h&BlL{CEZd+#nq)yg$lu_
ztpasrp!O+QDA#kj`pPH^eOu(a;_#@~aE5A=<Kx8FFlyRdm0y7rs<w)2NTK#C1;bVa
z8p=Yk0xmpN2TZPGLVYVWUR8Hl9{iE1O?L@RgL77I8(AGnFJh{yxaJhfRy3NbKywOZ
zEtY@q5>PVgHA?(6VsPSCGpzP&Z((TO3+Q`q$&*Xhu1Umds^aWu*m$L26cK~%7oC#b
zsIOT6<?E5dUcuGXt9O4~)r>lguaoI{;}tqzx^>!`vo|CoGhe}VpiodL80}P`gDjM|
z*4^k!H+%GBQs~gomn>k{`(0Hmv0F>;Bv<i!0tZzp6}9o=JM_%8{WKewM<^z~t9t*i
z1PQTrDy|15)<p$)qZ=_;4Z5n>yC~1#io&c)ui%Xz^P_#+zebBZHo9KF_#7>;yzb{R
z<cb6;N5MH!sBS93aKJxgEej=RVEmZIuL6GEq5F2GhBoYmS6>-oRW=OWQufjlSTEDv
zxnq+L$Y=Jc)urC2p%aBWhYWE%FCpfj;`&o!&MLqgF2rCp7^3Woz1AtW`OQwp!qhD2
zILGs9VaXgc-nVjzuWn}4Xi%F-OBLz8w=OEqjY7F81!Is3xXD2ElY#0HIqAauleb~~
z*cM;MwaY`RUhSSSy5?Q<!XEvXop4UlszEAl1ch=}3dS%M7$FPQmuc1avpwcE%gchF
zL$`L?I^aF(8GG+`BfP!huYWgcvRax%&MMA>LJbp*F)H983nlcd_SQdiv)HKWNVgeu
zQBBz$!|^JX*n>Jt^52)d3+?((A2$1J9$NCDuGa!ZB66)iq<goXF%k{Ns5l==%u5A$
zV*)YQp6#njWG49*)uT7fbIO8)n|1p-SCxyrlj>CncS}Y7n+`c$*>qL{m7wINP$(Cb
zVEC!P6j>-i1N~PU{)R-$#x%Rl9u?W_o+d+VvN?LkiplBl`J9vM7xm0T5B`0-%yc^m
zeQex$OU;QVB*gqwTredTr~<q(ofxbJ(^TvgeeahwF1aj9h811i;?iv`$UV;9WkvN1
z=uJEAoFh(0Bv8-s9utL{t`dw{Dll6XO3TQd-DL2nXDK(~bN`Hj6gvx=vZH;CT<$zN
zmz_5>f8SvV)GQUZkV4H@0p6&m#2&U)<5knJ*Lutr=oYIhR!WCcf+E7_bjd>=)l{E8
z&$^0I6lF34R-BYT1**7Z6l#KKEKz}FvQR?Lns)s~vs*j-6YW`Wz9XC6t7M2BPn<r_
z$=(F(XurRmb=HDLmsibPeChytli%iZwMIq>u_Y>Q4JEcx1$bjMF<1>&saUz4JeQ6i
zx-%ILiw)^+-vs}##DA+)T?U*(Uvu6LDX1isd%lW`pirwtBU}X{WT84UJ^OjUnx<PG
zo`R{`q@A<gS<t`g@JF7;MX+_ljMJS};gVK`tGI0xYKsc+Mkgiqu&o+WyjllCPm<NT
z;qpYfEo8iFU^k6-tJrP!NBO;OHZrEbJK-f`hm6icHU{I*c}H)da*fSFdBdbXu7daU
z_flfJRD!XG7%Z{fDj^Sa;dwEH7;sw0KNwdzf+coHhFJLtbLu<xFu{v=cTPXE$bv3*
zYVp2)#$^;Vqh;g*6fIF~kBU1&i5*k{-iRayOYD$pJoZ|Tg|=lw-!)v20yX>ZW{+Bz
zho+{r(TC(*NAAw!8o1n!l|Xr^xEKl*DH_LBAVwBSoax&Y(why2u}A1k4_?Xa=*P(r
z^UAvWX!#ctY}DgJ|5ZCJ=-mG7r8kq~(AdE>B06-Aln^_v;?7cHu`0kDr-{L8uv^7G
zEtQ}+#ORW^^<LDml*_R8&h8)non%3$7MuFNuAPKjhp1hH?M_MH530D!6h2-Bc;g~5
zSom`?P+ryMKYx4q9Ln)@Z2scD1wA;uZ}*wS+hJC3)x4$;H%g!`s<<l@%A^3ik*LCk
z98?_BsvOJe_<c7JJbhr(Uh@hpYFzh;ny;5ov@(8h(+<+aidAvR6e>|PZm2-A4AglA
z3)L@d-K$66&!Cnqm5yso7Br&bUsbMuKMg;r-;Ue8EC5;WO5IR#sTAt00`SHi6*kyb
z#i>>?t*X8&qOpCAOE9G6&qd?TSx{lwHk%TfoJ6k=rmYXHb5J7SN)>mXLY)?kdn#~W
z7K*+3<E3QbOD^fwbW8O(_yuuxU0ztwn9vSO{m$=0htE8Ja3DZBYu{6GPbqws3h>5b
zVz4dsQnFKNuTHH>Ke%}ewz<)2@ZX;-=x&P-4&_%wpc%cpcTQcoL(<YMD()49dMp|*
zRNxhbvYrIe2F?mtvpO7pOuG5#{ZHJ2GV!H*sn)`C&aM+8fpms`q2h9A*vWWvi5jzr
z!M5N$y?bU2b*$Im6EDJI@h`P3dRY&Pm7Bb;{FyojQKM`1%eVECK7o^^;_@iM9nr{D
zfjn6#_D<QZi2P4CFKmPx3NL+X{>y^ywTqAHP;oZASHkkCL3!!8!nXqdp-{OhjyFE5
zu!pqDx&>bx%wO^z>Y<<Ws_A8L*mm#t!Jb_=!+OWf*VXQ8C4KN&#TC%7w-tghU5O1=
ztaCE=w5Ghz>a87i3|_2Ma=dGv1s+tmmMhx;ZwECV_Nu6t^q$t=O0I}PomB|NPZcPV
zfjXpOZ=XG{zqmui|4yT&UgjqKV=ZvUf>Mv3w2p@+=Y9QZu90s4{8VvjHQ8yxa}RGQ
z)!1NLbx6fN?%|*eEbY+jJj%VUN-KN80-d`Z^+>XuhTg9~Z$tf#NM?rl_{k;;rBn+>
zNj3P3LRt6A-u*4MME1RoT3_dOyXEJ>7O}S8A)l|oIJ<p4FBC~1)+njw%G0p;T*(`w
zmDodCU>$Z?E*iJI!*S?bSaGK6vjy&(y3z1p>q<Ciaru^ci;NPsc&4mE!<rO=flmZg
zWWtuNb~0p<`7~M)?={F{hXuMdXw@$JvI*{W-q8hCJ1Gf^C;gf<Y`kdTbA3&juvzH|
ztw!BAgNzHB^?I-${~*%y!|2|%%W#moc7d|g2}xLd7OzLc;`0}8;3Z8xnXuowsyr<B
z6VUT1TYj|dZh`N@+Jtu=c@_Rwq1%S+8B%TWf}|l0yGu0iHE2T`)_NOMSR)u>ZpR`l
zytb8aMU)hGU3`SrIPv}|Qf9i&KfVRV8?WOvm35rvY9W%@YZ;AX*xH|e5=9xx)^4e8
zhPhZrXema}W-N=NTyh`N#iVIm1RKFlCW5%;+Z;iU2Lm4Q$Ip3k9kO_K>bCzg2Se}P
ze2j(v(HJ0p0n4F-+K!1Ja_|nPn(1;T@!P7OV~X`OpL3^W=6{yZGVQ|4Z0s)TmQ3uH
z>duU>xs0!ix;ax%;H9@4;D-AS7>6|Cd*?*w;)k~Nk;lDAnPF{LT4wItjNNkAiM?bP
zV>^P>)|GRjJ4E^|9ogEBYWP1fF)r%9n)EX8u20dx`73E+#+h$5ok_|JU^V}=^FEm`
zaP<+H0P~&=q_%G0IR2sS4L8y-GwbZ?tL}}NSkEgzH<cNB_t{IdtLlvGbD1yEam_X@
zJoN(hbR9F|M!fWvYA-eDPluGVXt)rAG(id_4uv@LCPK`(dO2-|`PN@7vB5ILMxTEi
zdSK2Q<n!5O*bUVi1Seh{`tV04Oi<4#`?ud2$rLh34csX)H_>oWbM7+41X{*w+tyQc
zH&&q61Ev!{QXx^tx*3DjBN@eN-tr18{pdC7QNGpKYG2==-p4B)dw%jBtk!Ln^QyCP
z5@I9NV2nVF<Bd_o^S>yjTYPv2?aGB&{4egVE=Xm%Qm-D&5c_^8Y2@>6Z&3GEi>B4?
z{RX8hUAnk;K_-0HW$yE1uB>9*1WIh28t{e}F<4@PV%im9^asJkFBEFa&rE|lT;EzT
zsP>id2{Cl*mjscfnM?5xejCazVv}KtOa$S0li6z(Io{Y}54~w_%6yXwS-dIg0ER>H
zNYSrLTt;GO@8$CkZGS4uj@jwzzBq#QND0}N^VKK&5}Z``ZCd(z3#{ndJn8nzOYnu~
zbej?>(UN|5R&ya#-f3#U8$rZi<()1LVbj;!bO@WfRpI-+=SWtZ*)qh|K7Wz>>iuPy
z?h|%kAig`-X{Yb}Vb|l~rSvbpp~=!UQ>Yruqr~QjMv$7DCqrzuTF+?UZadXw+353d
zXZLbT#~-r5+%6>w-G0Qwh8~uil^aPl7^mhI3s8b#P=m!XP{kUUZNDugodZ5}rq7~+
z;X7FkR;Xt)#7qV1Tc3X3gtvaKO)l(bf$=p_rbqA*xcUB_gYIV!NIEA}&8?!uma748
zgb{=793k(_^BQcYIWsnx&KA1uo9;q3#{$HzGzRzHM(P`q(PoI>brqN1#qZW5C0xCZ
zX-2=%bw|`({~V5=?Xk1xr1vmw(Xu$718HdIwRSsFwo3Pv*Q&ur+Klz0v4I$DGr~n;
z`s9LrgqVJL6x|Ba9&k%xh;5T0_GIDWy>Bv}!%qJmS~J1tJ?!0Nzq4EWG_*V*w@c+@
z=@t7{HP}gsZ5NFVYHp_tF>zdPezTv@GPGOHuU5(rPk}@oYsI#y_cDsr9<sXbm!ps1
zZa8rP+?orU-2UR)=hjUW-3n&9b~ym8ukVd&a6ll&@y0&l`Ck;nQw~+k^va$pX1+3l
zRqTj*8$&E5{MMjr_?vRmcR1JbewqtcOc~@HF#kHbsqY$c^{(^^bE}#=Mu{C(1Kx-t
z21`s(On(v`Ac`5ihtu=DVf{aMAsMgMis{9U*9Cqu()!Wqbk;MCKFwxitokI=jEci!
zZ{<`m!4?yIR?I$~2R(A~zPi*%MZ*W#p6+^nzeL{?YH)@&<CJK`5rb_;tVqn%{9q&@
zrmMf6E}@KuG*;hu8DhtitG1n7fMA>bznt%%$b(N3t_H_DrlQ9eJR<B$Njv_68eFEt
zE{aB+n!7AROw7nttB(>|+8eoa*<xs=z5|Im*80Y)lNiO?ma|_pZSN&my`E=&DN`Oi
zaKBWqJylat!l`{9m2;$uC91(Sff&adSBOVWF_Qe&@O#zq4E*|-t|{LBCV0Nu`n*qv
z@?h^BA;+Dkr=snT_ASqt&FaFXQ21mu;Eh|vVBtkw?oK#HbTOyCqa)Rz_DhB=v2E&f
zhM2MU<4pAJAv~&2TG7fb7j}1Bdv-$WG~|?{FJDb_Op-}yYLH2Z?Nf8SkwH8xv29`|
z>A!o@F4NED_uoxN*C#`%Vp%f8#tyqY|JJOBFlkIj;4>x{#+WJ{tdp3E=H9OPFs{T=
z39(0N@RSmJEE*YV?x_s1E)>eT!?M&}7+sFVw)+)jc?geRZ@(xTKQn$iv;N$ui)pBR
zf&0F7|4Mavp$4x7c#bz-5)Z4(5p@;=6)}48OUHhX;0)dOMvBV0u*BzM9s5p7Lj&9S
zS9A`SLOoJ*?<rK2XymBDdl@JpH^9z8$4PD&eBbi95#38JH`3J>hFEl9)!66Fji{yO
zh3k@kEzsve)eWn=9e^8bf3C|?>_gVGc%B-3ro__J9B<?k5351C%!OfR8TjsZnvTqx
zbP(B({&4W!2Matpeoy9si^t%(3kQELD<xe$d{u)23ja+s^3_~{419A6Wt{=BGAGyX
z3H2gJbbJXv2Fz-rd6o@pTnZVqzwv$aE8@+%qa995640pTfQD>(C5y%{jICi?Up&Ve
zE=}D`Co|XQbdJ^aU(a4qs5R_z#6PjUZLr4+eEpi)d}iltxT$5cca1AOMu(?|Zq8Cl
zpS=5}=1NdvDh=Qb4KY|^Y7JRCS+B0={+HcS-Qf*vvixOEpR`x-_Jg|Rbf2@3^I!3{
z5Bf`=yj!d0%2FteMleciKv`KRAvtve7O$WhO!>qoXKl!?EGx+n`>ZJp(zJR5(;lv!
zR9$U`XjKF4yT>n3pU3_4Cv8iVbWUjvSCta0r~$lDnHa1FdbJvRtu?3}y68Wj;Ae1o
zwSdJHKEH!?60(nNOUp!)+n;w<?U3FCQ)#%`6zY^(FluT*Z5gQ9GEm0Ywc9E>WWk_*
zXWE|Z^d5e=^P;QW{zs@^R&<Ai`qHNgYHB!J3T03WhE@Y?WuYoDty*#P{fZIB7qDYj
zzjix&Wy8`_nxYzAvQUS-RwLWCkUj-dQNuN*P+HMwtN~4BpjN0^sF0$YGu<4X!j<|t
z_M?a3K3h;?wqw>yq+Yo1W0_28Up3ZnttnKPS}<B_Kx-MOk>V*vo8h;HB$2)&N7wac
zw@>UqYNug$S-gj)wcOw0AsV*SH-6xc4`}F|8yDWq%79^2+T8VOBi&{lq2@YLVr?~m
zH`)_}O`>)haq7LOUQDyQFq*%`TlXNF-Q8q}jkFoLci!tOs9KfxcWx^3kazjde>-l^
zfN+0NhZ}9B8@25<Tu(}@s|N5!cVe)_x@r0_BmC{kqPIGSD=7TV-q}C$KB5~ADWA4?
zy9bvWKe--xBZcav=6X@6?i#^x)PP>HP=W^f{KtBtfngKB8D~B;hP|+Nks)??cc;J0
zPrQzN*C&1`d+8(kJK)W>xncL9?KwBM?n9)V<EY_WDY3p9z#ILD!D`TsPA1l~e}K9h
zu4z5$Ee$SD?z%J{%`2*}-Lp6kHL9_4{J0YMJ7aG*FIzYNnB?5oRl~Vc_`w>$8*ap4
z;it$zRjNEN{ggQheF?u{TzxkW4cy(kV$wgU@K8u*%MB*!Ee|&hH;O_9ss&?&28@!0
za$#C!SAV>1aOr4dd0pcCx7T@yd!5te226z=AFmtjY=2nNs=gX-9EBPo8Xg)jP6i69
zS*ZRGr|xRdD+$fLUjBM&NFJ)bCCod&b{Y&C;~wfB5+#B1&~QE!YO-1|CTM_<43wid
z>cNu>Q%GW&(ysG6vEg^v!8KVNiiU_n51NLpfAUWaI>`L*O8hmB%=l1F<jT%<zYp(p
zzP~c?`$srnLF+D0H*SY*KJ8dqHbQ!b$4>(SX)~sX##CakdEl>Mx1aqrL`Cb=oUB=a
zDOvkgsQqz0>vWwF+UDz!l&jEf?d0Y2gDo(B%Vd4m8mHjZ@9i#){}3rrdy0k&r8H+~
z0B_7B21|3g3{+zHs}51$Za{ahp5^9@w7~ZsVE7S-BXI44@Mnn^q|36I8g2oFTCNt1
zc^a@l7K+WG7CB=U)C<1{yWMJbBc?|lJfi|HvOh$l`HR+r#y;~Uty-+%mQtu`YQgA7
zJZ!6c)uf-TMfDZ)$~5c?{a<Ps9metZK$2uOyH?3$%F=vPC9-xlJdG^lbVto_&C69W
z;dP&)VI{nipZ1o1%_B_1t)XOBY5;GnCI(A(m1Z*bTKBfPPq`9jBeLPOpcBedE6p(C
zUacB8-abYplK!2R|DSYOwpznQP^fSX;0-_GVW9%ls~D&T8!NYU#}7L0b#@D#<oO2f
z=xn*Q`1va|HDurQ7Eh9(^)<js4Y!R#O;roV77f@Y164`GLbWV)d(Oo1S@6pK1&a~}
zzJXC|f)A_SzCwe%W=?7TMhdk>!|kC^l|^Hh2JDfAVg=k>v}s45Ru5r?+)I=58)n05
zv4^wc7rsP;FJvqm*;u+H3D<B3Dby~}*slQxDU@};6m6<|Yf|$pm>*HEx1#1-SRsGo
zvxus%&_wgap3xR**!>zViiT||8Z(H&_RC3`+X|)o9<DdF&MTA<u|C?X&I{D*VCtkz
z^<Kdm?W^YRuW>~(G`!T@2?}*WG@>=&ge;VB-qwyCzL!jxpyomTCffKf?AFw2&0uE2
zwA=8eZBzRvXky(nSK2mvk92N6-=AH60M$NcT;}6@+SUmZt>Mm5VsRS48)t~YYH(V^
z-t#$fs#{FX%a>?k?Z^_|Z(pMu_@}OWdOU;sM!r?f`EXeRH41MnQK&N-!MLaamt~>E
z^;@%(^q!9aMA8jreaIbFgCrSZ-F8H`_`K%{iW$;mdMCdR=tVDN+%YQ^wzqZp)#J8w
z@o-VYU8BSjHGns+5QEhqNqri7ty6Bze)~-)muI15`-TlYkK~{wCw8M|-=D!}kFtlh
zYb*V>Nt}ke%|odLBUuA(%Rt4;Ku!K~d3p2X+bHr}`*9n`=OJUgw7TyLZ$ag_@gG{B
zm2L+lYq)d@bww>0sTz<j3zfvQYV-TxtTGqz)kw<3nlEGDqe;CrSL4A0`1ae@-Tl&~
zck>c8+(QbLDjN4S;Gry((6c({*K}(ev|mD3=K8F^+5OF@8kX3V;|>0a?ROWQs&P4I
z;q5%+8FuXF_STnSWYl8YV8!2(l)JCt%#_#@4d9Ju#E|J(O*=+|uCu$Xa<$JwVe60B
z<aN(QVO1*LxDuBF7l+wej0w`UT3ZeGmX}*JUTeTxStv2P&t>zsLs9_EZsWEyY<7Q;
zAvWkr{c$aprK3LY+*++4o`<>}%(`3UtqBf#Swnldb%aEN*BUO55__)!ypc-`R)Y^R
zm-)w<{T+KTAsOZE_j{;mV?q9FH#*I090x~a@62o!H%S6DSi}88p>jpzvj+Sl3l+}H
zTV;N|^1Rz986`})Q7N{Y1vR<uw$HmwEIhYV9Wv^ghXm@ghWk#T{?h>7Sg*z&wpC9x
zAF$VY%xaJKnOL<&Iy(6^V#cANd1!*cwa|H8B5Zf&-|(r!rT@Ra_Zkk^ke#JxqVWqy
zw2^}nde&S6e=87|YeO7qb{p$VW3yXr!xAeAPQARh(u7hTWVqG6U_l*H|GH6PZ8#hf
z60s?)v-Ih;UmC6iC8n|gyrCfmOH6IU%DvL>*5ajKlTl8cQ=DsC{N;hI{YPG$kDmko
zFePH`>0uJN|HB(f6iQ<w7^Q7MSy`wfOwT@>d+OJwq*(l5T;m_pUs;fLL7Vd%S{u=7
zW7U?0F*~948L6}lSD8Xpv;n+vSdBewtCGYOBk0`!B$d0nD?L>jEHBtC?ix1iO#!<p
z^Cwh8DJbLT))$-bHD;^Un<M*dzX5A+-lvQizel10z5`L4602?_7&VE(602b&<blEV
zX$&Ez-#n9lkR>dhC01XCSl3^7W=z;&Lh2*sz?KLLO1wJTG55_mm_2Yt?*;p%!>*<c
z*N_s^+5q0LB?e2ZzRgo+Ed0C@lsxWK3JNupY||tr4>c`yy#M&zE3kRuuEdd^TO}Gi
z(QwTvl&y_mG_?WEWue4buGxEfYec&tg6=Syl`{7q>|}_gR5$-T>6U=(j;A(`Ib=bV
zYbHO@B^`$|o1a1T=7vbJrl}3rmJ(}i19-!p7_0_0Y}zu{9&Oe2aZT$vqC+Xibr%;Q
zWWQxsqw)p|iu3MVW?gL)1n^Vd9{)uWU9>h_7Yg6e2Jl8FVzBVdWT2w_zMoe9I1A_Y
zn4Y6Zx1bwg+tS~)I)V~*Z##EkqVx&rPBt8*P;JzJH+tA$Lk`N0X;t`>mUaDmm{5sk
zIdcu$EXe7l-KVJqXQ6NYmfSY6<0P$WZNv4ZP(4J$$p-Y6foiU1p>iC{CiQG{1|F@@
zF-m>Hf|ADUG2ZzUkH(cx{<Y^yl%)ThY`FduswsYQiW)99*kD^_XQO6Xb@)fSmIsqA
zq3i{Be{R7~v;XkFKK<a(L-5Bx4Z5qYEtWv3Y&bWHU@sbjY=E0A6uDhzeVLlBX5qVf
zP8~WE#i0{1{V$DuZ9!eeX0$E6WEJev^j_yFWj09Q2ib5VDf}=Sz#GGf!L~GA%}%8q
z8Xa5QZ+$e%DH&R0D1OAet<unb%&$On$Zk^Nk!PDFP!(-BPYN|$G{)KhPYPw7>~9us
zTVB$z33VE?+IiN07G$}9KcRiY{is3n@tf;bHA=#cwc#evu#eS(kwXl&1<hq{D{`T4
zQj+cB(3Z4i1)bkm(9WUdp3nFd4tw><ZIjhj`ZW768_thHxroLj8{j7k#opITv@2D8
z&(W=D`=!KM9ll%867KW#dh2$fS36zbUu?Tu(kgu8GLS+|vf+4Rstxv#R#}TRpzIIF
zu4h8ft|K3gEc<3bADY%(y}Mx~>Sh=)q||8XBMeh*xDXn)2Y&R48ZU{#iq%Z!4xInf
zQzNgvk3!Dtmi_JZ)&gq{xNX-Be-q@r^Wt734oSCqeyX`S6rrhTgxY{PGEntx*n5qI
z_uo}$eD(|suk`GRcajAnw@hRIPN&fW-*$mbF8CtrlXR#JXW(0919)QrG1yksw_zVn
z`SogN-{HCE;S}z~vXrY9__N!Q|2%%ipgt4#pIEeQjsz-C%`K-;3v2{qsSQ{z(=Xm<
z)K!~=U5AfHE!uOjtOY)<+oz-F$0W2mq}iSYm8Cz&u+)ZIO~c}IC2!nPV-MTiyS6w^
z`8DP!%3A61ChLm@a;s~uSkiSFJUrLyXhAjU1|*&-*VC|V)PjLe1nXtO&TrdU5x?sU
zyyXxvEAWH`w&-%S*3-H1=y@5#+Q8vnlH|mb{w5l>qiEoB{U({P^D^FjnZM#J{QO)u
z?Z_Dmj2<><UCZQi=*h?u4o~-LC1LSdd^-(`&tJTOmo(dD!j7IZVoPwXM0kDIBkgIt
z=a_ddsnR`{MD$|Hxt=krS4+a;1<4*7wz_EGYtTJ3EYX*|Mqa$t0~Gx#D(wgY!3^LJ
zynzo00$R`%IDtW+87Wf^1Ma{9G-*@fSnVOBO*K@*%eGSV($V8VZ4>`4{+ka)i~R8N
zVEmy~u|qV3Ut|_P%D?{+NVdZN+j7~UGR~qReAxk<+^6&j3<$x$a{H@D?SK{X1727y
z080Np1T*6Bi3*g$e`J{A?|4!h6yd`-(2l-diTX6u;TJC9>jJQU1r4qliUa%N&X|hd
zCE@Wee9*u&GC?4R7ahbMN=gpc5R0!tNS7p}r@4pB_V)qcY1JCu(YyK`{`+FkKl|35
z@W;)dQSf`&F}QpEFy1uWARpZI?jQurrnU!Z?$|M)7xquYd`N<X;2IM!KY#oe1cE_p
z{Fxl%i_1y!c;ipAaJ&%g(c*u7Kq&rq2CnOaYinto3E0-+Pa=*OV+zLA;<5l7YdmG(
zEyQ=G$CDB*F7d()rhrM<N0K&xV*cjDNAm!7SPb$jJ{*20U+^LC@Ba9VKZ5svd?w}i
z*LY|>VuO!=6k?P9P7f)dg_b`GiTwG09{K5yLIRC{dFOZ7FMkx4#D(NHd5Xh+6+Vze
z!mpxle-@_U4kk58NP?Lzd?uBP@GIkw&qq((F1jatri3&9_`uy4K9ES{_2AFKhr$Q^
zCcMnhSdND#P}?r8FWURZXWyj4qJ6?=+K~N!6sD)1FFNo?Avh>}Akb~`-=RMWxv)yV
zwcu9b59Bqn)^BXU6%~#8<1-msqyPAfs~3&=<8#ppP&D?B&(r+8iah@KOzP`}&y@T4
zKR$p7e}3@(^MjA@fwTg55tu0XtgH7&LmY$;zXi>Qj(=8g`lG`3ZRGV1M%o-&@qY#`
f(U<hg{~5Ua9Pxh!E=~q<a{T}1z{Lc`7x#YwZE!FA

diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skp b/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skp
deleted file mode 100644
index d525f6e3f18177d89e61ed3a8c1a322f9dfb169e..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 44219
zcmeIbcT^Nj@GjiF3A329V$O<~W3OP2pqLXNh$sRID(1zA`Wkr68FNMyGocqu2nJ9Q
zMHCbfR0PZcmD^!fnBaTwIp6okz32Sa<8DoNO+8OlSNHVv1oD69ml_JD0vF%|CW6Ue
z81MoXU?A`W&ZNv8<p0huHV<?FEr2EY--bx7$iD?(YriIA*Y+CFFJO4HykgF_zlk2O
zG;2O6KOcbNz-GA13~x72kAaR}q@t(|=niHO^EO~6`JF`!Ljag*TH{0h%>Zt|iPZX#
zI{G1dl~by-A;dh0mLt*kAi6V5+NG7W2NAt#M9bNPXKn+mN!di=uq)ZulOTGK+P*}~
zk(9WAVjSDdhH&Nk&LF>9URsQndJ<hP#=?a$DbDN4D%DvNi<8Ozvj|&Hf+yH1ucX_9
z=uTo@xe@=UzK4m8qV2w<-kU|jgZSeDG@M5TZkyN5ApTAKW34yQqU>o?&j53XK8tgi
zzwa?Xh_cXH0uLqIw!|`R5g(IP9kps|ZGjtUBPA~>3iU+bqoG<f8`PX1i8|e;yeTq|
zjKGMrr@YR@+L3sv<2DrahLDzVCiWajnya`TV<^QMO1RA-I)7r!v}j(;CVP93yy?km
zIYS>%l-ttUkaB01Rf6>*1tr6XCx3bY$+n&>cC_W^nEWRD_aYdyZG}jX_?t@XNvSW<
zrV(~wSxNKDnOGHKU4rWJzA}(l@gV<ce*ft&q<wmmE!qRTOud7Y74!rl!lY~f*>?`x
zSMZ}`;WDvx0iAFkKx}&!*d}8D)ujEK_H`Qb5`Wr8TBB%_Sg;kmFlCIuu{f>qBo=8a
z@o}Lwi3R<TafGlPLQvfqI?o<&(ktBvH$j7B$KNz4lRtW-r%*jQVsI~L+Ycu7rvB;;
z>ixkSN^}bPo-M<tBbE?D!g(kg8=MLA*(B~Br1yIQGrm8`2s$X6T2SzlM4<3cO}7LO
zN{MUeAYL$pS1iOyJkXosDYoxL?3yxOs38%e$c1afZ6tU_+TE0yLN6e_*HltqRTu|J
ze=ybYJQjK@+h;P#%xPp4pqcANq9-sRkr~dSPczBa<UfhbaH8cxB5CqT$Sz`Q1Z#QP
zV$+B;gZLrXBJC-!Q}nAW?Vrw|Ice=l<eM`vjYZ8_X7enemV-$rU<mnY(i?4hxH-{Y
zv6K8?X*;NQ$zoOML8fHiK0StzUjz9+xCnK;uHp7E@}u##?rUF!eC8K%_9xp#z50yu
zCcpf%%c+4Ck-GKm(cRv6{JTg$T6`t&`_KugMTSw(|AUWLiQR(%%=C?6JNNB5s7H{s
z!(#Ey^l(nwRA{LZwyf9E@m-wnRFC{GZi>3BmP{@tvkbQ<7U(!cqh{(aW{~V#N~y-4
zXwmVM28Mq00+9Jo*2QTDq@9>{9T{Xv)6gT=Wq?Hs$|W$lNPsCZj4-7<z2)Xh4<O*Q
z=lc)>G%mEC(<2xkTQovfC{b9Ac4VG@K5T%dF)LPB!Gx!wsX{8t6s{af;OH<!lhBcL
z33meN445zGN_vIMbORe~xan;5n0i*KJL64vSKv((fGC+4DE$X6i6Q4ype;023))oW
zhqB{}7mJQJiH*rWZ+5))CeG0Dcn%rwC?pRLJ<`!}kWNGCQC*@%HA@U4d(pgbmbVL_
zQ_ph1rn`^N3^%8lJ}x$%9zKq49xmjVm!A(o=|WY59H+TB)4XCXmo6A9X<R%BJ33m>
zETw5iaEsG<i#K6Lk6i`heKAr+tBdv}l|6_%G$zxC%0%v%#zdDYmZ(GaG+B3NjW~l$
zs_Re#oC;7I{$Cg=^7FOCJsTSm!x@eiNm+-s*GWNleA4PnIr|oU+iPs|ZsaGVuh#N%
zeAG?^GA2i~44;hJwcY3UtHyogI``1(iJczeR(GbBu9BRInv6K?w)Rdc<`Kw6>{q`|
z&xa#JcReczbl|^iL-`99isK&*!QP*3D$xE(#%Bt!Eqpx<eLjFRcgQcPV8C?3#T99T
zuo)fwrHPcEe?0gW)g+%d#D7zTUuKjP<zil*i@6)rECiFU<gxwk#a$xl2<bSUzXIfY
zxjE8ea<BkwqDOay{yj4KRUYvWK~hDO*@vJAQZ9nqx6#jQ#I(tm)&PJR`A<J2q009r
z2kc>B0-GArVY}c2i;hIze<mD6my9)zq{K&<GPtqR5ZcA8Nk;c4i9ZLJ61|xC$j2)+
znS?q`Vw1B%5D61D7Uq{A0kj$D=;JcO&C#8ymUJeN^hnId0SZn#O&xM-$v*i7eS#Oz
zZ&=E}b}mH^<Mi-vnn==fQ%lh9f44icLB8_yRphv0Gr(~U8ybG+>k4MLmQ;y=lhNBW
z>77t$0!*r5zP-I7J-R0-%Yu-fUksEdJ;ZaGm#2q|hffceNp2o)KIDX$De)X*BLAX+
zD`Q~5|9@~1(y;<FKAtuXNiHq0>E$@l1psrJjjSqp(c-=7_ft^&&xh7bba{h%Hr(Ia
zu1!2H|FX=3Yl}Cq<fS7g*>!-YCz;@oK1Mc+0Gpo9t}es8i7^^WQcbs+Nx?GhPGpE6
zs{lSOe3BMCW9bQ+tj2#9E@equvvM%1X<$29I5j^+%M2QOfA+g%(qZ~r1ym&p)yaSI
z5iDB(VJCBs3d|q~PG80hw&)!Ex1DN%y3|4yW~c_qlll^?f=%P5?gyz2<M`sMn9X*+
zhY{UX%Ap}Ct7s@3%j!c`*Zg?=G1`qLEks+hP{Ugv2lR@)i9dDiTp_I!k7Z@D2V_1q
z0H6sI>Hx@vMzn-}#89<N?i%}FV=>ZWhZU5XLAQv;NUSZmQGG__IjR%*$#Nreqs*Gi
zrdazdUd`%2xd#STcengy@=Kj5{U^xxhxG}qaXkx_8E&`fy5lU=f4A=NR*;OpY-)SB
z{mVTpF$$bf<WOPHdWK^GtvH9!MwbyC@?aZ<R&52^7gUi>)`n~W(xW>{9BgF@$JriX
z%)GvJBzL3y9O{OcN*6!@#bu_H+aC}@-485ZlhHH82mJ|Ai-}uVokLDlUe~E+sLXbI
z6O&V|x-urI;jOrK__IqgZ2{GDm@CtD82^y#j{WBnqMj>qe9$F<Yrhn<<KF#;cH4G0
z8SB)sRhVtyxj59+=--?c@H(gSysqClxkm!W2(zv{G94~*-KMQVQ6CvcJ&>0P7K+tu
z!!4W);}#6N|HO8x_j^_se6q}58h=A$68FFOZ>e);x)$f6xShS_E~7zYCvmctyL~}d
ze)~Ioa`tz4_HGO+KCsoI4!s}XRs$=7C)F<@I@T2=>p(ybjPhZ{j?5=XZt^NyszX1+
z6&uEoxM9#)N*<gTwwnFc&-@c=_oS+<(G2e|tYLM{C(uw+$^`>2eAVve%&AvVxlU6K
zj%uHcvFnD8mLB);pvA71S;Ye-logZ1s?1f6Gh@JVies30BLa;k0vxO0-Y7B?_)|3!
zfU#r?fbrxQr)Yfs^!Cg_{qnWkiP0ZT4jOb`MHsNY-1&9P!4-C4<X3FR#ne02R4c)>
zLG@x>dwGmJ^IXYXLu$blj8Z704*mtny<3+HluxSPx&ZoXu$~nm<K<3H+oX+g<-`cH
zw7h-zSk(GP-8ST)6U9eOZqfBBz7=_8Mdej9C5<r&Ku;Fnseqg)&_tR>1^N*a6FNhW
zdp~)&Jm0TpwD#Q%MRF1^f7g2KaNr?sbj`MZ;Q4oGyraw3fSX|`_~!RHQ9mb1NK6B8
zmO?B0kdq41%DjrK8O&m|<|q@Jr#jDj>8(1fcNxa_{L@R<-TT4n487CX=xPXj`qwdS
ze9(QCD;5V^aytVrUowq5cSlcPb;f#cxt-f5s2y?toe|e$&yjMcaE1Q;;)|(wqOnUJ
zRK5Q$2dC~Y(&TIGWr^!bK{ligb7nY!U7B$YB_l5(1C7OEg)l7w%L=L%0<f5cX(?DC
z3DhDXi46ln?lAL)-EX)X=#V@ds{jQQyVhTGbW2E?AUtXSYJ4JO2Xbf^JLySw4xXIb
z;NR0xQr8v&xQ5YP2>=&XQ-OYzyaryLJ)>w!85h)G(<XiWpc|&hoB!GyN$d3U9`oVh
zLfvQ~@&&_CO6|pM%YHkDmpZ04>>rYYb}TIRIJreA>M?m`$wwEYa~4Go4lZr3GMwXD
zh66@~#GnlX7;aLC{8sQUsRFzzfC}`p1#Fi%_^)aB2!6Gec4A;K8_Q-rpiS9pGB>)b
zJxg?Nd<kdW(8QOzoP&CIK0fYB&N<}UuBCdD_8%-h0Epe#0Co}ca1SFJU=nr$u!k}O
zdnE(+-u+Ft9PV=ix3~d!+vR4XrXh8leLh@AAKtvLSE;u&Vmkpms1Sue-g)h4Z)CxH
zwvHV~^xb!`U@Gmj3mm0H4>DRuz;Ow&VOe;>^0p^Y@4T|JG#_%%zG)i`iCb5qXWA{b
zYQESkiNSUNPbv@-hAa@hh0!oRIKyVv`p&Ck&{m4Bw9{$crY9M(U=Si{O2H;hM|>oh
z(UNr`aHW*#hyqTJy~;<M9{YHmqlf$$(Z!S!gZ)eKBg*fdyfZ$VE}udC(azi3kZBv6
zwBg#Sdvfi|;38o!PK<K`-pdnln;3K8Rgbf~s+Y6t#ZFws76i|Gt*CIGHgaI81U5DS
zFyk_!r@4ySjjmN^Xci5Gxu^TBKXIx%<}IHOz2>txLwH5`k+(01lG*N~P$sZ*svXVZ
z<50E*V`p&tsl?7mE=5Qg_cgW1mZoJGXUl7V&*{oFlt-vPS#gjKkDIGDej8FW3wOQK
zyGHn&TWI)zgEd->dxDA_*y^)s@OsI}e-nV)3Q5}^#1O-fSH)5t`iWBvuOZAOnTHqO
z=k87%dkI++eQ{&-AWI+8GCf%ek(LbtdQv7H^P5iz-8IiD2OlU|{Tg<SMU}toYP_t;
zDb(zKnW2aBPDz{+;|^vR@DX!!AP@wx&LE}(9uZ&wlE705^<HEhQc6>3>pHm=SX-Mv
zHskG7$?-Chx2vH2HSjYFRceR@4^{Cue=;$AksqrwoLI&C#JptM;^IJb+A?@-we_da
zhUH<K250TSNf*b#@$Yhws@>h?o-kZ8B#E6&6LQPoeIu7488`TIq-_Zl38X7zLMC`Y
zW5TPRQ-OXmz#9p%F5cIV=9N8#j_lI>GwAvbT>V*w?l~a_`b3TW@H0$8>^Xq%6u@|t
zg3q*H&iGketIneon;VKK4aJ?(z<XXriRFTilC~2fzvk*F)=m~5>T{cYFa3%9QoG%(
z&fvX+$0Nng6#0VVdjCh$cGc~11<$)-ek0B&8&}@q@0?pb9vR+c8?8efB@T)sFL3BG
zZYm#>OCIF&ht}mUnC2GY=S%Q5sk5A)9c)@i$5i<3uVFI$ih0C#0lWILBc0*$hf64r
z#zJYQeDIS7=o|e4KfrIY_M=ELs1{ESeZ^&*$cQ(8rk)P?9CILWU~fL}*7v(eNQ&)f
zpy2L@!_~M;_TSgi^a8Mg{4k+|YBH6eNnQ|Y^(0to-q45WPKSppJ%7AI0~faF_;llT
z^t9-wa_#mXl7w0XK~YH08MG$Bj0zM`OiTy!70PH-#CigK`^$Y9eG9X@8!3H57neVQ
zIJN2;3q<O&o2(9OJt&`pgXO-l({;%xVClmL2M+DPOQzY(_lwLzO{e!nmgbQXH^dx1
zgG>Sm%Q45qRWHEjf~q%Ehirlhu#%)b%LwgY@HlPB9Lc>{l?_qA%v#<KRiU}i4h1V#
zYmb#J-DUn0+;vsh1asS1^mJE7+RpM>Sl8+0knU;WhyqtO5SlDUOG8kD(XC<<s!@TG
z6FYF!bc~D3Tf-)z08Zs|BD=?QjwIHuV@jtZW&GJFW%#^vDQypZug!F(E>4}q8cTBD
z6upaD_Mbj%&V_8e<ZVsIg{mlQK6cjd%G13hl*LF#K|R72HegQFhJXuosX(1*B#Cc5
z6S2y>`p{kg3>%v-roZ6FLZggW)5<}c=G!D8+s2*0%+q9H=PR|!1lYx4kXSkLbM~13
zBqk)J@ogl-0qcgc02tRzF`{OaatnntsRvsXR5gX51#`j@w*H$Nk2X|b@zvY)U&7qE
zc!I`P9HVxS0*YfkB{gWriYfO{%G}fI{kmo2#Lusm8E;*|`p<oamrt^lxYiWHj*M<w
z2)NLm3N&s~D8X;@wHa&?!q8@-A0uY5Ngm&xFRFz1^@~Ae2iTpxS0@J#J!{!_Mdi!b
z_E(+y<7YZbNQjY|!EQ8EdPb`~6ojr2=ou|*NyOTj8vfh+EZUI(_<eyjyy3_*c}8Y5
zv>o;A_Dz)He*gRJmN|Ipjy6@Y;3XWnFVi}{o0M2r2>UP^Jt5$Nm})oJi&E{whz*bs
zs{`ASa&hB)*DuzVEq4!1ov|TcZpUmqu9D{chuPP#;bl;A%gyeRxU_|EFoUma5(Yvr
zn1P9T{OOezE>(CRKJc6;rN?J^AGTK@b~0-Ed>cz6s$uct)$9v7c(l1@*5We<uw}H}
z2j7X~CBz0oID!!y3IP|$jTs{ph}p9MiDO_heyNlF&KNW-#HWj8!yIh(ZI!0uz>C;$
za#y+ZIBA0Rgm4^#8fFs4Krl`Lil^tu@2~!0!>dE_EVf1llGdAM7KV0B`Ouqs`V+5v
zHHP*vaV#ea`D6^L;=wE#ZIk(G+t=yxa}kp^h}fLYXA=w3x$Vc+a&6Ah&}mW&W?A3i
z6JJrNGsMIZL=Tz6?0{u=dEKHXa*je*T-9hE)3vDekuw~c9*QQC*oZw6P)|)Q%H~!2
z;U)Oxm1oEQtcER3AIIv9(H49W0vhGZKLYB9@;A6HH0QdJ)h;8Czo3G4gVpTZ&`|3G
z_vga4ziS(gTNY=w9a`k`DDFG=hhz3*ejXP%uH3(D;5k%Ze&7^1ejYuZ*-8CcmFWTy
zeF@E!ahz!yJC^$B7|YZNYHr){pxm~HNqd7+0&l-&jd>(rtp97Y#%=4#^RaO)&gAmm
zKl7HXy1Y(rva@ZQ+|D8sYS!5+thJ421)sj9{)hHF#I+69yhRO}kL21yw0=HJX3^3Q
zI>%?iz0Ul}$9_Lkc#Cx6d2PrIm*?Yh6Gza@z_bHnp78clHIerMf4EH65(1Mmx&>^1
z<J|q6$>f@0NUl8}E|OVT2<I!533j{Q;4S80YK0G5<<VGX@?xW|1j`1nJD#(+(pc_u
z09-D^6VP5XEzS2&{=oa?!nUDEu03DCGxXVXp5+Kgsl<C!8M1yN?ZulFd^Um`vIDii
z!OEc~<6to{ek1EG+clv`uKnJ07Mjp+7UK|TcbVyfO}*qTcZHqYiAR?xg))JI{`7vH
z4RxDvo5?Op9Ja&2zeUn8Jeygtn0$+Sv1(l?`m1(_?~@{_ub|v}-fq+L|Ew0rUAPs_
z;&A2yJ2Dz}m6R{D_GsU{MB>d8s8w`x+kf8Y;JZ!Vb~j(K0o%J)uDf#5Jjqc|90z-N
zh<E{yu!EJj>L9c)s5$__5wZoqF?a%skBsqyW_zqz9f00lx%v3buN*w4WN3*V8gjOF
z^i<!qj<Y532OvD904Bu#(Utlv7KX^5Y&LI<cz6RHq%@RvIs`*_6(x2Co|8;v1e*?h
zFI{0Vys?nQ*VrvOhS?OmaiWK9@N@qV^zee;i(1cfa8}Gd^Yb+hVsNujrJ!{Ni5ucj
z2}qe+{26;=upLK=N)*^%QgHbK45RFM)p-amvG|6<2#FgPn3t4n!CBSV9i^>ek{;j%
zF?Cm$zq|#z_C98{wp%vJZPg^kV|xgurV7rg#AHpK2e|*N#5#|D^9H_T(e)x7FkloT
zyBi9Ec<*a4ir6Mq<QrUt(Gs$OrqQTPS`_O8p!Z2`d_kssbm#%@6Dwi>9?Mk2v!jfh
zZA`_zto54Lxs2!vnm7>M0tWwn-TeXDF=5HU9fxkCR!>J)S>^c-cLC+1eifB2>cv8E
zSD__tLrMeks#{ctY=V0d*Djb`vy9%%5(>P!#hdy2#TY_S$qiumFq`Yf6=#E_@#3)<
zbb;7c)ZWlf$6LhKgI~XH+aL_dFTsuik7X8|6)wvPX}L99&CdCZXNvJPo(fmOO-n{m
zF<<zhtBe(2jXC&1-b~L-o=;xdlOBM8ei-J{g0V4lcoO@P3ZD{o;?C8$=I`i34bsr;
zj~!E=s9)e4YsRhe?D_(KZIQd=>W=_P=SqekjWtt>Nq9~L+9+Zu?x02fzy&O9UZ39w
zvRo-ODHPGgXR&q+xI)Ur`D0sD-?L@sY~*vmA^ZB6b$H8?U)NGTKR`piwZD3IxO6S_
zCWLPl@+S~}q1=?JzJM6Y`z<4%4Ra+qH5YCqHDa2+aF(oW7Mw0Cn+|;y$~<Ldv*27=
znUER7HEUSwr@p$rkp*u0uTZrAFWQDO^S<ydnf{K28Pw|)ioX3t8+^AI#k7G#%ktDV
z(A%0O#fBd%NAkL11Nq=^cBDM(ewnh)+W!*QHjk>nETy%RYjckb*%23+uKv?tX4$YE
zT}JtT;b?fA+<;p)+$_#44><IPV@qFNXY8owmQE?$5c3PFRnqqR$;!m}@BZ}6$m?&8
z;oj?({p0v52UQz*t7Yf5LFmY{y*I}^UG<;iwa`}J$Gv%!qke@y9~&H6+M9YYsC{Y+
ztusc)^4sG^yKE-gu!u^2LygJYqvXlV<sl`xIlaSpRGc`YxKn9W2~q`$&@WI-RZ3Mx
zB~DtC)$$wpnMl1XZnZ)6?TGFw4oBX@*JT=9IFAC#Jxg}Jl7p~aLSX;)=WtBAWB-d4
zS4+ZCMg=P<I8s_wj?&>(WmQC=<SI*ul~Xk&rDFKsX*>H2&$@)B!r*1MujQa$osWJS
z_v;jHKRvYGKimKNx^xL<4_0S{%BlpRstQzR@HJIpDChIqiVgj5peLjJ_JoznK~HM-
zYB&Df73}o7O}$$Er43(I1?wnyT23W|*9aH0gQ31tEw&nN`0R3&Hlor_4M79Kh}ff1
zsjq4zA+~Fa_0->Ej^m`2<I<Bp<{-Gb>WU?umZ4m&RYaAGQeu@=u!#aOQ>#-5@-YUS
z=INJO!wr?D=t?`a;O*9g5o@lplr$K(X?SvH0PC8D*5&!xYEr?ilFM2TWOWX&_<1jQ
zyy>q4LRD==J|L|7$<OUZe<HU#5^SaXH8hXlL!3VPEk6e`pZVvUGG*&WK3Hhd`8<7v
zoBaH$gUU%Z*tAw{mX!&SEAyxc8-NXoU%1Um#Y0hh8N01OK4thb9m&0JPFKswJ?e9~
zja|9&=?GG7B^qL%ktwY#zpm#NhVSBQ=))h#Em$j9uvVS^yH$r^FK)F}9Jkv1wcKhi
zm9@;<1ehp`S0Y3*J)}w?dgA`}Df{#8HT$08S9_nF+vxcc-T!tIzB`tNd@Fp|5$u0Z
zGO~!{A+*WlpSEn0V-e@DfyFg)EjA6beYX6=myw6{=b7I35hgltfI{bR2ZIUazf{?h
zDlmY4fkCPvDtk#MXr?fSn(?FW%=7_|Q0<9ZH~OA@i#vRHeIyDd;3F3f?%ccOA4FpD
z*ExSHW)F^FG%d-hCliLLh(IZflEDkH&_pHkHGz{A*_}*4(^-D+-Z+(f!Z%~+xevW=
zT}9THs~ft6zQakrQQ1$e6Y%CAMatRg_esbOQ$YvDXsilwVLTNmHE|RDxyfAbynY95
z97A^OO4dj{u5Bg1Vr>^wf*UR^-^R4J-Q&$x)}J0P#i=uPSj2+Z*^khbG3|iMm@IV4
zSngnrs5pFL=Gd)gzpRy{j<X85G0Kxnf*9KZxDx)*jX5z*5?>*@;O%ceM(ermANmWv
z?RG?TH?b)fl_x0^lRXjA`uDM%N9g2@HhvjZv(T-C+VhTu#p9~UWnSneOUZhuzzl&b
z<boG1p^#!IftbOjJ&P{r;m*zqz|l6xOkDtcu;wxJ+QP5xIt`|}VmrPndhiibZaH<q
z#7g)!zW;0M^G%Dhaq||N5BJ(0jRHqEa5u!SkfemzUIW!^%61-eVwOq}=1_q;u|N`E
zUv`KQ!*}|9XXeBmMyx$r8f@8+gQKp^vCc}rh<3N@b#Y<;)e`tQD!7<|8B~A^^{GI?
z#LWI2oAv3|2WcZ3Cumt$F^nC0glvmR{JJ_LX2O}<*w;|BRl`%+xKXi_{hhL|qO;%o
zMI}F3B_Sb3YM@#{@Zm~EtG-GQmaD)@Mr*Ys27ibFv$?cu5aJDZ!)cB3uCk697n8kR
zIrZ0RyGY#fWL$$&hjMWFsxis>D<_fjKZn~j+_^?VcDV}v%c!kY0WPek0s}VCZ_|S!
zzN!|aR1DR&nDx3aKa4H6?5b~W$iZiwJCs~k-H5!_P3^a2{z?gyK?S!msLd+C1xqSW
z3~|VWbgn*m1HU@4`z$}*s9r1->1En_(=}x>%JVhr1vj|<gY9&FK`9q3!Aw8Bw*K;5
za?5C6*QD2Deb9<|$D1!7eF}w@X|aA{%4rE@F|R$UU6k!!=EP2wAnc|BDF*x5T&)1A
z`?W!{o)ajuaZYuwzVJbHjGo2U=LI3F(Tg>6UP_^MtKeZ~xEl}zDLBmrQbnPTOQwZZ
zr7iuu_J*U%wZ`WbGiIX$4~zBKQ!x%38hnd1=w{>pI>^j64YwBaTn|tTLuvv)8>sp{
zm~NkBw8U&0sDcR*$g38phz_N7N_9q(&O%e_!`sqc1q@Aw@af#Cxxq+2!(V@@(`{#W
zBf3;+efIl9*{J6ZpOd|($Kl|{hLss}{@aanZ0v#;7}>Kbz=cLspwuo&h`B19U<CGj
zl7PQHLdPAhtZ3dc3w5zudtqXWczktEy|I-trK5A03PdolMgVeQ8ZDt<;#ds^Rb>;S
zs?biRSB8~|)Ahi*72{4OzC~S@F3jrIGY$n!o>B9q?g_5*@MTKTh<%cVjRxR4qm%+5
z7sO0bfsxX?&Pc{cA|f<ZE~v=Xu0aD&b`UXM4~s(dre1N^-+#u@e~pz9f9baS)Gm)~
zw6Mk8q^y$nP>~zQ-=Ew1-!rybDt7Pf9Y!@)1-Nh=5P{N*lMp)yDZJPd6WM2#*(GS>
zwL@&OYKSR+O<|E3@85W-Q;Em;UZs<}Z@znr{3FPXX2<WL=&F@!-7dL862<!}kjSWs
zArn;W)@EMyfa*}PNfNRND!RBW-m|W0glaUp_i5S<z~HX@t^wP_^xQ<O{Y+JhXo#cT
zZ*<KORoAB=r#a(xc5{7$;{BGLbvY1^!z-Sv*6!iI5(l2Dz;m7kCZRqcB@|c;^$pVd
ziNs|*vW9M7_+u#+6^$Di<*=?{NUpuW<l2|~d^Y%|4s68r<K8P=^dc`hk`Bn=`&^yH
zk0*F*WYD*#sXNdK``%{WSF`Y!A*gu9JB-9bSEdSNDYVTp@S3;>dDR=LL!Hf$w9PL_
z;l=J6z%N;Q82}{vi}j#NuJ;SlmlKHfG^WwCVnQ%K8ufU@k4AQ_<Y&8I6|AmOK-Z}D
z$dIN$cNue`TO4tC!LSXZ&+~K37VX23t4!Nf!Gb&drGO+a6Ofjk;!n33M*iYw-m&DW
zn@~4CgFm-svAYOAp6p7HM?kF>w6mvkZT-4D#u===t)$&n#;z*7E%WR)yQNLsGFGZ3
zGQHKXgUp^EY%MEmukx4eYbCU_p~LA4Y=yyCT*t4dj$!u(iP1}${ES#Xk>`c!j)vmo
zIU#8lnXCW0)}gPH$I$eayLg;7j|&qbo;v;BN?x~0SnJR)ldpA@SId3wpejcmYZfzZ
ztCGjT56a^&w4dqe!ob9`!t7z-WhB>budveM1m)3nGA$#o>;0Sibnp?+Fuj}nT5&10
zR>q(6(mQ;b!uAL70PhO}CxxN%GHoa5B5UDNYByP#n~7K1PCWDVrdWrLlgGNgx|9s*
zmrBX1oKbnTyw^=sh`(AbzY9mj%EZTzV{SjrsefKT^SVyYRNc$L(f-@+y>5OK>$~rp
zW}PHGiLq3{7HYZ--CPB@P?-vJSQV#9Y1KN?UBplU$<1oIcQxW7jWg#Nw&h@(7cJjU
z`+flp9vokEw~O?oZLJEnVNhhbk_%R9&_)5OxB^tBb*U@eTAfG7%d|VD4bH(=#_S2a
z^F9=}c|J354_PB84OnP-#Yzo3F{n~1z=aNKBFMd3XBx%>%Qid2j(@33_=2We>S3}i
z_V>uo*3AxH3C9@=@BZ3i%)vk1Z%jXEe+Xso?Y8ImT<Iy7IDRWsh~UHSjMjRUAaqlM
z?u?d=TCBcKC0}W9WhTUWa}_Q<c`KB;Llwah@2gVRmzC95%a1no)l+2sLl_MrPJd>-
z&Zug@kA5r3Gc1>7$rBC+%a8`E>HW`QMwuX7Rwf{2AGYV0Li?{_NQQ3*LXq5RKK%JN
zu7i%WWfsiKehs8eZGcIa(GQvS4=BIHmZ4J8%arYV(KJo^(V-E;0!BSxX;tK=eDuEz
z#>%3?y-oIhzKM@!geUzNYIF!i^4OdM6aHeskkm-eE$Fphx={<wb)o2Q+92r@Z%6Vr
zg_~3x1e0g?<?MDsxzAU?P7(*&Q3_6pYoBmU&WX=POFnNq`ZysDjXXMY?6x;2a7dfT
z1dsaXB=cBt4s3@;N?<bUDB`LSYFY)AtF{vsWH0gsrl{T39+D3AFQE5xi0y^JIs)~A
zClef#?mk}r(TM7IecON4&K!Jkf5y_AF=w&mD<{8yqZUa98nL~90ksEbFzTLazy&WV
zP+C3`N<wDqV?WY+ih<GR7GEsgx$*|0EBE5TCu-}1V<&D$pz1rjy#4H&gU>8B_J3LZ
z3O3%Yqnq!)`9F#Is{bYS;9N#*wi<9D1Q3CggZUC-TD5$z&?*cTwbk;2sS8w^fYz3!
z=`WSMtgpf?0Jpt7M{5tf#8)f#^PQV{8^vBM@7k_U1{!PEVZ^qrdnKv#8p0LK$(ukB
zmZ`xC=A^i(GGT^n_P3Lji8FZ)ym!!c@d=dhtH#gtX>rK*d%Z71Q?t>d+O5XyG)nJ4
zSgnR@8N7>0_(u)aGI+7sv|47(r{BmzjzeZIs919r%KiPIX`{R+IJv~la!YfiZwj#l
za04^j82~PHr2=g_u~+B8HCd8Jf%7uG8=#A<>@%>JHIluW-Z~-1$YgqAcPczRx_6;E
z89A-IHOgks4jk2aU7OBPSt!c>jiZ_DIhdVlu$#HFT@ATV0g@7eB!RLv4X26qJMiJO
z^9w%s8)M{Wo%_|Rhy^h*pUE4;g5EzsPj7w<9W-+bntkwm)}c<>cw@t*cLz+6uFZ)Z
zwFcB4JjAH(Qv)s>paP|OMAB(|z-Uq`HX-!zmd$-R{lG(fZrb5fgz4<*NztXOPCsET
zzb5}^qWl_8kec37L|rQwr~)(rb*D|v!0Qj|%IrCsf-a<tY-lihhQPvE>uhTekaP?&
zuanFkJk4A?p$1$yMFr|wh{UxZwfrupAhiq86jNH*FMaN{qEGPT#$7rdv3!eqUdwpf
zx77pm;o{;uUx!I=95}Crml%NyYQTkw<bFGaH0TC{NU0dgVxj*1yM0M`dXKZaoF~6T
zk7}K&<rV%C{d0d_qTSP@67Nr_A!bnGFm!__iD98CTn#V-kCJ$AtCGVHxR~Wo9w*_i
zev?-m8TAs))NHbT67>?jj9cNdEM5v9u7=kY;B8gxp%h+qRSm8)_?t3#d7u}asR5?c
zFycPt8my|hEF1kyu(;RPHy$<nCwRjCOVUB{f*Rgt@K;SjtQy>AVB(;<doKY+kG;fE
z??>21ZB0d$e(%lm&3=wLR6kpK_V@rvP-E5b9y4pN5(M&w(0k0RILtyXFxdQJi+K9P
zuY7U%ks->|3mjTkpz|XDzII{nJJGirX(ZcXdSz?BcsX)d8d_bsa+fC+Q*nEz8VTd0
z({P>eL>K?V+Ysp@h0XyKIdo{vpD;5mcj-T^Frr6<GfYxwphWf4f~tpVki?uzR;Ngs
zDA9D%?~vM?-w+(Mja@P{l%7iu?P4k~)D%$cTI|w0F%{gB(cp5$j%^Hkjh_u@<7L+O
zG0xoR*4ZvIK;qg%HB4u8pQ`~E(x^b=Cx-HX@_QQsp!~UtE-HB$Z#Dg;Vi(vvGSyeh
z&i6q+d1I9PsRv*9j^K;Y|2zpX;a77u#+jaxF$7kWpF`)W=gN*<9#D?-PA%v9PA&J-
z1Ln#Yby3O7+@Sotx|CYJqA?MclG$^DO6T)(do6*B?BsdF=*2Ir`#nZ8^*`#X%4eY>
zA5OIE<4Ud(FRB%>^@H>(gtH3%R>;tnz=AZoQ1w#{ezPQi8gWCovirlt85iVPF(jo)
zAa166K48h`9OQDj;=ijqA3$ez2S&CpDjln9lGoK~=rTc=3UWcMAteM`(&nzF6Kb%&
z3_DcoqwnzJTJYB~vaV1}L+?Hlll`i&28zH}A$|qt7|!6W&qkYU{G-D7#qO8ZqP!aG
zYj|9HfHNcG$1bQ8D(NyMG@vwd;J8W<O41U!1MR_nSu<NHl<iW<r&Z?_UhdTg?2@_o
zLQNms6t~ASv?4F5TpEi0xgcnAo0r&c+{OVn!cuT*ml@&JRMKm#;*dRJ_Fz@!V47MG
zDr-Ph?w}+cUa09)uwwWM|JrXU6`qW0B@FG|uHjqkGUv?dVsGNH%HyhTxa~kmG%IUh
zZ3b3L1Gvx{5<wnKVd$Sct`)oW9?Tld?u^rKopKeuAaNFx*qpx8Ixj8>S<fAREw5-M
zcA8wi$QQd*+$C-4?8N2L+ftsZVIxLD9E=8<L}FN|s;>c!7_Fv~7#sz1_^yXtFE2QK
z3x$qt`ej1vY`iLM_sr2%?_zr!rxJS_ZIQ&Fz6Q2bfIkWv5I~`-xdyak@KzeJr#~)q
zo!2-!34QS0+J5W6H@I8KgIo32Kf+y(SJDQw-XMXhrGaf3RCANi2!gf>;l2%1Wj%5~
zq-VzB7>!WVH4aLtpg&!zwEweZ^>?UTLon`Yvv|~W{>2)*`#eD3thSCkTs{Jm9SR*?
zJ83{yM#)1BxzL%G5FH7WkO9eKUa^bJ24}d09q79!oJG%MJ>!{a_%J>ja)#+;kLCAk
z%s4=A?Gi^Zr*6cQPD?}a{QTM$d&oU2^{cFOno#5(T7P0$QiWafC6vV>u-5dT?bM4o
z(Om<$U_%A!L?21M<N>NKhA&rs(7iLM$MDC1%Ym!!X5&G-dzQWODGt4K3VTrX^I{3S
zjRp=>$d^1oqaalE*MNZx-d2(?Eo(c~@h%aBb6ys?^z~&nhA%TaMx!_s_oMdLGO>#!
zP-0JeXy^+N;7|tMUn2-V$jkZ|)G!8BkOz0Y-7LHMW?*e@<nCEFV^FO!?W$Ovd5L#t
zPruU)L?Ce<Tv5SM%y1Pb2v=2L6f-OimSd#_DX$_f;>_{ZO`bo@!HMVg?LNPFJ9-$j
zJN{aSO%k&q0FGy7gURdmn6RA+v}MH3ZDq?kVyMiV)uH>MF*<i()85n-WC`bNmr1%W
z;n)!Md{Ftj>m*Q~YUnH=2!fLaI4gM2&wpLo;~(d7vu0}RwPf{oMA_mMZu~fhEE@LD
zS=L~I#H^DBx-qj|$sK4+h=4?pdl1GR<Pv*OdDn&pmQ})$PqSZs6E5c9yi%<;MK(N*
zXRP-=Q*pa=5o#!eo(#cDEeO*zz*E74qDwkA+EV!}`iNo6j^rV#F}`h=x?S3b!&=|$
zP{n?}#Di%X=)=s0LcoO+RG=P+*_uzBTid#;5ry5|IsLp}4i0PI^iA#i5!n5Gt@AzW
zO5aB$Za-f&yGLLS1DdY}TsQ)VK!N5-`his`-`DjP-bT9pcQZz<%f{2<TRHe--oPX0
z<c`|qCB3*&8^T4*@DU&gK5DQ?!Gi@>9aN#a&ZF4w8)kb3=b)w?k5_v-FBIQ(>*Ks9
zY9$uuJh^7Fl$qUZ63A_6OBKw{zyJE<f)y9ghZMcn(epVdXxQL&&0;R%m2W5ZU*avj
zi<{mw#>|o%sJKAxpj)Y6cJ$m4TfD19p&Pp%Tbvu2gR&o7Dfggn6s~qfbN*wxzl1Hh
zS8gpcJIf?2paPAqxG4+@SM4Jk@3i#%@&qsNZ|grRaR(ar%Kzi&YgyQ1qSa!9?5h16
z72L?6mIA<qe>FsqLoHzQIWhcK)qJ8T&aA%YFKVih!{YM#V;(mn_fgvUTE=YcaSyes
zyEpjD^W_pxlT}~`gFgcW;eiV7P=HT_^r1yDd<eU(Sqz_N^Q6}Nl8<p~{n|@$_unG0
zq_ayO>-)&keQy^tgS7qjXuv)J9&#a&mQe4-W^J6@FZ`PL7;l*y(lGh%Th!yqwlg5(
z9<sd@r=R^s?iD=D%!>IQf(i7v!K=<eaF_udlN`1VLi$oc@t%+21X<YxKvzP<dJ_O$
zo)DKkgY@qWiOYOID$x_WIBi<6+2YUh@VWZm-yZIjgR11dc-pIUEcTt-u=cdh3ne2>
z3WOodMe-*=xNw>Z1W5)(Z`u~a4^}C_r_~uyGvFLf(QVpL<!TP{u()M6v-WxHFuq$U
z;MYU~e?bE-Gx&=p;j{)`R)8O@qU!--Pn(&YsDEk1MO=JphsO3{IjGn($6@J3&*K<P
z^>pZMFM$$MC(q*1sj5)`7la56Ff#Bc$>3+#yXAPd+&j2I?$-&H`Ps<PXTb2J@h6eK
zQ|u6rwIe0H;erNUXNJjNtm48D6%ph?6=rCGhw9Oja-e@)cPaff?7I_%<QdQl#u6J6
zKNMb`7Q@~QERI#D@zd;Q;j=jSRR8d?FLQ9mvG=V?ELnvjHnp>EJaLUAR^8Mvjycdv
z4Y<&o3UUWrRV_)O7^-dk6N~$;55k#6eXH1$r>?EkhBjk<d*YzY>o#W8l|qT#L27Cb
zK4jp%)q?Oq10FK)N0MeqU$kv`QNt$Oe$49Lv%lrwoQDr1+tk~SJyLG;wTqVC`Tsxz
zlbPX3Dna<ECW73n;tE%Q$Elvly4voTB}EhGlbe+L&I)cF{0_H`$eh}FLjvA8sKRak
zL(-F`WC+t3{CJfhJlB9U1^98Q(S(yYFr$GSeoUtKqODD$QNS_V*hb#(@Y_`fr!9Dw
zfOn61IwF0~UP+ri*T6RnK0^bzkVyr(_ub$)($mFl`s`L>VkL5Yxk;A+e*LYp@rOLK
z_v269$1PrNy!**(zXWQm3g$8>YY4cIts#OOY66f$4LEzg!~E$-(YtB^$3||<#>QxE
zR-4WD@UixGkM|WjD1pk>z%LBylu7uc0bdxD*n>BI_b<n|1)-Y}H@(a*XX9<L7vn3=
zj>kH)#Yd9YOFhWYz&vL5lSvp4K%RmJFM!g;tQWHO`wZl-IoQwc4HVP-ap=m(l+Nk6
zOLIT3>OIr(?WIc>_xzrKysF!V9}AGq)x|j?j3$OIiKpl&ViEI<FB|r-x@cPLHNV#`
zh>b92I{y4ZV?>t+p+-wrn8fDHw1Pp0w?mH8ogC)2*~E5k$e#sM+Nrp<h?b~o=oipw
zi)l-0#a0EIW<xIUd$de<bal!+Zz4HQU7M|08q53e^{c06<(HiDL1}^^ww<R?_Dm($
z6F4j`+KO>-m|u(q!>}~l^pGpC@9~7+M{4WE?}>`&FXvEEYeqPT8}RFAn~;_vDcE9T
zv#}mE-=JBMsjgp&+(#h(>cgw4eI@A|qXAV|=m$VSxJ657@Wih5Vsj30S%Qil55(}9
zXC|2+`<#MbgiSAbi@;m@4l6Tb^F3s6_loS`>Lh`$p#>HUzNSgIrGXX-@VkH<YQnHP
z=KW4T##TXh%1xM>g|tB%J=BM9p~dE_<~DmUNCH()3mOPekPAsFQljK3ees6atDCJB
z40)!0jBWil?{9N13w_#jYTMp1F-Y%Y`7`m2vjnP!7B*v0O|*au$23HcLp@dBlFeyu
zspuM(7=GZQ$M0M&V?3^R!{>7sW~0U_jk<m~8;^$ecbhU{jPy?I6g6ng;4QU+(25Fj
z_@h7$H74`;(t#^5Ze-SOcab^Ss7)=n>SIbg^4Y#^{f8}5s5lkq$e`M51)-G|c4Sau
z59U|~C+}?=j=vnK<+{N?8)dqOO*%t7xV|~{mF9=kY*P*BCYXg>u%ac@18TNl!Qx`_
z``oC=EWE9&qeFN#U)*v_9Cj$1i~=Y2KAiSldSgTd@~7pP*@`Bi5*6fT*Otgh>Pv1=
zZo1}M<B;vM@vUyJJc|`cM*2gJKE2CGR|6|)U>|070C{yA6LzYIU@}{9*%tby-;QZ{
z7H^4P_Ps-T4&G^BI%VeX0JJys;pfPb(uqkgH5|ySbubC3WQmBG6?enpD)|+LsFuYl
z?>W8|Zx4^E*7ipZUIIT%ueEL$wu+ixWc*6$#AK2R3}sNMWQm9gc3M&*_h4YDpVpnu
z``}$i-yU7|H3z?KRCD$2dWW&shE>^@`by2(Y2ip_P0ZI*#hzy8RbDEhLxIL<#ZCL;
zZWs0R%`efaq_#Vc*SU+@c1|oaw^If-jyp3sy0jGP8CfD?P`5RZ3n{dO8Ww{$Fs(8=
z#KqCO{D84(U%oCK@rABZiqm$=$B5-kVs7EX7u!tO=#-5EYsJ@mlNXC_oO9Z|ZOKwe
zzZWCTR!t=M(1p<==iOXz(gGJo%T;n*`a=wC9mI}y#&7)3ROnxvkQ3Yd#yhEGSQ2h~
zds5XGA#bp2Pu;apkcdFXL5AOb|NEUd6SY$*v1yE$lU5L>Xu&i_%u_;ag^H?+<8t+6
z-A^I??&335A~F}<%EsgUPyE{6A_D2nja902kS_a7(Lx^vwps<aFhffOdE-pgTFVY7
zo#u32HNY|n`>#K0mfa-_`&TF%ef8{ZRL_vHvFbS~l(-3m<LpS=X*7bsXi<khLK3Dr
zhbR)9%V>#rnyOtu!^5k5wO}qII$yg;5|^o_>50L%HT$zl#(x1bZ)~=J!ilYJhVt9J
ztyGI-XW3m;0kX1Xu#4<4u}tB%_6{n!UTc;7;_N&1IvK_~g<IkmDwJ(hxU`z9ZZG54
zUL}8jN_&<3rDcm1ntbrp+7p^CyN7$dwrjqAcsA~QFzIfES4NbdmoUN@AiW~)tA!g_
zGx})(7Xqjt&#uK<y4)^K<P(km2?>jg!P)!W9_d=;VE45fZRV5Li(IX^qS!wP((LN4
zf!i2VfL0K;Xu&o`s9FSH3{~=X+W5QmV{qiu=yD;Qb8y2OcKe*k1n^~8k+KW!OQE)C
z;T{IHOAEM=q9P@7uU4oQlTtC1#mQciDmJ}`Pk-4k^N@Wuo@f}5*Lz(QTJqf7@4zG}
zl%EzJWKc6q!hS6{r~tKJEq`cczxpEKB+m7VijTLPlj)sPxIVf|C4b<?3Q!E{V!@F=
z^_fRtNAg~+_OR1%r>|>qkASXoXS{rXCRsW9AGVX;oG0dYgT49(o@P$(fr4-og44|D
z5Xq5f=m>DN{`(yA{;}#$i~7yP0nfp#S|LGrRh8ZoRaMSn(w7Qd9qSC>1!nlVN!X?a
z7Zjoy1L=);Vy{AM&qlZssO2#$Z|1$2iQi^Aw<|v_2)kDDUm96m3bjoQ!x>bF7H}by
z3dE`;A3h9R(`d`1GbqmD%FfxZbMR+vz~k|Oen@q-%7zw2t4R)HW61l(nAu|xaG{Bo
zlu)zcI5yDu%BHH1b9>yZA9x$x2`CyeWOOz*GX(yce>@iZfmyaq9!vW!nbt+~U}*(m
z9xai3(B)2}kx8xxvE}Hu2VcL<LC2l;Bpe7kfgVn(_j`kl^p=I98gQGLEp8Ij8hBg5
zgLA67vS9s)taW%qyBFx4$Lxl>XBntUxX<AI4IX0iFEw_09F^V))d0Zz4C<^(5aPAq
zz9N)xG%^m%JxPy7V0}1$RZIgrdKM@S?IW$6n0r*4I^N@+BP~d1GOI%d+SIJ^>jveX
z;9NK_;?kRCl01yp!Y7Paq84!BF%>AV6iPlU&ij_pOxrdcHC+B8vsZi?x|LY7wEja9
zwjA-kkNNTS5~!yt_?$sK)(S$37Ccvk5@N7*z<z#qd*?ZO^4&0%y&+Rf?3KcJ{Xv&E
zL)SbV#Xnl>T3MTl@T$5Nub(`}fuEk#Z5-_-A(o<ruNkp)E#N{17347}u6;yG#e-;d
zU%ziI-p|nTN*;^Le0Ys&L}r}W7N3Co%$eq^>aa!vm8gX|3`*=naqT&B%n_>IX+aJH
z{~(!42vM;(ZDb24fgg`<pc!KL=ye{+i3NtN-Bz}H5}MKPyw&OUZ_wL2&pWl;{}=~9
ziS9Zu&R0V0ofdvoAof{XoKO*}K54;MM(l@#*elZ<=ij{JY^egw3+GEBx+U^!^396f
znmfrU30>X4&@XaOIy$z-`-tXM8s1u~$zsnt(!-88P|sAqD4%>rHA5>1Ked4T<y`WC
zI<fjIt%eM{;s)ECziCIW=8sUBtnewh^)gVUkRutPi(cTsso>hX4${*rvAti+9@OdR
zGSpA4AZT<zr=##ibYiIdO*La(n<Sy!4Yhizs=h*HayLHPP%#Z#4%(4b_lxx8M5BWx
zm|-!d(CRNwe`0+hb<#z?(qrd$0llKZP})fY%?Tq?MQN4Rm6gOLSVfn=#AHkKIZ|s{
zjWis&VSSKejpw+>!8q4VwbD@FySL}sEs*9*NiD3PKsH##@`YEG(}4<%KxG*`J?9a-
zIgzc%i7B=GH{Gg{Wip;r^ZZq-#&59R&gI9mh(xrt!sp@c<D{oA<#ezHqf}J~xKND>
zGy+m6I&~LA9X-?eROX8pcvAJlMVw!~#L*7x^16+ChEmJyZ)(+LHWDAb#rBHuQ-Qh+
zyqXSjp|%dxW#IKCS<!h%P}2{4lJTh_4X3wvdyAj<z=1nv$DvHWg<eT<()_QjgN>PC
zPc7iWA}Ua?#2&2KZ@KC8@+2H%S+CysqnUU~@NV4r$1`M{-|u|ASHmU!y{ZnjU}jH|
z$NQMzss$|+%-#-&9ef==M$>onuIBtS3$2(sxVOiG8~9L5>*VzF8zg3H0N9#YYXJZk
zpoR$YHaN##8zJ_f?C_A-%nC--bfU|OIp?y`xXkP?eXGRbk#%f}tNf%HSXl=;GN=z^
zQHcrdX^A{ACu1sFP5F*dtNp)wKMc-B$&uH*L#^YmrORZS%7>)ylDMP--I%pACZW9!
zc2n>m6^tO$8gV9E0rcr7u~)k`<i5X2-fsMFUikYazjN?|)}hDRmYsu+)v$T=rR97{
zW|0fiJsJFY2)SUSC33Gmc2E77{m22i^<Fi-Br)6i%|6tv(`Gbf${n+}z2-{H8X@e*
z%sw;;ff`aGH#_xBQcsIvCs0_qqD}*{bI?K6fYPPv?!(<j1M^Rp{UyyU_WlC9lne(m
zpsp%G*g{@%z<}%|{h+daX|wHcAG%!0=J4(BIcUI{Q9U01UXQzv+%Z-)QhM!tF95@s
z;rlAcg%cW5BG0UYFoCpzm{|g2CT<sVr`dkftqvni%y;*S<OO<7^6!p__#B8E<qbH3
zZcDGRkJ5p$41TmpIH7@K72t0vtadNl0f&Db`2r98Y*y9UGXtr;_N=+Qm@LBt;5~`m
zI!c0CPYazGRIEx69CW}*5lT2Vcv*E|_r@Dr{mWkIWY{^7-b^WufiIN5T680nFCzp%
zZ(01j6<%}d&0b4NV_I;!)gX3wyGNP~^cy#x@}pBcS{BoFbMk_hD9K4Te~p{;uibow
zz=JtDQVqHAotDU(G($z-QYwZzQPCK@KOqSv%)R3G>{}e__qp<%E75OJlzaQKhsQ{v
zzC-B4phl?$VTKO)C_r5X&az%TSS>FLSJ0cFpf}j`fD(C0GrLRPa_e&T3P>>En*4ds
z1v;fS7z`#65x3<6U8<}s1}q@{NcH4nR3=o?lRv%csqkj|`A}&|NS;^g6kcunT2)4t
zS7qQbnIGl~W%Gg3OLFMlKw^Jivpa;uWuLWlmL%@`D~`WeF(U9eYS+oF_0Ap{sKnGp
zxJt(){OHWLh_3n4Q7&Bz16cBWG70N+Ab=&0*sM?f%~^KcpQ4oxb1g>?A*UY;i_Ec3
zdVzDFE}yj5Z<%CFUZ;bbnOQMkbKPgcSEwqj1DhGpHpvvqS|jxR61rw=UTDPK*_7Mx
zv<`h)w3wK)eSEY1O&{T5ODBg8`uP^y&yBwPdiH%Zxqf`?$~@^rO3Y`0b|+x~cQdN<
zwSWsdbVMNW2Z0h|Jv3BZ3_sFr<lgx&ui{D--rTvV%Er#-AO5l4eji;-D%L1%@GQyr
zw?hXHGO#`xz=i!fB2X|fvmTlXvX*_dGXIsn`&ArpXYZV!+3#?4_uKEccYc5-XZC%w
ze%Cw+l-S-*9kmCKGw}U7K{%=d#~JuZiKjn-9RA4e_Wzhqx`8LJk9u1w{2l(sBYoRE
z{|Bh@^2`2P=1V<2s)J`3*f0&?La>eqa!<{*YFXb=!+cppDzGcPVz10t`-vOm*QS#8
zcb~n$yDHAixR~$)pVV!$Kxdw#?hC`*>-l&~qI6ORLK)4ACgBnl<TQ&YK#jii#P`75
zbnNn>@33f1I!2SO*+2T3fI7Ts>)9<$dZ&O+3nCd5)(OHT9gJj9Vh^guI(n9P{1SIH
zZ$7rtmvr3oWVsV5ryroDecP;^_Ck6|FHi@r3uYk~>eCXr2dR)gc_j|uBeneXm|n{w
zD~%0IN9U_GpH+R;OMD{g#>C#1iP%EdAb(YR>D(no2W~U?Sd;J^!rKa79eY2m<(3~W
zk)^|h+)gXg@xc?V?N7W(z!&S?j40YcYIc+g+!M?~E>zc$66%#WSSy}sP`Xn(I&~=B
zzGTcxJgUyYU<blBwex`%*{;&zE=C6vnb{}};6k#R2=ZW=!$qV}9IX35UWNeu+wx*P
zJND88aoK!@GHV5Ut~&Wu{*g`3-9NnIIj;1th4qKSuh8_Oj?T@NlS{lI@m`~*N|#|A
zbTEy%I7tV%@SF;A7hQGq{x)$mUs+Z&W=%}T*FUKP&0D6S!OQ0Qj%${TK(oDu{sFBe
zqkN18zGhI*b%Kzg1FsdKY-QIS?$3O9b%;|sJ~V2VCb9A}lvOHjV3!#$Q0ma{XAT~f
zF0f_jU=D+NrvqHLsV0KltEXyLQY!Xp+f;+G;jw2pX70|jFV?<B=LQA6v>T9!B4ZwR
z*1wXz8Eujder8aXT0!`z1D_S32CL*yRU>xoN%Bp?v8Q6L)Qx<NrrlcNez5Bk^dRc!
zOTE_)$>{S@2lE(I1i8nF3Ey=fk3oq&cz-lxNX47a@w!P9sy@B+3T1rG*knBX1f?b(
zev({5n&t0w5SY<robM)K5DCATJXpeUc2KR->~0@GUe`>HufU*nQ+hEyRB4F~ab8~p
z@-ip2{6dFD<s=(?)Cy%|)pC3Hf&5Q5`UkZfW%E4<Z;USTz4qW+XwmKC{fzZ<@NS=?
z`N6RlC5c+X43uI4DWZm4xCcoI4Tw0-KHD<CxMYMQ*P5^5@2$^4WhXbea%*Kc>Ubdp
zw%;jz6X8W2EXT~2*8(n7qJlim6}5EUBaYl>g*%tlraaF|dlP}~x%eL#v>^wz-#K}~
zup6Psy-xcBWhP7EE17|+48F2SsHBBe6}%c+XIkH7qc5SIT}m%?I+TO5Iu^;Z`x%PL
z7Cm?MpX+-iNm)z_YYAor;fEH~QuK;0#EAoF{H~3C|LZ1-{k1kGuU`%dt%?)Ic^^ej
zhFF-_=`Z&H)@M+4%>Wm+>4+e2mlBmu`}n1v!z)4^2ans4gY4=yZ=DfgM6WJf_|RbL
zR*47X`I#on>}<6lkY_8JD40#U7ukGN^m!b(uyK#X{p9*q$`SnFdIV}Wq*7j)SDPee
z$#WDfnc4YjK_HiES}K_R+DS7m=V2sHnY!htRhJy}+P_smhmqINx4N&#mr0iXUG;ey
z*oK+Ct`!6;S|ZP);-(unK(90}+E0y*HuI%usw>T}j%KAvrx)j3M>C<v1O4)*)B=b*
z&)>Ui7~7w0i?zEbSm<I#Uyv)-E3j(0aVX>UIfq*XDNSTn^=4g&Z(<9@H1sXf;xbQF
zN10wnvts0)1+iXnmAot;n9KUxHJC>HrP*3=PCve6^quXu9^f&3-W<tH-Gb}2?GX4?
zpN%}?dLBp*43V^dZ!^%BHPlBS2v;EyXc)zm!WCXbat+D{#Ta;5VP8s9Z0`$@>wQsp
zsg${njQ5fbIn%e*mm#;WA-lCxmM`$mLAhI|ICQFV20d-o=#Hv^v_onk9L8KMs{>pZ
zYDNUPixstUsHlLnw#U9kqoI!7O3x)v=DZmPh9B*I6y@0U9eoi<p@y2lF$}7%Nf>1Y
z#wbG3C-}s}Ow-IU3u^^DK%HY7N1y7Njm~Sp^NhDa*lXw9#r=*3N*Zp08FXY&<+Xwk
ztRsTltI`VRBBizTvW&Pvela~UrKP#J!r|%}=p4?Opg*39*1TACDxl_5+;jVv(N%j$
z#}XGa=*B2bG6P(2r2?fSHmmJby2ynM8R+_qVD*`msc6H4YE`0NJ;A}T9bFgIla73@
zX3&F~EusTlP(e~6H(PgOd8?u1&-L!@ZRhJcJ{|4okQ2K&B@I6cTGKczNxD!!$qafk
zv*omc0Cm7yA%LqDUUKLUYswD&HPx$SCw=7<%KYF$nVt)jzs9k)T3%LF?I+vU4=$0F
zErC^K{FXp-Ss7BxZ!;+h&b)ZA(ui*--nXlHIS03mD;`~BZ2$^R@i6!VNW-{a3zxDm
z+Nc2+7Ml@4o`*<XOO^;L-C`Fn{St#SYn*`ttjHe#-r9d;*n%@iyCJLX;nC9D3U+DX
zDh9RKOc4Cdz$%4AcsB3M?@d=i@UaFBeojxz!4?Z!UHZ30AfB=k@9J_$>Vdx*T*u5l
z(f}^B0Hnl}Uj-xU=ueJO(I^{N?X)@mdxv$X&%GK~Y@a;9hg^o;{ZT{ueu9!3xRIGn
z(FwvfS|T^={^siN@2L;a%7>~ChW%U6-uN2+eqFQir?mqQXH7bdNaGf|5oINS+nCu@
zogf@hgKY}&R;%SHP*p8Y0duulmKNp;Z{;kfR!Vsn!cKhrDQmdd^mCsFcu2B)&I_-*
zC}eNS&{ekYP|b>+jlscZCBvAD8XREm*ytb^CeacaCH|RRZQC`!fgSp88r`{1seZO~
z@_*+Sw*j7D8t@|D9>9hC_W^Z5D?n=4|B7bK>G|vb;U_;If?~kNe)7y|P9BbK?&Qxc
z8I*U;rPBbVk6v8(S3N*ml6<=9*$?=;BCjWFTg)NTmhh{z8?~IDuK{I&jg99tFHa8_
z51+ms-ad{V6J6MDkYkts4;w-i`%%J>)zc+%OiJ}dAbZW7UhR8Bh*2)0tzr6%42$hb
zJt<*LnrtR;2hOC~W&jJ&2-uK^${N!;^)N6LbO#Mv6**CT$Y^5~&G1sqRXz0FM0KOd
z6#p$mk2q#a3Y&`+$d=%-tXx!3$dIVqwDJG7-el*0_e-<T4A=~v+RM{}Jda7@q3up0
z<OUo`v;Zhkus>l0$+4T{EKLvcM~DO&kZ=<tt=T6{Xa-PEPd=<6c>AAR!HnzdiQ&nt
z7devsMdrz*l_x5-O!uO@=bs{7lGX&7QAwyEctt5`uc1D3+)182tysl5Xji`@|Afu>
zv~OLoJIw)Vh5VKpLz>r(^;&n*_!eZ#2h1VPxqxxBe(V_X#GwnAM0n8z@gW)$2|su8
ze+KXdEyy<AXELd$$>U76W)pipq{M=Jy8vJEJ(K9V5N!))XCjd;$d(DmWMeA9wIFpK
z#Fi6d;4Ikh&Gx4?7No|JFqjHlNf}LA4~AL5iCY^7S`z;<iIb50l6gG)eO+jq6oEH|
zwy9p0uuWw^Z{#)YOhk}fxH6|uB@I7)*%4J{d%iDJNufU!uKZZ2vM8ziRJihsut5`v
zeDc2*u8b!QY$8N4?+M#fIiGy)7ur4^d@KKfu+2Cn6xx6fg$+uMei92;J`y&_kMK!F
zf%ITYwkXuL@b&q73vExnl9#_v*rqygf1%2IahLKB6siOVg$)XAMgAWuR0;jdaTsQ1
zCE1{#k<|*Y$sJ4iqY7=)zBRhgHc`(XQ)oMX1;`&;Xxq!pF@Id4ZL04eY%@@&LK|RW
z;SJ})8!o~I^@21Jm?YWO*DB;lcVVL-pt;Dpu!2n?h3(tu=QTQQ7QEtrIxdYbZI}P)
YxGW6+({X7sm<GrHJ3B5RX!^ka1>cHn-T(jq

diff --git a/Tools/ArdupilotMegaPlanner/georefimage.cs b/Tools/ArdupilotMegaPlanner/georefimage.cs
index 17c166f02..21b637467 100644
--- a/Tools/ArdupilotMegaPlanner/georefimage.cs
+++ b/Tools/ArdupilotMegaPlanner/georefimage.cs
@@ -19,16 +19,16 @@ namespace ArdupilotMega
     {
         private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
         private OpenFileDialog openFileDialog1;
-        private MyButton BUT_browselog;
-        private MyButton BUT_browsedir;
+        private ArdupilotMega.Controls.MyButton BUT_browselog;
+        private ArdupilotMega.Controls.MyButton BUT_browsedir;
         private TextBox TXT_logfile;
         private TextBox TXT_jpgdir;
         private TextBox TXT_offsetseconds;
-        private MyButton BUT_doit;
+        private ArdupilotMega.Controls.MyButton BUT_doit;
         private FolderBrowserDialog folderBrowserDialog1;
         private Label label1;
         private TextBox TXT_outputlog;
-        private MyButton BUT_estoffset;
+        private ArdupilotMega.Controls.MyButton BUT_estoffset;
 
         int latpos = 4, lngpos = 5, altpos = 7, cogpos = 9;
         private NumericUpDown numericUpDown1;
@@ -40,7 +40,7 @@ namespace ArdupilotMega
         private Label label4;
         private Label label5;
         private Label label6;
-        private MyButton BUT_Geotagimages;
+        private ArdupilotMega.Controls.MyButton BUT_Geotagimages;
 
         internal Georefimage() {
             InitializeComponent();
@@ -419,11 +419,11 @@ namespace ArdupilotMega
             this.folderBrowserDialog1 = new System.Windows.Forms.FolderBrowserDialog();
             this.TXT_outputlog = new System.Windows.Forms.TextBox();
             this.label1 = new System.Windows.Forms.Label();
-            this.BUT_Geotagimages = new ArdupilotMega.MyButton();
-            this.BUT_estoffset = new ArdupilotMega.MyButton();
-            this.BUT_doit = new ArdupilotMega.MyButton();
-            this.BUT_browsedir = new ArdupilotMega.MyButton();
-            this.BUT_browselog = new ArdupilotMega.MyButton();
+            this.BUT_Geotagimages = new ArdupilotMega.Controls.MyButton();
+            this.BUT_estoffset = new ArdupilotMega.Controls.MyButton();
+            this.BUT_doit = new ArdupilotMega.Controls.MyButton();
+            this.BUT_browsedir = new ArdupilotMega.Controls.MyButton();
+            this.BUT_browselog = new ArdupilotMega.Controls.MyButton();
             this.numericUpDown1 = new System.Windows.Forms.NumericUpDown();
             this.numericUpDown2 = new System.Windows.Forms.NumericUpDown();
             this.numericUpDown3 = new System.Windows.Forms.NumericUpDown();
diff --git a/Tools/ArdupilotMegaPlanner/paramcompare.Designer.cs b/Tools/ArdupilotMegaPlanner/paramcompare.Designer.cs
index 8e8781184..2d90d5f5d 100644
--- a/Tools/ArdupilotMegaPlanner/paramcompare.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/paramcompare.Designer.cs
@@ -34,7 +34,7 @@
             this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn();
             this.newvalue = new System.Windows.Forms.DataGridViewTextBoxColumn();
             this.Use = new System.Windows.Forms.DataGridViewCheckBoxColumn();
-            this.BUT_save = new ArdupilotMega.MyButton();
+            this.BUT_save = new ArdupilotMega.Controls.MyButton();
             this.CHK_toggleall = new System.Windows.Forms.CheckBox();
             ((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit();
             this.SuspendLayout();
@@ -124,7 +124,7 @@
         #endregion
 
         private System.Windows.Forms.DataGridView Params;
-        private MyButton BUT_save;
+        private ArdupilotMega.Controls.MyButton BUT_save;
         private System.Windows.Forms.DataGridViewTextBoxColumn Command;
         private System.Windows.Forms.DataGridViewTextBoxColumn Value;
         private System.Windows.Forms.DataGridViewTextBoxColumn newvalue;
diff --git a/Tools/ArdupilotMegaPlanner/temp.Designer.cs b/Tools/ArdupilotMegaPlanner/temp.Designer.cs
index 767443ebc..1f5e4d083 100644
--- a/Tools/ArdupilotMegaPlanner/temp.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/temp.Designer.cs
@@ -28,26 +28,26 @@
         /// </summary>
         private void InitializeComponent()
         {
-            this.button1 = new ArdupilotMega.MyButton();
-            this.BUT_wipeeeprom = new ArdupilotMega.MyButton();
-            this.BUT_flashdl = new ArdupilotMega.MyButton();
-            this.BUT_flashup = new ArdupilotMega.MyButton();
-            this.BUT_dleeprom = new ArdupilotMega.MyButton();
-            this.BUT_copy1280 = new ArdupilotMega.MyButton();
-            this.BUT_copy2560 = new ArdupilotMega.MyButton();
-            this.BUT_copyto2560 = new ArdupilotMega.MyButton();
-            this.BUT_copyto1280 = new ArdupilotMega.MyButton();
-            this.button2 = new ArdupilotMega.MyButton();
+            this.button1 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_wipeeeprom = new ArdupilotMega.Controls.MyButton();
+            this.BUT_flashdl = new ArdupilotMega.Controls.MyButton();
+            this.BUT_flashup = new ArdupilotMega.Controls.MyButton();
+            this.BUT_dleeprom = new ArdupilotMega.Controls.MyButton();
+            this.BUT_copy1280 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_copy2560 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_copyto2560 = new ArdupilotMega.Controls.MyButton();
+            this.BUT_copyto1280 = new ArdupilotMega.Controls.MyButton();
+            this.button2 = new ArdupilotMega.Controls.MyButton();
             this.label1 = new System.Windows.Forms.Label();
             this.label2 = new System.Windows.Forms.Label();
             this.label3 = new System.Windows.Forms.Label();
-            this.BUT_geinjection = new ArdupilotMega.MyButton();
-            this.BUT_clearcustommaps = new ArdupilotMega.MyButton();
-            this.BUT_lang_edit = new ArdupilotMega.MyButton();
-            this.BUT_georefimage = new ArdupilotMega.MyButton();
-            this.BUT_follow_me = new ArdupilotMega.MyButton();
-            this.BUT_ant_track = new ArdupilotMega.MyButton();
-            this.BUT_magcalib = new ArdupilotMega.MyButton();
+            this.BUT_geinjection = new ArdupilotMega.Controls.MyButton();
+            this.BUT_clearcustommaps = new ArdupilotMega.Controls.MyButton();
+            this.BUT_lang_edit = new ArdupilotMega.Controls.MyButton();
+            this.BUT_georefimage = new ArdupilotMega.Controls.MyButton();
+            this.BUT_follow_me = new ArdupilotMega.Controls.MyButton();
+            this.BUT_ant_track = new ArdupilotMega.Controls.MyButton();
+            this.BUT_magcalib = new ArdupilotMega.Controls.MyButton();
             this.SuspendLayout();
             // 
             // button1
@@ -279,26 +279,26 @@
 
         #endregion
 
-        private MyButton button1;
-        private MyButton BUT_wipeeeprom;
-        private MyButton BUT_flashdl;
-        private MyButton BUT_flashup;
-        private MyButton BUT_dleeprom;
-        private MyButton BUT_copy1280;
-        private MyButton BUT_copy2560;
-        private MyButton BUT_copyto2560;
-        private MyButton BUT_copyto1280;
-        private MyButton button2;
+        private ArdupilotMega.Controls.MyButton button1;
+        private ArdupilotMega.Controls.MyButton BUT_wipeeeprom;
+        private ArdupilotMega.Controls.MyButton BUT_flashdl;
+        private ArdupilotMega.Controls.MyButton BUT_flashup;
+        private ArdupilotMega.Controls.MyButton BUT_dleeprom;
+        private ArdupilotMega.Controls.MyButton BUT_copy1280;
+        private ArdupilotMega.Controls.MyButton BUT_copy2560;
+        private ArdupilotMega.Controls.MyButton BUT_copyto2560;
+        private ArdupilotMega.Controls.MyButton BUT_copyto1280;
+        private ArdupilotMega.Controls.MyButton button2;
         private System.Windows.Forms.Label label1;
         private System.Windows.Forms.Label label2;
         private System.Windows.Forms.Label label3;
-        private MyButton BUT_geinjection;
-        private MyButton BUT_clearcustommaps;
-        private MyButton BUT_lang_edit;
-        private MyButton BUT_georefimage;
-        private MyButton BUT_follow_me;
-        private MyButton BUT_ant_track;
-        private MyButton BUT_magcalib;
+        private ArdupilotMega.Controls.MyButton BUT_geinjection;
+        private ArdupilotMega.Controls.MyButton BUT_clearcustommaps;
+        private ArdupilotMega.Controls.MyButton BUT_lang_edit;
+        private ArdupilotMega.Controls.MyButton BUT_georefimage;
+        private ArdupilotMega.Controls.MyButton BUT_follow_me;
+        private ArdupilotMega.Controls.MyButton BUT_ant_track;
+        private ArdupilotMega.Controls.MyButton BUT_magcalib;
         //private SharpVectors.Renderers.Forms.SvgPictureBox svgPictureBox1;
 
     }
diff --git a/Tools/ArdupilotMegaPlanner/temp.cs b/Tools/ArdupilotMegaPlanner/temp.cs
index 219e468ae..28e7bb4dc 100644
--- a/Tools/ArdupilotMegaPlanner/temp.cs
+++ b/Tools/ArdupilotMegaPlanner/temp.cs
@@ -16,6 +16,7 @@ using GMap.NET.CacheProviders;
 using log4net;
 
 using System.Security.Permissions;
+using ArdupilotMega.Arduino;
 
 namespace ArdupilotMega
 {
diff --git a/Tools/ArdupilotMegaPlanner/test.cs b/Tools/ArdupilotMegaPlanner/test.cs
deleted file mode 100644
index 5f282702b..000000000
--- a/Tools/ArdupilotMegaPlanner/test.cs
+++ /dev/null
@@ -1 +0,0 @@
-
\ No newline at end of file
-- 
GitLab