From 03dfcc7089c54a2ec3cdfc7f36806d7799e6ad9f Mon Sep 17 00:00:00 2001 From: Michael Oborne 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 | 63 +- .../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, 4002 insertions(+), 4259 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 8665324335..8b4fee9116 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; } /// /// 0-360 /// diff --git a/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs b/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs index bee2aa98df..4791cae5f9 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 f77df09450..e7e52d3047 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; } /// /// 0-360 /// diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs index 7ac7ab2cdc..90eea7c067 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 589f67111d..d768645b78 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 ee9137adcd..74e13663a7 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx +++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx @@ -750,7 +750,7 @@ BUT_connect - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this 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 a685523550..9647491a74 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); - - /// - /// Arduino STK interface - /// - 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); + + /// + /// Arduino STK interface + /// + 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 ffa350cb5d..19c8bdea71 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); - /// - /// detects STK version 1 or 2 - /// - /// comportname - /// string either (1280/2560) or "" for none - 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 ""; - } - - /// - /// Detects APM board version - /// - /// - /// (1280/2560/2560-2) - 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; -} - - /// - /// return the software id from eeprom - /// - /// Port - /// Board type - /// - 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; - } - - /// - /// STK v2 generate packet - /// - /// - /// - /// - 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; - } - - /// - /// - /// - /// - /// - 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(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); + /// + /// detects STK version 1 or 2 + /// + /// comportname + /// string either (1280/2560) or "" for none + 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 ""; + } + + /// + /// Detects APM board version + /// + /// + /// (1280/2560/2560-2) + 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; +} + + /// + /// return the software id from eeprom + /// + /// Port + /// Board type + /// + 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; + } + + /// + /// STK v2 generate packet + /// + /// + /// + /// + 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; + } + + /// + /// + /// + /// + /// + 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(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 372cf568c8..3a3a825e66 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); - } - - /// - /// Used to start initial connecting after serialport.open - /// - /// true = passed, false = failed - 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; - } - - /// - /// Used to keep alive the connection - /// - /// true = passed, false = lost connection - public bool keepalive() - { - return connectAP(); - } - /// - /// Syncs after a private command has been sent - /// - /// true = passed, false = failed - 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; - } - /// - /// Downloads the eeprom with the given length - set Address first - /// - /// eeprom length - /// downloaded data - 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; - } - - /// - /// Sets the eeprom start read or write address - /// - /// address, must be eaven number - /// true = passed, false = failed - 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(); - } - - /// - /// Upload data at preset address - /// - /// array to read from - /// start array index - /// length to send - /// sets eeprom start programing address - /// true = passed, false = failed - 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); + } + + /// + /// Used to start initial connecting after serialport.open + /// + /// true = passed, false = failed + 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; + } + + /// + /// Used to keep alive the connection + /// + /// true = passed, false = lost connection + public bool keepalive() + { + return connectAP(); + } + /// + /// Syncs after a private command has been sent + /// + /// true = passed, false = failed + 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; + } + /// + /// Downloads the eeprom with the given length - set Address first + /// + /// eeprom length + /// downloaded data + 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; + } + + /// + /// Sets the eeprom start read or write address + /// + /// address, must be eaven number + /// true = passed, false = failed + 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(); + } + + /// + /// Upload data at preset address + /// + /// array to read from + /// start array index + /// length to send + /// sets eeprom start programing address + /// true = passed, false = failed + 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 746a6f0e10..81351906f4 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(ref temp, count); - - //Console.WriteLine(this.BytesToRead); - - return mes; - } - - - /// - /// Used to start initial connecting after serialport.open - /// - /// true = passed, false = failed - 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; - } - - /// - /// Used to keep alive the connection - /// - /// true = passed, false = lost connection - public bool keepalive() - { - return connectAP(); - } - /// - /// Syncs after a private command has been sent - /// - /// true = passed, false = failed - public bool sync() - { - if (!this.IsOpen) - { - return false; - } - return true; - } - /// - /// Downloads the eeprom with the given length - set Address first - /// - /// eeprom length - /// downloaded data - 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(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; - } - - /// - /// Sets the eeprom start read or write address - /// - /// address, must be eaven number - /// true = passed, false = failed - 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; - } - /// - /// Upload data at preset address - /// - /// array to read from - /// start array index - /// length to send - /// sets eeprom start programing address - /// true = passed, false = failed - 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(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(ref temp, count); + + //Console.WriteLine(this.BytesToRead); + + return mes; + } + + + /// + /// Used to start initial connecting after serialport.open + /// + /// true = passed, false = failed + 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; + } + + /// + /// Used to keep alive the connection + /// + /// true = passed, false = lost connection + public bool keepalive() + { + return connectAP(); + } + /// + /// Syncs after a private command has been sent + /// + /// true = passed, false = failed + public bool sync() + { + if (!this.IsOpen) + { + return false; + } + return true; + } + /// + /// Downloads the eeprom with the given length - set Address first + /// + /// eeprom length + /// downloaded data + 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(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; + } + + /// + /// Sets the eeprom start read or write address + /// + /// address, must be eaven number + /// true = passed, false = failed + 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; + } + /// + /// Upload data at preset address + /// + /// array to read from + /// start array index + /// length to send + /// sets eeprom start programing address + /// true = passed, false = failed + 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(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 7a63c6dae0..32227d2fb8 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -355,7 +355,7 @@ UserControl - + Form @@ -364,12 +364,12 @@ Camera.cs - - + + Component - - + + UserControl @@ -379,12 +379,6 @@ UserControl - - Form - - - XorPlus.cs - @@ -439,14 +433,14 @@ Component - + Component UserControl - + Component @@ -473,7 +467,7 @@ Terminal.cs - + UserControl @@ -515,7 +509,7 @@ ElevationProfile.cs - + Component @@ -757,9 +751,6 @@ ImageLabel.cs - - XorPlus.cs - Configuration.cs @@ -1021,6 +1012,7 @@ Simulation.cs + Designer Simulation.cs @@ -1096,10 +1088,6 @@ Always - - - - diff --git a/Tools/ArdupilotMegaPlanner/Camera.Designer.cs b/Tools/ArdupilotMegaPlanner/Camera.Designer.cs index a748b9749f..b2ff93843e 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 b5668d74bf..8e934149df 100644 --- a/Tools/ArdupilotMegaPlanner/Camera.resx +++ b/Tools/ArdupilotMegaPlanner/Camera.resx @@ -915,7 +915,7 @@ BUT_save - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs index c6453757d3..30b5395688 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> getModesList() + { + if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) + { + var flightModes = EnumTranslator.Translate(); + return flightModes.ToList(); + } + else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) + { + var flightModes = EnumTranslator.Translate(); + 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 cd85b92445..aee48f0402 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 2fe153f289..ac07fc4a32 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 allPorts = new List(); - - 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 allPorts = new List(); + + 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 76492e1e8b..435e3f46ed 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 f5b5feb3e2..d569cad89f 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(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(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 6e33d77c35..26ab3db6c2 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 e26038bdcf..2326987b33 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 e87062fb46..1ca4337e68 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; } } } - /// - /// this is to reduce cpu usage - /// - 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; - } - - /// - /// pen for drawstring - /// - Pen P = new Pen(Color.FromArgb(0x26, 0x27, 0x28), 2f); - /// - /// pth for drawstring - /// - 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; } } } + /// + /// this is to reduce cpu usage + /// + 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; + } + + /// + /// pen for drawstring + /// + Pen P = new Pen(Color.FromArgb(0x26, 0x27, 0x28), 2f); + /// + /// pth for drawstring + /// + 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 dfa1e43a2d..fa42576c8c 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 2b16d6337d..1cd32b95c3 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 9e9002a875..5c96aff3e4 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) + { + + + + + Graphics g = e.Graphics; + + g.DrawLine( + + Pens.DarkGray, new Point(0, 0), new Point(this.Width, 0)); + + g.DrawLine( + + Pens.White, new Point(0, 1), new Point(this.Width, 1)); + + } } - - - private void LineSeparator_Paint(object sender, PaintEventArgs e) - { - - - - - Graphics g = e.Graphics; - - g.DrawLine( - - Pens.DarkGray, new Point(0, 0), new Point(this.Width, 0)); - - g.DrawLine( - - 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 9faaeb8441..0516705645 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 cc18c0b723..b2a931d4bf 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 { /// - /// 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. /// public partial class MyLabel : Control //: Label { diff --git a/Tools/ArdupilotMegaPlanner/Controls/MyTrackBar.cs b/Tools/ArdupilotMegaPlanner/Controls/MyTrackBar.cs index 1e010c806b..bf4536df0f 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 0a7a764793..58260f138b 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/MyUserControl.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/MyUserControl.cs @@ -5,6 +5,9 @@ using System.Text; namespace System.Windows.Forms { + /// + /// This is a mono fix, windows handles this error, mono crashs + /// 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 683b995004..ff11f878de 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs @@ -5,8 +5,6 @@ using System.Windows.Forms; namespace ArdupilotMega.Controls { - - /// /// Form that is shown to the user during a background operation /// diff --git a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.Designer.cs b/Tools/ArdupilotMegaPlanner/Controls/XorPlus.Designer.cs deleted file mode 100644 index 2a14e1fe1f..0000000000 --- a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.Designer.cs +++ /dev/null @@ -1,112 +0,0 @@ -namespace ArdupilotMega -{ - partial class XorPlus - { - /// - /// Required designer variable. - /// - private System.ComponentModel.IContainer components = null; - - /// - /// Clean up any resources being used. - /// - /// true if managed resources should be disposed; otherwise, false. - protected override void Dispose(bool disposing) - { - if (disposing && (components != null)) - { - components.Dispose(); - } - base.Dispose(disposing); - } - - #region Component Designer generated code - - /// - /// Required method for Designer support - do not modify - /// the contents of this method with the code editor. - /// - 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 98808fe432..0000000000 --- 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; - - /// - /// either X or + - /// - 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 7080a7d118..0000000000 --- a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.resx +++ /dev/null @@ -1,120 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - text/microsoft-resx - - - 2.0 - - - System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs b/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs index 38e37a84be..f24440fb59 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 { + /// + /// Mono handles calls from other thread difrently - this prevents those crashs + /// 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 50e01de71c..a9966cb926 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 fd5a942cda..6d3ff562e1 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 7f73de58f9..8aed12b210 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx @@ -367,7 +367,7 @@ myLabel2 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null groupBox17 @@ -379,7 +379,7 @@ myLabel4 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null groupBox17 @@ -403,7 +403,7 @@ myLabel3 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null groupBox17 @@ -415,7 +415,7 @@ myLabel1 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null groupBox17 @@ -2341,7 +2341,7 @@ BUT_Joystick - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null TabPlanner @@ -2353,7 +2353,7 @@ BUT_videostop - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null TabPlanner @@ -2365,7 +2365,7 @@ BUT_videostart - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null TabPlanner @@ -5926,7 +5926,7 @@ myLabel4 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null groupBox17 @@ -5950,7 +5950,7 @@ myLabel3 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null groupBox17 @@ -6016,7 +6016,7 @@ myLabel2 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null groupBox17 @@ -6127,7 +6127,7 @@ myLabel1 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null groupBox17 @@ -9018,7 +9018,7 @@ GDI+ = Enabled BUT_Joystick - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null TabPlanner @@ -9045,7 +9045,7 @@ GDI+ = Enabled BUT_videostop - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null TabPlanner @@ -9072,7 +9072,7 @@ GDI+ = Enabled BUT_videostart - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null TabPlanner @@ -9120,7 +9120,7 @@ GDI+ = Enabled BUT_rerequestparams - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null $this @@ -9153,7 +9153,7 @@ GDI+ = Enabled BUT_writePIDS - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null $this @@ -9189,7 +9189,7 @@ GDI+ = Enabled BUT_save - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null $this @@ -9225,7 +9225,7 @@ GDI+ = Enabled BUT_load - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null $this @@ -9258,7 +9258,7 @@ GDI+ = Enabled BUT_compare - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.Designer.cs index e674259f91..c3ddcee8a4 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 6837cc9ce3..5c08a8ab7e 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 a4f7288080..062a6b34a5 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.resx @@ -175,7 +175,7 @@ BUT_levelplane - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4492.39671, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4492.39671, Culture=neutral, PublicKeyToken=null $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.Designer.cs index 823abeb9ab..b9e95dff5a 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 5da92ae68d..7cc693578d 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 fafc62b415..d21598f126 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.resx @@ -250,7 +250,7 @@ BUT_levelac2 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4496.35237, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4496.35237, Culture=neutral, PublicKeyToken=null $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs index a67ec30bdb..ec5d7ca2cf 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 606a5f34d4..ce263e44cc 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 1be2fe2b20..c404907f7d 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx @@ -135,7 +135,7 @@ myLabel3 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this @@ -201,7 +201,7 @@ myLabel2 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this @@ -312,7 +312,7 @@ myLabel1 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs index 34afb1dc4c..11bbb4fb8e 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 d84fe9af39..404f48b844 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 ed3be8b223..a9c3c3d324 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 a19aa5c250..3e89a13282 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 7f2a0fb988..5fe9928d4b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx @@ -946,7 +946,7 @@ BUT_SaveModes - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs index e5a2e07eae..dedab86cf2 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 e804b80529..b9795fb111 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 b15fe2836a..64dab98e71 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx @@ -139,7 +139,7 @@ BUT_MagCalibrationLive - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null $this @@ -526,7 +526,7 @@ BUT_MagCalibrationLog - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs index 3b6108454f..2bd4051212 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 3e35ec89ce..11e3e4a01e 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 6e75804078..8e15fbeacf 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx @@ -1268,7 +1268,7 @@ BUT_Joystick - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this @@ -1295,7 +1295,7 @@ BUT_videostop - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this @@ -1322,7 +1322,7 @@ BUT_videostart - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs index f3e54cffe3..2ef80c22ad 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 91e6716fe9..1cf26eacaf 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 f4c0f26f3b..55749712e8 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx @@ -403,7 +403,7 @@ BUT_Calibrateradio - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs index 389ce857b8..6b072f30bf 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 a131ea1b17..a831f31c1b 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 3a3f70f565..e4bef97a51 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx @@ -142,7 +142,7 @@ BUT_compare - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this @@ -172,7 +172,7 @@ BUT_rerequestparams - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this @@ -202,7 +202,7 @@ BUT_writePIDS - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this @@ -235,7 +235,7 @@ BUT_save - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this @@ -268,7 +268,7 @@ BUT_load - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs index 211699c119..7a4c662264 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 c4d3effe1d..6f99332ff1 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 133ab792d2..56cc3b35a7 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx @@ -217,7 +217,7 @@ BUT_swash_manual - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null $this @@ -409,7 +409,7 @@ BUT_HS4save - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null $this @@ -550,7 +550,7 @@ BUT_0collective - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null groupBox1 diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs index 780efaf1c5..60cc50f7b9 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 fbd2dcbc83..9b13408161 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 fa56951ee9..8dd5014360 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 8971889c8b..cc696b6745 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 2f436fe289..be5eb92e01 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx @@ -367,7 +367,7 @@ BUT_setup - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs index 9b17adaae6..87435b07aa 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 11e610087c..da690be453 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 2cbf5522e0..8921faf5e3 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx @@ -208,7 +208,7 @@ hud1 - hud.HUD, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + hud.HUD, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null SubMainLeft.Panel1 @@ -247,7 +247,7 @@ BUT_script - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -280,7 +280,7 @@ BUT_joystick - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -310,7 +310,7 @@ BUT_quickmanual - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -340,7 +340,7 @@ BUT_quickrtl - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -370,7 +370,7 @@ BUT_quickauto - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -424,7 +424,7 @@ BUT_setwp - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -475,7 +475,7 @@ BUT_setmode - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -505,7 +505,7 @@ BUT_clear_track - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -556,7 +556,7 @@ BUT_Homealt - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -586,7 +586,7 @@ BUT_RAWSensor - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -616,7 +616,7 @@ BUTrestartmission - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -646,7 +646,7 @@ BUTactiondo - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabActions @@ -700,7 +700,7 @@ Gvspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabGauges @@ -730,7 +730,7 @@ Gheading - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabGauges @@ -760,7 +760,7 @@ Galt - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabGauges @@ -793,7 +793,7 @@ Gspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabGauges @@ -874,7 +874,7 @@ lbl_logpercent - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabTLogs @@ -925,7 +925,7 @@ BUT_log2kml - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabTLogs @@ -976,7 +976,7 @@ BUT_playlog - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1003,7 +1003,7 @@ BUT_loadtelem - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1192,7 +1192,7 @@ lbl_hdop - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1225,7 +1225,7 @@ lbl_sats - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1255,7 +1255,7 @@ lbl_winddir - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1285,7 +1285,7 @@ lbl_windvel - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1457,7 +1457,7 @@ gMapControl1 - ArdupilotMega.myGMAP, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1520,7 +1520,7 @@ TXT_lat - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null panel1 @@ -1577,7 +1577,7 @@ label1 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null panel1 @@ -1607,7 +1607,7 @@ TXT_long - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null panel1 @@ -1637,7 +1637,7 @@ TXT_alt - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null panel1 @@ -1838,7 +1838,7 @@ label6 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null $this @@ -1916,6 +1916,6 @@ FlightData - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs index acadb4b905..524e96127b 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 5e38631859..bdf89907b3 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 8db443f0a2..f70e995ead 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx @@ -556,7 +556,7 @@ BUT_write - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -583,7 +583,7 @@ BUT_read - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -610,7 +610,7 @@ SaveFile - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -637,7 +637,7 @@ BUT_loadwpfile - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -1261,7 +1261,7 @@ BUT_loadkml - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints @@ -1291,7 +1291,7 @@ BUT_zoomto - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints @@ -1321,7 +1321,7 @@ BUT_Camera - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints @@ -1351,7 +1351,7 @@ BUT_grid - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints @@ -1381,7 +1381,7 @@ BUT_Prefetch - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints @@ -1411,7 +1411,7 @@ button1 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints @@ -1441,7 +1441,7 @@ BUT_Add - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panelWaypoints diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Help.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Help.Designer.cs index 965140d1d5..9151f64fdb 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 8d7938a05c..f5e2d6cd42 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Help.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Help.resx @@ -196,7 +196,7 @@ BUT_updatecheck - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs index 45318952a8..54ae0bb1a2 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 fca5683952..307090fb1b 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 b78bdb87cf..0b480ae370 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx @@ -261,7 +261,7 @@ ConnectComPort - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel5 @@ -309,7 +309,7 @@ TXT_roll - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel2 @@ -330,7 +330,7 @@ TXT_pitch - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel2 @@ -351,7 +351,7 @@ TXT_heading - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel2 @@ -372,7 +372,7 @@ TXT_wpdist - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel4 @@ -396,7 +396,7 @@ TXT_bererror - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel4 @@ -417,7 +417,7 @@ TXT_alterror - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel4 @@ -438,7 +438,7 @@ TXT_lat - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel1 @@ -459,7 +459,7 @@ TXT_long - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel1 @@ -480,7 +480,7 @@ TXT_alt - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel1 @@ -504,7 +504,7 @@ SaveSettings - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this @@ -588,7 +588,7 @@ TXT_servoroll - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel3 @@ -609,7 +609,7 @@ TXT_servopitch - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel3 @@ -630,7 +630,7 @@ TXT_servorudder - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel3 @@ -651,7 +651,7 @@ TXT_servothrottle - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel3 @@ -675,7 +675,7 @@ label4 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel1 @@ -699,7 +699,7 @@ label3 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel1 @@ -723,7 +723,7 @@ label2 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel1 @@ -747,7 +747,7 @@ label1 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel1 @@ -792,7 +792,7 @@ label30 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel2 @@ -813,7 +813,7 @@ TXT_yaw - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel2 @@ -837,7 +837,7 @@ label11 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel2 @@ -861,7 +861,7 @@ label7 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel2 @@ -885,7 +885,7 @@ label6 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel2 @@ -909,7 +909,7 @@ label5 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel2 @@ -954,7 +954,7 @@ label8 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel4 @@ -978,7 +978,7 @@ label9 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel4 @@ -1002,7 +1002,7 @@ label10 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel4 @@ -1026,7 +1026,7 @@ label16 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel3 @@ -1050,7 +1050,7 @@ label15 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel3 @@ -1074,7 +1074,7 @@ label14 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel3 @@ -1098,7 +1098,7 @@ label13 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel3 @@ -1122,7 +1122,7 @@ label12 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel3 @@ -1167,7 +1167,7 @@ label20 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel4 @@ -1191,7 +1191,7 @@ label19 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel4 @@ -1212,7 +1212,7 @@ TXT_control_mode - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel4 @@ -1233,7 +1233,7 @@ TXT_WP - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel4 @@ -1257,7 +1257,7 @@ label18 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel4 @@ -1302,7 +1302,7 @@ label17 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this @@ -1375,7 +1375,7 @@ label28 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel6 @@ -1399,7 +1399,7 @@ label29 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel6 @@ -1423,7 +1423,7 @@ label27 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel6 @@ -1447,7 +1447,7 @@ label25 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel6 @@ -1495,7 +1495,7 @@ label24 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel6 @@ -1519,7 +1519,7 @@ label23 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel6 @@ -1543,7 +1543,7 @@ label22 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel6 @@ -1567,7 +1567,7 @@ label21 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc panel6 @@ -1684,7 +1684,7 @@ label26 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this @@ -1855,7 +1855,7 @@ but_advsettings - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this @@ -1939,7 +1939,7 @@ BUT_startfgquad - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this @@ -1966,7 +1966,7 @@ BUT_startfgplane - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this @@ -1993,7 +1993,7 @@ BUT_startxplane - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.Designer.cs index 29b1c3207e..eacae4685d 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 2c4897acef..9dbeb0d323 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 4da6d80a1b..af41b2749b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.resx @@ -166,7 +166,7 @@ BUTsetupshow - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this @@ -190,7 +190,7 @@ BUTradiosetup - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this @@ -214,7 +214,7 @@ BUTtests - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this @@ -238,7 +238,7 @@ Logs - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this @@ -262,7 +262,7 @@ BUT_logbrowse - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc $this diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs b/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs index 567ecfd7c9..6b6ab46c6d 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 92e7c613d4..c750515d5c 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 9b38147048..1912c313d4 100644 --- a/Tools/ArdupilotMegaPlanner/JoystickSetup.resx +++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.resx @@ -1258,7 +1258,7 @@ BUT_detch8 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -1309,7 +1309,7 @@ BUT_detch4 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -1336,7 +1336,7 @@ BUT_detch3 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -1363,7 +1363,7 @@ BUT_detch2 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -1390,7 +1390,7 @@ BUT_detch1 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -1417,7 +1417,7 @@ BUT_enable - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -1444,7 +1444,7 @@ BUT_save - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -1567,7 +1567,7 @@ BUT_detch5 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -1618,7 +1618,7 @@ BUT_detch6 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -1669,7 +1669,7 @@ BUT_detch7 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this diff --git a/Tools/ArdupilotMegaPlanner/Log.Designer.cs b/Tools/ArdupilotMegaPlanner/Log.Designer.cs index 97aeebba07..5268c07d9e 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 5bef471ab6..520c59ac44 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 b1e09b2bb4..cf6b035012 100644 --- a/Tools/ArdupilotMegaPlanner/Log.resx +++ b/Tools/ArdupilotMegaPlanner/Log.resx @@ -159,7 +159,7 @@ BUT_DLall - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -183,7 +183,7 @@ BUT_DLthese - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -207,7 +207,7 @@ BUT_clearlogs - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -276,7 +276,7 @@ BUT_redokml - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -300,7 +300,7 @@ BUT_firstperson - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this diff --git a/Tools/ArdupilotMegaPlanner/LogBrowse.designer.cs b/Tools/ArdupilotMegaPlanner/LogBrowse.designer.cs index e262c3dc0e..aa1db0eff6 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 f122be17d4..93a5287ca1 100644 --- a/Tools/ArdupilotMegaPlanner/LogBrowse.resx +++ b/Tools/ArdupilotMegaPlanner/LogBrowse.resx @@ -193,7 +193,7 @@ Graphit - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -220,7 +220,7 @@ BUT_cleargraph - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this @@ -247,7 +247,7 @@ BUT_loadlog - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c $this diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs index b9fa51deec..485ef2a42a 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 83e817b7e1..be039b53e8 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 cd4e7d8217..0a77c3dfce 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 9406a8df5f..ec4f313eb2 100644 --- a/Tools/ArdupilotMegaPlanner/MavlinkLog.resx +++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.resx @@ -139,7 +139,7 @@ BUT_redokml - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null $this @@ -193,7 +193,7 @@ BUT_humanreadable - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null $this @@ -223,7 +223,7 @@ BUT_graphmavlog - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null $this 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;^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!jogT>{I8!UsZ=?*JJJGk_uv z_G)ObiU0k2}~hBUT_savecsv - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c tabRawSensor diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs index aa2773fdfc..ba32270f0c 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 d1b6f9ad9a..56fdc08200 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 99cb96659b..d13b7ec707 100644 --- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx +++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx @@ -1959,7 +1959,7 @@ which result in a valid packet CRC BUT_savesettings - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null $this @@ -1986,7 +1986,7 @@ which result in a valid packet CRC BUT_getcurrent - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null $this @@ -2037,7 +2037,7 @@ which result in a valid packet CRC BUT_upload - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null $this @@ -2061,7 +2061,7 @@ which result in a valid packet CRC BUT_syncS2 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null $this @@ -2085,7 +2085,7 @@ which result in a valid packet CRC BUT_syncS3 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null $this @@ -2109,7 +2109,7 @@ which result in a valid packet CRC BUT_syncS5 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null $this @@ -2715,7 +2715,7 @@ which result in a valid packet CRC BUT_syncS8 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null $this @@ -2742,7 +2742,7 @@ which result in a valid packet CRC BUT_syncS9 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null $this @@ -2769,7 +2769,7 @@ which result in a valid packet CRC BUT_syncS10 - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null $this diff --git a/Tools/ArdupilotMegaPlanner/SerialInput.Designer.cs b/Tools/ArdupilotMegaPlanner/SerialInput.Designer.cs index babfd7e315..06d99e0a85 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 099d4b32b5..1f57d7eefd 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 859cd8e7d4..c15b74ec62 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 8b7bd960df..11c4d121c4 100644 --- a/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj +++ b/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj @@ -56,7 +56,8 @@ false - mykey.pfx + + @@ -80,7 +81,6 @@ True - SettingsSingleFileGenerator Settings.Designer.cs 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|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 z24chjTHajk55eO#b4_D$12P;)uTZ_?eh( zAjT8oRF&qnO8<&g!_{%6IpxVR%-Ydvh{}Gp7F-*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==mL0mRftlS0MzV`YZpT0U4w zu}wmD;aDSR&yyaTimf2r4j~rqPqs|9T@}gr^aibPZ%@Sk@(jees1?m@K1)dC6L=6% zgd!y#jZVG%#*@Q^uuluOax|fd2-SAPsL|NQuI4s$fT#p(XHZ zUJ36o{JG?`zN3QiJOA1>zHwV@^>pdwFf`QjW5OchPBIp_k29ATMnL}`yrz}jJqU0) zp~>`Mm)-+=MLX&jTOUkL=cG@Co+>??B|~v7GM^G*$V(>xm3OB@oD4uRh{@1lAj^nT4_lW4mi+CPz~n;#rt~n( zl<*8@!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>Zx(w9V$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 zwkZysT+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<|AnK- zRUyaXVi?4U5^DoE-f$ou@{&Rc)O6kZ>j^b&t-drD4bDT^TQ=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^txM*ZL zB4Myzy;EVdZ&2OWn#bs*9?TqN5J(g?!w#tAk)M04XAUUP6Vp*YXUxq_4# zI<=*-b;~xfv4ij#TN>LHOlN$a)MwpmDboT+s}H8M*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;O>iz5Eb-^^B}t7MJwfMsvVOK`h=+3Q+)$w|;!*XiIXG)!LLIOJn^IVsnNrzjQ2ur~m#`jdlCn|9BsxRTH?dHzwIy5RB z%JF)~MBNKm-xe9)8yTN~uANzZ0@2^xU)?|{dKI@<(a$wehfTG8~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-v0pJI220>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))qH8xMJ?nR?A1nz#8AP zeY$ksELotoKrkv2539jV&IsAOqL9<~`L#-@$>^r8~z)XeBCZZj(*d zG5SMkG=h2C7B&Lp*i}plXvHXd?#ZY8#DrY5t%sNXQms&AwNlaJgl;5pgYrojA4D_>s-r)6^6TQy5=<#_TR0E+zOtcpF?*}SW_BF=7??_H;_W5 z0>N{UIRR@1NNLa!mS=2xvd6XyTA*P?0R zW3*;;!xi2dDKS@$8%~K0;Q((8B?hYj6!QSgc5wX%&Zq1jYckZZxPpOl|#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)4ehgFCA&&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>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?&s}7spS5T_X_H~wcD_xEr?HGK%S1RUM$k^m;HWAWH_!;iwtuq`5;$@` zv2N2C?kwZ;;Vv`21dhx>*2gZAskcaEWO%-u?u{6hMNmfOS28z9Z^%SQ;BGKTH#jn? zt02} 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;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!$UZAeiO6-Cfa|;m}=S&-er#bY)vlC2ci0@cCfckyNY$ zIJbe8nFjLtpj~{8#dA<}U}ASr=onvn8DDYBOr00Hla>{qccwLDk@|=_fK5ATZSkB2 zd}Yp3eHC394t*8f8K0no>936;LT&#mpe~p$IF8lELF#jmaZh*ppiS3|p zWqdjrUjf&bsnRiR*xRVW59K2FB>`@Fw&p#y2XF}O5;=2<3ljW<%k zvK%S)iT2S+H`0UVU8VSSMkv0IE*+y|WFm;;v1<-pr{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=|;jaF^yWn zkLu%99*N(-GW>XUij-~-M;{0IzwuVMBsxQ&n`oZnl+VP5W43l^< zf_CKEID)6O8$=_RS~g}QT$YI-w8d1ggC1|l8%2-T?cp9l7Vokm;eX~}NFG3A7G6gI)re0{({|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;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&~QQ0j5DR!?sQO^C-%9|5Nj$!Ea%k3@=^ajM=viQUwcShUGbl}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-stRODFJVEAqGoKoE=AJ9H6wugwlaxociM)B;(auF^iay`b^bcQePWo;a3wrHQ9`G zRO*;!3|RQ+qt69|Je-@nn6n@cHhbQ*$LF{-So5!*j&s^vk~9MgvikOuAvPxG=+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>~$}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^v7)n30Qa%^OTM1%QCu!s`VD>>d+NIa|t zUP|_2@w$SAFF$_PqUrd1Mt3~-b=xh~kj4gWUsB^vOrO-;wZY^a>JXU&Dh4`78gm3OV5iX`xMN^Tv6 zA0--Vlwh31**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?%YPb&8jC3liSl@pB^B{(SywU24l zrz5dLs@{Bo)=eB&^Xd7wF#F%^O{U1luu|=p8*@XYP+8mE=utPE6DB@6XW z-oLxo?0bsd?tOfEW8iC;@!w7EW7I3?zpAZ)6iV!-67a??Vz9)Lm6^;4-<`aq(^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#(iSXe7jq=+u|0qH1av%~s^*Q7sVldI(Zp-{gR zg7H}i{*i&YD~@{O^p5myl4;EtdhMj2kjm~D6^KJo=U(5Fq@i|$n%36tk7jEZD(^Da zYK2O6pSVy-nrody1T`>gXS>DUOHSB3jfRO0%kJtHje*k7Z3TlctvEQc%C zSHwg}df>Z~Q>f^El@jm>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=PVgHA?(6VsPSCGpzP&Z((TO3+Q`q$&*Xhu1Umds^aWu*m$L26cK~%7oC#b zsIOT6lguaoI{;}tqzx^>!`vo|CoGhe}VpiodL80}P`gDjM| z*4^k!H+%GBQs~gomn>k{`(0Hmv0F>;BvyC~1#io&c)ui%Xz^P_#+zebBZHo9KF_#7>;yzb{R z-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?QLJbp*F)H983nlcd_SQdiv)HKWNVgeu zQBBz$!|^JX*n>Jt^52)d3+?((A2$1J9$NCDuGa!ZB66)iqCncS}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~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`Wz9XC6t7M2BPnu_Y>Q4JEcx1$bjMF<1>&saUz4JeQ6i zx-%ILiw)^+-vs}##DA+)T?U*(Uvu6LDX1isd%lW`pirwtBU}X{WT84UJ^OjUnxZW{+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^^|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*+35b zVz4dsQnFKNuTHH>Ke%}ewz<)2@ZX;-=x&P-4&_%wpc%cpcTQcoL(y^ywTqAHP;oZASHkkCL3!!8!nXqdp-{OhjyFE5 zu!pqDx&>bx%wO^z>Y<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$Z?E*iJI!*S?bSaGK6vjy&(y3z1p>qZpR`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}}NSkEgzHoWbM7+41X{*w+tyQc zH&&q61Ev!{QXx^tx*3DjBN@eN-tr18{pdC7QNGpKYG2==-p4B)dw%jBtk!Ln^QyCP z5@I9NV2nVFyjTYPv2?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_cDsr9bznt%%$b(N3t_H_DrlQ9eJR|+8eoa*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*?hFEl9)!66Fji{yO zh3k@kEzsve)eWn=9e^8bf3C|?>_gVGc%B-3ro__J9B(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;wWWk_* zXWE|Z^d5e=^P;QW{zs@^R&yq+Yo1W0_28Up3ZnttnKPS}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@25HP=W^f{KtBtfngKB8D~B;hP|+Nks)??cc;J0 zPrQzN*C&1`d+8(kJK)W>xncL9?KwBM?n9)V$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(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!|kC^l|^Hh2JDfAVg=k>v}s45Ru5r?+)I=58)n05 zv4^wc7rsP;FJvqm*;u+H3D*HEx1#1-SRsGo zvxus%&_wgap3xR**!>zViiT||8Z(H&_RC3`+X|)o9~(G`!T@2?}*WG@>=≥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>0sTzc8+(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 zzsLs9_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{Y1vR7Sg*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(f6iQd+OJwq*(l5T;m_pUs;fLL7Vd%S{u=7 zW7U?0F*~948L6}lSD8Xpv;n+vSdBewtCGYOBk0`!B$d0nD?L>jEHBtC?ix1iO#!

dhC01XCSl3^7W=z;&Lh2*sz?KLLO1wJTG55_mm_2Yt?*;p%!>*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{~9us zTVB$z33VE?+IiN07G$}9KcRiY{is3n@tf;bHA=#cwc#evu#eS(kwXl&1Sh=)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<>`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`NVuO!=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(UZt|iPZX# zI{G1dl~by-A;dh0mLt*kAi6V5+NG7W2NAt#M9bNPXKn+mN!di=uq)ZulOTGK+P*}~ zk(9WAVjSDdhH&Nk&LF>9URsQndJo?&j53XK8tgi zzwa?Xh_cXH0uLqIw!|`R5g(IP9kps|ZGjtUBPA~>3iU+bqoG%l-ttUkaB01Rf6>*1tr6XCx3bY$+n&>cC_W^nEWRD_aYdyZG}jX_?t@XNvSW< zrV(~wSxNKDnOGHKU4rWJzA}(l@gV?`x zSMZ}`;WDvx0iAFkKx}&!*d}8D)ujEK_H`Qb5`Wr8TBB%_Sg;kmFlCIuu{f>qBo=8a z@o}Lwi3RixkSN^}bPo-M3BmP{@tvkbQ<7U(!cqh{(aW{~V#N~y-4 zXwmVM28Mq00+9Jo*2QTDq@9>{9T{Xv)6gT=Wq?Hs$|W$lNPsCZj4-7G%mEC(<2xkTQovfC{b9Ac4VG@K5T%dF)LPB!Gx!wsX{8t6s{af;OH zETw5iaEsG{q`| z&xa#JcReczbl|^iL-`99isK&*!QP*3D$xE(#%Bt!EqpxB0-GArVY}c2i;hIzek4MLmQ;y=lhNBW z>77t$0!*r5zP-I7J-R0-%Yu-fUksEdJ;ZaGm#2q|hffceNp2o)KIDX$De)X*BLAX+ zD`Q~5|9@~1(y;E$@l1psrJjjSqp(c-=7_ft^&&xh7bba{h%Hr(Ia zu1!2H|FX=3Yl}Cq!-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?gyz2Hx@vMzn-}#89ZWhZU5XLAQv;NUSZmQGG__IjR%*$#Nreqs*Gi zrdazdUd`%2xd#STcengy@=Kj5{U^xxhxG}qaXkx_8E&`fy5lU=f4A=NR*;OpY-)SB z{mVTpF$$bf)`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$F0P7K+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*2eAVve%&AvVxlU6K zj%uHcvFnD8mLB);pvA71S;Ye-logZ1s?1f6Gh@JVies30BLa;k0vxO0-Y7B?_)|3! zfU#r?fbrxQr)Yfs^!Cg_{qnWkiP0ZT4jOb`MHsNY-1&9P!4-C4 zLG@x>dwGmJ^IXYXLu$blj8Z704*mtny<3+HluxSPx&ZoXu$~nm1^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=&XQ-OYzyaryLJ)>w!85h)G(>rYYb}TIRIJreA>M?m`$wwEYa~4Go4lZr3GMwXD zh66@~#GnlX7;aLC{8sQUsRFzzfC}`p1#Fi%_^)aB2!6Gec4A;K8_Q-rpiS9pGB>)b zJxg?NdDRuz;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~;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|{Tg3>pHm=SX-Mv zHskG7$?-Chx2vH2HSjYFRceR@4^{Cue=;$AksqrwoLI&C#JptM;^IJb+A?@-we_da zhUHh?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?(zT{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;3qSm%Q45qRWHEjf~q%Ehirlhu#%)b%LwgY@HlPB9Lc>{l?_qA%v#Sl8+0knU;WhyqtO5SlDUOG8kD(XC<4}q8cTBD z6upaD_Mbj%&V_8e`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;*|`po;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@*5WeC;$ 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 zf@0NUl8}E|OVT2d8s8w`x+kf8Y;JZ!Vb~j(K0o%J)uDf#5Jjqc|90z-N zhL9c)s5$__5wZoqF?a%skBsqyW_zqz9f00lx%v3buN*w4WN3*V8gjOF z^iek{;j% zF?Cm$zq|#z_C98{wp%vJZPg^kV|xgurV7rg#AHpK2e|*N#5#|D^9H_T(e)x7FkloT zyBi9Ec<*a4ir6Mq9?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<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$~nETy%RYjckb*%23+uKv?tX4$YE zT}JtT;b?fA+<;p)+$_#44>(WmQC=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`2WU?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$^wf*UR^-^R4J-Q&$x)}J0P#i=uPSj2+Z*^khbG3|iMm@IV4 zSngnrs5pFL=Gd)gzpRy{j*@;O%ceM(ermANmWv z?RG?TH?b)fl_x0^lRXjA`uDM%N9g2@HhvjZv(T-C+VhTu#p9~UWnSneOUZhuzzl&b zD<_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|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;S zs?biRSB8~|)Ahi*72{4OzC~S@F3jrIGY$n!o>B9q?g_5*@MTKTh<%cVjRxR4qm%+5 z7sO0bfsxX?&Pc{cA|f~zQ-=Ew1-!rybDt7Pf9Y!@)1-Nh=5P{N*lMp)yDZJPd6WM2#*(GS> zwL@&OYKSR+O<|E3@85W-Q;Em;UZs<}Z@znr{3FPXX2dDR=LL!Hf$w9PL_ z;l=J6z%N;Q82}{vi}j#NuJ;SlmlKHfG^WwCVnQ%K8ufU@k4AQ_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- 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={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-auhTekaP?& zuanFkJk4A?p$1$yMFr|wh{UxZwfrupAhiq86jNH*FMaN{qEGPT#$7rdv3!eqUdwpf zx77pm;o{;uUx!I=95}Crml%NyYQTkw?jj9cNdEM5v9u7=kY;B8gxp%h+qRSm8)_?t3#d7u}asR5?c zFycPt8my|hEF1kyu(;RPHy$AVB(;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 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;J8WSc!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?21MNKhA&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@_{ZO`bo@!HMVg?LNPFJ9-$j zJN{aSO%k&q0FGy7gURdmn6RA+v}MH3ZDq?kVyMiV)uH>MF*m*Q~YUnH=2!fLaI4gM2&wpLo;~(d7vu0}RwPf{oMA_mMZu~fhEE@LD zS=L~I#H^DBx-qj|$sK4+h=4?pdl1GR9aN#a&ZF4w8)kb3=b)w?k5_v-FBIQ(>*Ks9 zY9$uuJh^7Fl$qUZ63A_6OBKw{zyJE|o%sJKAxpj)Y6cJ$m4TfD19p&Pp%Tbvu2gR&o7Dfggn6s~qfbN*wxzl1Hh zS8gpcJIf?2paPAqxG4+@SM4Jk@3i#%@&qsNZ|grRaR(ar%Kzi&YgyQ1qSa!9?5h16 z72L?6mIAFsqLoHzQIWhcK)qJ8T&aA%YFKVih!{YM#V;(mn_fgvUTE=YcaSyes zyEpjD^W_pxlT}~`gFgcW;eiV7P=HT_^r1yDd-)&keQy^tgS7qjXuv)J9&#a&mQe4-W^J6@FZ`PL7;l*y(lGh%Th!yqwlg5( z9IQf(i7v!K= z3WOodMe-*=xNw>Z1W5)(Z`u~a4^}C_r_~uyGvFLf(QVpLpZMFM$$MC(q*1sj5)`7la56Ff#Bc$>3+#yXAPd+&j2I?$-&H`PsEJaLUAR^8Mvjycdv z4Y<&o3UUWrRV_)O7^-dk6N~$;55k#6eXH1$r>?EkhBjko#W8l|qT#L27Cb zK4jp%)q?Oq10FK)N0MeqU$kv`QNt$Oe$49Lv%lrwoQDr1+tk~SJyLG;wTqVC`Tsxz zlbPX3DnaVkL5Yxk;A+e*LYp@rOLK z_v269$1PrNy!**(zXWQm3g$8>YY4cIts#OOY66f$4LEzg!~E$-(YtB^$3||<#>QxE zR-4WD@UixGkM|WjD1pk>z%LBylu7uc0bdxD*n>BI_bkH)#Yd9YOFhWYz&vL5lSvp4K%RmJFM!g;tQWHO`wZl-IoQwc4HVP-ap=m(l+Nk6 zOLIT3>OIr(?WIc>_xzrKysF!V9}AGq)x|j?j3$OIiKpl&ViEIb92I{y4ZV?>t+p+-wrn8fDHw1Pp0w?mH8ogC)2*~E5k$e#sM+Nrp-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-@VkHg|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_jkSIbg^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|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#K0mfa-_`&TF%ef8{ZRL_vHvFbS~l(-3m#rnyOtu!^5k5wO}qII$yg;5|^o_>50L%HT$zl#(x1bZ)~=J!ilYJhVt9J ztyGI-XW3m;0kX1Xu#4<4u}tB%_6{n!UTc;7;_N&1IvK_~gjg!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|>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}Hu2VcLXBntUxXjveX z;9NK_;?kRCl01yp!Y7Paq84!BF%>AV6iPlU&ij_pOxrdcHC+B8vsZi?x|LY7wEja9 zwjA-kkNNTS5~!yt_?$sK)(S$37Ccvk5@N7*zT3MTl@T$5Nub(`}fuEk#Z5-_-A(oaa!vm8gX|3`*=naqT&B%n_>IX+aJH z{~(!42vM;(ZDb24fgg`X4&@XaOIy$z-`-tXM8s1u~$zsnt(!-88P|sAqD4%>rHA5>1Ked4ThX4${*rvAti+9@OdR zGSpA4AZT!8q4VwbD@FySL}sEs*9*NiD3PKsH##@`YEG(}4<%KxG*`J?9a- zIgzc%i7B=GH{Gg{Wip;r^ZZq-#&59R&gI9mh(xrt!sp@c zGy+m6I&~LA9X-?eROX8pcvAJlMVw!~#L*7x^16+ChEmJyZ)(+LHWDAb#rBHuQ-Qh+ zyqXSjp|%dxW#IKCSPC 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`{}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_sFreqa!<{*YFXb=!+cppDzGcPVz10t`-vOm*QS#8 zcb~n$yDHAixR~$)pVV!$Kxdw#?hC`*>-l&~qI6ORLK)4ACgBnl@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 zzGTcxJgUyYUT9!B4ZwR z*1wXz8Eujder8aXT0!`z1D_S32CL*yRU>xoN%Bp?v8Q6L)Qx{S@2lE(I1i8nF3Ey=fk3oq&cz-lxNX47a@w!P9sy@B+3T1rG*knBX1f?b( zev({5n&t0w5SY~0@GUe`>HufU*nQ+hEyRB4F~ab8~p z@-ip2{6dFDUbdp 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>CUi7~7w0i?zEbSmUIfq*XDNSTn^=4g&Z(<9@H1sXf;xbQF zN10wnvts0)1+iXnmAot;n9KUxHJC>HrP*3=PCve6^quXu9^f&3-WwQsp zsg${njQ5fbIn%e*mm#;WA-lCxmM`$mLAhI|ICQFV20d-o=#Hv^v_onk9L8KMs{>pZ zYDNUPixstUsHlLnw#U9kqoI!7O3x)v=DZmPh9B*I6y@0U9eoi1Y 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`*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-l0$+4T{EKLvcM~DO&kZ=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+KXdEyyU76W)pipq{M=Jy8vJEJ(K9V5N!))XCjd;$d(DmWMeA9wIFpK z#Fi6d;4Ikh&Gx4?7No|JFqjHlNf}LA4~AL5iCY^7S`z;cHn-T(jq diff --git a/Tools/ArdupilotMegaPlanner/georefimage.cs b/Tools/ArdupilotMegaPlanner/georefimage.cs index 17c166f02e..21b6374671 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 8e87811847..2d90d5f5d0 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 767443ebc4..1f5e4d0834 100644 --- a/Tools/ArdupilotMegaPlanner/temp.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/temp.Designer.cs @@ -28,26 +28,26 @@ /// 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 219e468aec..28e7bb4dc2 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 5f282702bb..0000000000 --- a/Tools/ArdupilotMegaPlanner/test.cs +++ /dev/null @@ -1 +0,0 @@ - \ No newline at end of file