From 25bcfdd1e7bf0c135a538a3d9dc0b337ad2f4866 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Thu, 20 Sep 2012 07:37:36 +0800 Subject: [PATCH] Mission Planner 1.2.12 add arduino chip detect fix apm2,2.5 dialog test add write timeout. this will stop planner hangs on bad serial devices. change quickview decimal places to 0.00 fix map clicking issue. fix wind direction wrapping add airspeed use modify firmware screen from Marooned major flightdata tab change. add save/load polygon from file add some error handling dialogs --- .../Arduino/ArduinoComms.cs | 114 +- .../Arduino/ArduinoDetect.cs | 4 +- .../Arduino/ArduinoSTK.cs | 39 +- .../Arduino/ArduinoSTKv2.cs | 35 +- .../ArdupilotMegaPlanner/ArdupilotMega.csproj | 311 +- Tools/ArdupilotMegaPlanner/Common.cs | 11 +- Tools/ArdupilotMegaPlanner/Comms/CommsFile.cs | 56 + .../Comms/CommsSerialPort.cs | 3 + .../Controls/BackstageView/BackstageView.cs | 27 +- Tools/ArdupilotMegaPlanner/Controls/HSI.cs | 6 +- Tools/ArdupilotMegaPlanner/Controls/HUD.cs | 17 +- .../Controls/LabelWithPseudoOpacity.cs | 12 + .../Controls/MainSwitcher.cs | 2 +- .../Controls/QuickView.Designer.cs | 48 +- .../Controls/QuickView.cs | 38 +- Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs | 14 + Tools/ArdupilotMegaPlanner/CurrentState.cs | 2 +- .../ConfigFailSafe.Designer.cs | 380 ++ .../ConfigurationView/ConfigFailSafe.cs | 53 + .../ConfigFailSafe.es-ES.resx | 315 ++ .../ConfigurationView/ConfigFailSafe.fr.resx | 312 ++ .../ConfigFailSafe.it-IT.resx | 318 ++ .../ConfigurationView/ConfigFailSafe.pl.resx | 318 ++ .../ConfigurationView/ConfigFailSafe.resx | 678 +++ .../ConfigFailSafe.zh-Hans.resx | 169 + .../ConfigFailSafe.zh-TW.resx | 460 ++ .../ConfigHardwareOptions.Designer.cs | 45 +- .../ConfigHardwareOptions.cs | 26 +- .../ConfigHardwareOptions.resx | 94 +- .../GCSViews/ConfigurationView/ConfigMount.cs | 4 +- .../ConfigurationView/ConfigMount.designer.cs | 206 +- .../ConfigurationView/ConfigMount.resx | 2586 ++++----- .../ConfigurationView/ConfigRadioInput.cs | 2 +- .../GCSViews/ConfigurationView/Setup.cs | 29 +- .../ConfigurationView/SetupFresh.Designer.cs | 60 + .../GCSViews/ConfigurationView/SetupFresh.cs | 110 + .../ConfigurationView/SetupFresh.resx | 120 + .../GCSViews/Firmware.Designer.cs | 34 +- .../ArdupilotMegaPlanner/GCSViews/Firmware.cs | 74 +- .../GCSViews/Firmware.resx | 154 +- .../GCSViews/FlightData.Designer.cs | 167 +- .../GCSViews/FlightData.cs | 514 +- .../GCSViews/FlightData.resx | 334 +- .../GCSViews/FlightPlanner.Designer.cs | 104 +- .../GCSViews/FlightPlanner.cs | 138 +- .../GCSViews/FlightPlanner.resx | 693 ++- .../GCSViews/Simulation.cs | 4 +- Tools/ArdupilotMegaPlanner/HIL/AeroSimRC.cs | 11 + Tools/ArdupilotMegaPlanner/HIL/FlightGear.cs | 11 + Tools/ArdupilotMegaPlanner/HIL/Hil.cs | 93 + Tools/ArdupilotMegaPlanner/HIL/JSBSim.cs | 11 + Tools/ArdupilotMegaPlanner/HIL/XPlane.cs | 360 ++ Tools/ArdupilotMegaPlanner/MainV2.cs | 42 +- Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs | 213 +- Tools/ArdupilotMegaPlanner/Msi/installer.wxs | 313 +- Tools/ArdupilotMegaPlanner/OpenGLtest.cs | 377 ++ Tools/ArdupilotMegaPlanner/OpenGLtest.resx | 120 + Tools/ArdupilotMegaPlanner/Program.cs | 112 +- .../Properties/AssemblyInfo.cs | 2 +- .../Properties/Resources.Designer.cs | 14 + .../Properties/Resources.resx | 8 +- .../Radio/3DRradio.Designer.cs | 115 +- .../ArdupilotMegaPlanner/Radio/3DRradio.resx | 4870 ++++++++--------- .../Utilities/CaptureMJPEG.cs | 202 +- 64 files changed, 10704 insertions(+), 5410 deletions(-) create mode 100644 Tools/ArdupilotMegaPlanner/Comms/CommsFile.cs create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.Designer.cs create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.es-ES.resx create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.fr.resx create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.it-IT.resx create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.pl.resx create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.resx create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.zh-Hans.resx create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.zh-TW.resx create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.Designer.cs create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.cs create mode 100644 Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.resx create mode 100644 Tools/ArdupilotMegaPlanner/HIL/AeroSimRC.cs create mode 100644 Tools/ArdupilotMegaPlanner/HIL/FlightGear.cs create mode 100644 Tools/ArdupilotMegaPlanner/HIL/Hil.cs create mode 100644 Tools/ArdupilotMegaPlanner/HIL/JSBSim.cs create mode 100644 Tools/ArdupilotMegaPlanner/HIL/XPlane.cs create mode 100644 Tools/ArdupilotMegaPlanner/OpenGLtest.cs create mode 100644 Tools/ArdupilotMegaPlanner/OpenGLtest.resx diff --git a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoComms.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoComms.cs index 9647491a74..d9959f62d0 100644 --- a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoComms.cs +++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoComms.cs @@ -1,38 +1,112 @@ using System; using System.Collections.Generic; +using System.Collections; using System.Text; using System.IO.Ports; using System.IO; namespace ArdupilotMega.Arduino { - public delegate void ProgressEventHandler(int progress,string status); + public delegate void ProgressEventHandler(int progress, string status); /// /// Arduino STK interface /// - interface ArduinoComms + public 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); + 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; + Chip getChipType(); + + 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; } + 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; } + } + + public class Chip + { + public string name = ""; + public byte sig1 = 0; + public byte sig2 = 0; + public byte sig3 = 0; + public uint size = 0; + + static bool creating = true; + + public static List chips = new List(); + + public static void Populate() + { + creating = false; + + chips.Clear(); + + chips.Add(new Chip("ATmega2561", 0x1e, 0x98, 0x02, 0x100U)); //128 words + chips.Add(new Chip("ATmega2560", 0x1e, 0x98, 0x01, 0x100U)); //128 words + chips.Add(new Chip("ATmega1280", 0x1e, 0x97, 0x03, 0x80U)); //128 words + chips.Add(new Chip("ATmega1281", 0x1e, 0x97, 0x04, 0x80U)); //128 words + chips.Add(new Chip("ATmega128", 0x1e, 0x97, 0x02, 0x80U)); //128 words + chips.Add(new Chip("ATmega64", 0x1e, 0x96, 0x02, 0x80U)); //128 words + chips.Add(new Chip("ATmega32", 0x1e, 0x95, 0x02, 0x40U)); //64 words + chips.Add(new Chip("ATmega16", 0x1e, 0x94, 0x03, 0x40U)); //64 words + chips.Add(new Chip("ATmega8", 0x1e, 0x93, 0x07, 0x20U)); //32 words + chips.Add(new Chip("ATmega88", 0x1e, 0x93, 0x0a, 0x20U)); //32 words + chips.Add(new Chip("ATmega168", 0x1e, 0x94, 0x06, 0x40U)); //64 words + chips.Add(new Chip("ATmega328P", 0x1e, 0x95, 0x0F, 0x40U)); //64 words + chips.Add(new Chip("ATmega162", 0x1e, 0x94, 0x04, 0x40U)); //64 words + chips.Add(new Chip("ATmega163", 0x1e, 0x94, 0x02, 0x40U)); //64 words + chips.Add(new Chip("ATmega169", 0x1e, 0x94, 0x05, 0x40U)); //64 words + chips.Add(new Chip("ATmega8515", 0x1e, 0x93, 0x06, 0x20U)); //32 words + chips.Add(new Chip("ATmega8535", 0x1e, 0x93, 0x08, 0x20U));//32 words + + foreach (Chip item in chips) + { + // Console.WriteLine(item); + } + } + + public Chip(string nm, byte s1, byte s2, byte s3, uint size) + { + if (chips.Count == 0 && creating) + Populate(); + + name = nm; + sig1 = s1; + sig2 = s2; + sig3 = s3; + this.size = size; + } + + public override string ToString() + { + return "Chip(" + name + ", " + sig1.ToString("X") + ", " + sig2.ToString("X") + ", " + sig3.ToString("X") + ", " + size + ")"; + } + + public override bool Equals(object obj) + { + Chip item = obj as Chip; + return (item.sig1 == this.sig1 && item.sig2 == this.sig2 && item.sig3 == this.sig3); + } + + public override int GetHashCode() + { + return base.GetHashCode(); + } } } diff --git a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoDetect.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoDetect.cs index 6c0199befa..015b015201 100644 --- a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoDetect.cs +++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoDetect.cs @@ -10,7 +10,7 @@ using ArdupilotMega.Utilities; namespace ArdupilotMega.Arduino { - class ArduinoDetect + public class ArduinoDetect { private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType); /// @@ -203,7 +203,7 @@ namespace ArdupilotMega.Arduino } else { - if (DialogResult.Yes == CustomMessageBox.Show("Is this a APM 2?", "APM 2", MessageBoxButtons.YesNo)) + if (DialogResult.Yes == CustomMessageBox.Show("Is this a APM 2+?", "APM 2+", MessageBoxButtons.YesNo)) { return "2560-2"; } diff --git a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs index e2665799b3..163be54070 100644 --- a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs +++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs @@ -11,7 +11,7 @@ using ArdupilotMega.Comms; namespace ArdupilotMega.Arduino { - class ArduinoSTK : SerialPort, ArduinoComms + public class ArduinoSTK : SerialPort, ArduinoComms { private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType); public event ProgressEventHandler Progress; @@ -45,14 +45,14 @@ namespace ArdupilotMega.Arduino return false; } int a = 0; - while (a < 50) + while (a < 50) // 50 tries at 50 ms = 2.5sec { this.DiscardInBuffer(); this.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2); a++; Thread.Sleep(50); - log.InfoFormat("btr {0}", this.BytesToRead); + log.InfoFormat("connectap btr {0}", this.BytesToRead); if (this.BytesToRead >= 2) { byte b1 = (byte)this.ReadByte(); @@ -315,30 +315,39 @@ namespace ArdupilotMega.Arduino return true; } - public byte getChipType(byte part = 0) + public Chip getChipType() { - byte answer = 0x00; + byte sig1 = 0x00; + byte sig2 = 0x00; + byte sig3 = 0x00; - byte[] command = new byte[] { (byte)'V', 0x30, 0x01, part, 0x01, (byte)' ' }; + byte[] command = new byte[] { (byte)'u', (byte)' ' }; this.Write(command, 0, command.Length); - byte[] chr = new byte[1]; + System.Threading.Thread.Sleep(20); - this.Read(chr, 0, 1); + byte[] chr = new byte[5]; - if (chr[0] == 0x14) + int count = this.Read(chr, 0, 5); + log.Debug("getChipType read " + count); + + if (chr[0] == 0x14 && chr[4] == 0x10) { - this.Read(chr, 0, 1); - answer = (byte)chr[0]; + sig1 = (byte)chr[1]; + sig2 = (byte)chr[2]; + sig3 = (byte)chr[3]; + } - this.Read(chr, 0, 1); - if (chr[0] == 0x10) + foreach (Chip item in Arduino.Chip.chips) + { + if (item.Equals(new Chip("", sig1, sig2, sig3, 0))) { - return answer; + log.Debug("Match "+item.ToString()); + return item; } } - return answer; + return null; } public new bool Close() diff --git a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs index 81351906f4..0916360f7e 100644 --- a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs +++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs @@ -10,7 +10,7 @@ using log4net; namespace ArdupilotMega.Arduino { - class ArduinoSTKv2 : SerialPort,ArduinoComms + public class ArduinoSTKv2 : SerialPort,ArduinoComms { private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType); public event ProgressEventHandler Progress; @@ -368,6 +368,39 @@ namespace ArdupilotMega.Arduino return true; } + public Chip getChipType() + { + byte sig1 = 0x00; + byte sig2 = 0x00; + byte sig3 = 0x00; + + byte[] command = new byte[] { (byte)0x1b, 0, 0, 0, 0 }; + command = this.genstkv2packet(command); + + sig1 = command[2]; + + command = new byte[] { (byte)0x1b, 0, 0, 0, 1 }; + command = this.genstkv2packet(command); + + sig2 = command[2]; + + command = new byte[] { (byte)0x1b, 0, 0, 0, 2 }; + command = this.genstkv2packet(command); + + sig3 = command[2]; + + foreach (Chip item in Arduino.Chip.chips) + { + if (item.Equals(new Chip("", sig1, sig2, sig3, 0))) + { + log.Debug("Match " + item.ToString()); + return item; + } + } + + return null; + } + public new bool Close() { try diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index bc9aa08dc8..3ebd1006a7 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -133,6 +133,10 @@ + + False + ..\..\..\..\..\Desktop\DIYDrones\crom.controls.dock\src\Crom.Controls\bin\Debug\Crom.Controls.dll + @@ -160,7 +164,7 @@ False - False + True @@ -240,15 +244,83 @@ Tracker.cs + + + + Component + + + Component + + Component + + UserControl + + + UserControl + + + BackstageView.cs + + + Component + + + UserControl + + + Component + + + UserControl + + + ConfigPanel.cs + + + UserControl + + + ConnectionControl.cs + + + UserControl + + + ConnectionStats.cs + + + + UserControl + + + HSI.cs + + + UserControl + + + + UserControl + + + ImageLabel.cs + + + Component + + + UserControl + UserControl @@ -264,12 +336,74 @@ Component + + Component + + + UserControl + + + Component + + + Component + + + UserControl + + + Component + + + Form + + + ProgressReporterDialogue.cs + + UserControl QuickView.cs + + UserControl + + + RangeControl.cs + + + Component + + + UserControl + + + ValuesControl.cs + + + Code + + + + UserControl + + + ConfigFailSafe.cs + + + UserControl + + + SetupFresh.cs + + + + + + UserControl + Form @@ -292,23 +426,6 @@ - - UserControl - - - HSI.cs - - - - Component - - - UserControl - - - Component - - UserControl @@ -322,18 +439,6 @@ ConfigFriendlyParams.cs - - UserControl - - - RangeControl.cs - - - UserControl - - - ValuesControl.cs - UserControl @@ -344,52 +449,6 @@ - - UserControl - - - BackstageView.cs - - - Component - - - UserControl - - - Component - - - UserControl - - - ConnectionControl.cs - - - UserControl - - - ConfigPanel.cs - - - UserControl - - - ConnectionStats.cs - - - - UserControl - - - Form - - - ProgressReporterDialogue.cs - - - Component - UserControl @@ -471,10 +530,6 @@ 3DRradio.cs - - UserControl - - Form @@ -483,15 +538,6 @@ Camera.cs - - UserControl - - - ImageLabel.cs - - - UserControl - @@ -540,22 +586,9 @@ JoystickSetup.cs - - Component - Component - - - Component - - - UserControl - - - Component - Form @@ -580,9 +613,6 @@ Terminal.cs - - UserControl - Form @@ -604,9 +634,6 @@ Simulation.cs - - Component - @@ -616,9 +643,6 @@ ElevationProfile.cs - - Component - Form @@ -671,33 +695,72 @@ Camera.cs + + AGauge.cs + BackstageView.cs - - ConnectionControl.cs - ConfigPanel.cs + + ConnectionControl.cs + ConnectionStats.cs HSI.cs + + ImageLabel.cs + MainSwitcher.cs ProgressReporterDialogue.cs - - OpenGLtest.cs - QuickView.cs + + RangeControl.cs + + + ValuesControl.cs + + + ConfigMount.cs + + + ConfigFailSafe.cs + + + ConfigFailSafe.cs + + + ConfigFailSafe.cs + + + ConfigFailSafe.cs + + + ConfigFailSafe.cs + + + ConfigFailSafe.cs + + + ConfigFailSafe.cs + + + SetupFresh.cs + + + OpenGLtest.cs + SerialOutput2.cs @@ -869,12 +932,6 @@ ConfigAccelerometerCalibrationPlane.cs - - RangeControl.cs - - - ValuesControl.cs - ConfigArdurover.cs @@ -890,16 +947,9 @@ 3DRradio.cs - - AGauge.cs - Designer - Camera.cs - - ImageLabel.cs - Firmware.cs @@ -1330,7 +1380,6 @@ true - "$(TargetDir)version.exe" "$(TargetPath)" > "$(TargetDir)version.txt" diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs index bd302abd24..2751b8911c 100644 --- a/Tools/ArdupilotMegaPlanner/Common.cs +++ b/Tools/ArdupilotMegaPlanner/Common.cs @@ -1112,6 +1112,7 @@ System.ComponentModel.Description("Text under Bar")] int _min = 0; int _max = 0; int _value = 0; + bool ctladded = false; System.Windows.Forms.Label lbl1 = new System.Windows.Forms.Label(); System.Windows.Forms.Label lbl = new System.Windows.Forms.Label(); @@ -1144,6 +1145,13 @@ System.ComponentModel.Description("Text under Bar")] drawlbl(); base.Value = ans; drawlbl(); + + if (this.Parent != null && ctladded == false) + { + this.Parent.Controls.Add(lbl); + this.Parent.Controls.Add(lbl1); + ctladded = true; + } } } @@ -1164,10 +1172,11 @@ System.ComponentModel.Description("Text under Bar")] if (this.DesignMode) return; - if (this.Parent != null) + if (this.Parent != null && ctladded == false) { this.Parent.Controls.Add(lbl); this.Parent.Controls.Add(lbl1); + ctladded = true; } } } diff --git a/Tools/ArdupilotMegaPlanner/Comms/CommsFile.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsFile.cs new file mode 100644 index 0000000000..54b29d2b40 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Comms/CommsFile.cs @@ -0,0 +1,56 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; +using System.IO.Ports; +using System.IO; + +namespace ArdupilotMega.Comms +{ + public class CommsFile : ICommsSerial + { + // Methods + public void Close() { BaseStream.Close(); } + public void DiscardInBuffer() { } + //void DiscardOutBuffer(); + public void Open() + { + BaseStream = File.OpenRead(PortName); + } + public int Read(byte[] buffer, int offset, int count) + { + return BaseStream.Read(buffer, offset, count); + } + //int Read(char[] buffer, int offset, int count); + public int ReadByte() { return BaseStream.ReadByte(); } + public int ReadChar() { return BaseStream.ReadByte(); } + public string ReadExisting() { return ""; } + public string ReadLine() { return ""; } + //string ReadTo(string value); + public void Write(string text) { } + public void Write(byte[] buffer, int offset, int count) { } + //void Write(char[] buffer, int offset, int count); + public void WriteLine(string text) { } + + public void toggleDTR() { } + + // Properties + public Stream BaseStream { get; private set; } + public int BaudRate { get; set; } + public int BytesToRead { get { return (int)(BaseStream.Length - BaseStream.Position); } } + public int BytesToWrite { get; set; } + public int DataBits { get; set; } + public bool DtrEnable { get; set; } + public bool IsOpen { get { return (BaseStream != null); } } + + public Parity Parity { get; set; } + + public string PortName { get; set; } + public int ReadBufferSize { get; set; } + public int ReadTimeout { get; set; } + public bool RtsEnable { get; set; } + public StopBits StopBits { get; set; } + public int WriteBufferSize { get; set; } + public int WriteTimeout { get; set; } + } +} diff --git a/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs index 41088c0211..bf0995fbcf 100644 --- a/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs +++ b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs @@ -11,6 +11,9 @@ namespace ArdupilotMega.Comms { public new void Open() { + // 500ms write timeout - win32 api default + this.WriteTimeout = 500; + if (base.IsOpen) return; diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs index c5f1d1dbe4..2fbb2c241f 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs @@ -145,9 +145,9 @@ namespace ArdupilotMega.Controls.BackstageView /// /// Add a page (tab) to this backstage view. Will be added at the end/bottom /// - public void AddPage(UserControl userControl, string headerText) + public BackstageViewPage AddPage(UserControl userControl, string headerText, BackstageViewPage Parent) { - var page = new BackstageViewPage(userControl, headerText) + var page = new BackstageViewPage(userControl, headerText, Parent) { Page = { @@ -171,6 +171,8 @@ namespace ArdupilotMega.Controls.BackstageView ActivatePage(page); } + + return page; } /// @@ -196,7 +198,8 @@ namespace ArdupilotMega.Controls.BackstageView SelectedTextColor = _selectedTextColor, UnSelectedTextColor = _unSelectedTextColor, HighlightColor1 = _highlightColor1, - HighlightColor2 = _highlightColor2 + HighlightColor2 = _highlightColor2, + // Dock = DockStyle.Bottom }; pnlMenu.Controls.Add(lnkButton); @@ -322,6 +325,9 @@ namespace ArdupilotMega.Controls.BackstageView if (popoutPage != null && popoutPage == page) continue; + if (page is BackstageViewSpacer) + continue; + if (((BackstageViewPage)page).Page is IDeactivate) { ((IDeactivate)((BackstageViewPage)(page)).Page).Deactivate(); @@ -335,7 +341,7 @@ namespace ArdupilotMega.Controls.BackstageView public abstract class BackstageViewItem { - public abstract int Spacing { get; } + public abstract int Spacing { get; set; } } /// @@ -355,6 +361,7 @@ namespace ArdupilotMega.Controls.BackstageView public override int Spacing { get { return _spacing; } + set { _spacing = value; } } } @@ -363,11 +370,12 @@ namespace ArdupilotMega.Controls.BackstageView /// Data structure to hold information about a 'tab' in the /// public class BackstageViewPage : BackstageViewItem - { - public BackstageViewPage(UserControl page, string linkText) + { + public BackstageViewPage(UserControl page, string linkText, BackstageViewPage parent) { Page = page; LinkText = linkText; + Parent = parent; } /// @@ -380,9 +388,14 @@ namespace ArdupilotMega.Controls.BackstageView /// public string LinkText { get; set; } + public BackstageViewPage Parent { get; internal set; } + + private int _spaceoverride = -1; + public override int Spacing { - get { return ButtonSpacing; } + get { if (_spaceoverride != -1) return _spaceoverride; return ButtonSpacing; } + set { _spaceoverride = value; } } } } diff --git a/Tools/ArdupilotMegaPlanner/Controls/HSI.cs b/Tools/ArdupilotMegaPlanner/Controls/HSI.cs index 48642745a3..a8c4237138 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/HSI.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/HSI.cs @@ -36,6 +36,8 @@ namespace ArdupilotMega.Controls /// public new void Invalidate() { + if (Disposing) + return; if (!ThisReallyVisible()) { return; @@ -50,8 +52,8 @@ namespace ArdupilotMega.Controls /// public bool ThisReallyVisible() { - Control ctl = Control.FromHandle(this.Handle); - return ctl.Visible; + //Control ctl = Control.FromHandle(this.Handle); + return this.Visible; } public HSI() diff --git a/Tools/ArdupilotMegaPlanner/Controls/HUD.cs b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs index 33f1ae38ec..76b2dcccf9 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/HUD.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs @@ -56,6 +56,8 @@ namespace ArdupilotMega.Controls //return; } + this.Name = "Hud"; + //InitializeComponent(); graphicsObject = this; @@ -367,8 +369,8 @@ namespace ArdupilotMega.Controls { countdate = DateTime.Now; Console.WriteLine("HUD " + count + " hz drawtime " + (huddrawtime / count) + " gl " + opengl); - // if ((huddrawtime / count) > 1000) - // opengl = false; + if ((huddrawtime / count) > 1000) + opengl = false; count = 0; huddrawtime = 0; @@ -1754,12 +1756,16 @@ namespace ArdupilotMega.Controls if (SixteenXNine) { - this.Height = (int)(this.Width / 1.777f); + int ht = (int)(this.Width / 1.777f); + if (ht != this.Height) + this.Height = ht; } else { // 4x3 - this.Height = (int)(this.Width / 1.333f); + int ht = (int)(this.Width / 1.333f); + if (ht != this.Height) + this.Height = ht; } base.OnResize(e); @@ -1799,7 +1805,8 @@ namespace ArdupilotMega.Controls } } catch { } - + + Refresh(); } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Controls/LabelWithPseudoOpacity.cs b/Tools/ArdupilotMegaPlanner/Controls/LabelWithPseudoOpacity.cs index 1617f2110d..e8a53e1b22 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/LabelWithPseudoOpacity.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/LabelWithPseudoOpacity.cs @@ -44,5 +44,17 @@ namespace ArdupilotMega.Controls base.OnPaint(pe); this.CoverWithRect(pe.Graphics, Opacity); } + + public new bool DoubleBuffered + { + get + { + return base.DoubleBuffered; + } + set + { + base.DoubleBuffered = value; + } + } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Controls/MainSwitcher.cs b/Tools/ArdupilotMegaPlanner/Controls/MainSwitcher.cs index a3425f3129..63d6544fdd 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/MainSwitcher.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/MainSwitcher.cs @@ -14,7 +14,7 @@ namespace ArdupilotMega.Controls public partial class MainSwitcher : UserControl { public List screens = new List(); - Screen current; + public Screen current; public MainSwitcher() { diff --git a/Tools/ArdupilotMegaPlanner/Controls/QuickView.Designer.cs b/Tools/ArdupilotMegaPlanner/Controls/QuickView.Designer.cs index 38991fb957..4a194d8dfb 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/QuickView.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/QuickView.Designer.cs @@ -29,8 +29,8 @@ private void InitializeComponent() { this.labelWithPseudoOpacity1 = new ArdupilotMega.Controls.LabelWithPseudoOpacity(); - this.labelWithPseudoOpacity2 = new ArdupilotMega.Controls.LabelWithPseudoOpacity(); this.tableLayoutPanel1 = new System.Windows.Forms.TableLayoutPanel(); + this.labelWithPseudoOpacity2 = new ArdupilotMega.Controls.LabelWithPseudoOpacity(); this.tableLayoutPanel1.SuspendLayout(); this.SuspendLayout(); // @@ -38,49 +38,49 @@ // this.labelWithPseudoOpacity1.AutoSize = true; this.labelWithPseudoOpacity1.Dock = System.Windows.Forms.DockStyle.Fill; - this.labelWithPseudoOpacity1.Font = new System.Drawing.Font("Microsoft Sans Serif", 18F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); + this.labelWithPseudoOpacity1.DoubleBuffered = true; + this.labelWithPseudoOpacity1.Font = new System.Drawing.Font("Microsoft Sans Serif", 9.75F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); this.labelWithPseudoOpacity1.Location = new System.Drawing.Point(3, 0); this.labelWithPseudoOpacity1.Name = "labelWithPseudoOpacity1"; - this.labelWithPseudoOpacity1.Size = new System.Drawing.Size(161, 50); + this.labelWithPseudoOpacity1.Size = new System.Drawing.Size(118, 20); this.labelWithPseudoOpacity1.TabIndex = 0; this.labelWithPseudoOpacity1.Text = "Altitude:"; this.labelWithPseudoOpacity1.TextAlign = System.Drawing.ContentAlignment.MiddleCenter; // - // labelWithPseudoOpacity2 - // - this.labelWithPseudoOpacity2.AutoSize = true; - this.labelWithPseudoOpacity2.Dock = System.Windows.Forms.DockStyle.Fill; - this.labelWithPseudoOpacity2.Font = new System.Drawing.Font("Microsoft Sans Serif", 36F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); - this.labelWithPseudoOpacity2.Location = new System.Drawing.Point(170, 0); - this.labelWithPseudoOpacity2.Name = "labelWithPseudoOpacity2"; - this.labelWithPseudoOpacity2.Size = new System.Drawing.Size(162, 50); - this.labelWithPseudoOpacity2.TabIndex = 1; - this.labelWithPseudoOpacity2.Text = "0.0"; - this.labelWithPseudoOpacity2.TextAlign = System.Drawing.ContentAlignment.MiddleCenter; - // // tableLayoutPanel1 // - this.tableLayoutPanel1.ColumnCount = 2; - this.tableLayoutPanel1.ColumnStyles.Add(new System.Windows.Forms.ColumnStyle(System.Windows.Forms.SizeType.Percent, 50F)); - this.tableLayoutPanel1.ColumnStyles.Add(new System.Windows.Forms.ColumnStyle(System.Windows.Forms.SizeType.Percent, 50F)); - this.tableLayoutPanel1.Controls.Add(this.labelWithPseudoOpacity2, 1, 0); + this.tableLayoutPanel1.ColumnCount = 1; + this.tableLayoutPanel1.ColumnStyles.Add(new System.Windows.Forms.ColumnStyle()); + this.tableLayoutPanel1.Controls.Add(this.labelWithPseudoOpacity2, 0, 1); this.tableLayoutPanel1.Controls.Add(this.labelWithPseudoOpacity1, 0, 0); this.tableLayoutPanel1.Dock = System.Windows.Forms.DockStyle.Fill; this.tableLayoutPanel1.Location = new System.Drawing.Point(0, 0); this.tableLayoutPanel1.Name = "tableLayoutPanel1"; - this.tableLayoutPanel1.RowCount = 1; + this.tableLayoutPanel1.RowCount = 2; + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 20F)); this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Percent, 100F)); - this.tableLayoutPanel1.Size = new System.Drawing.Size(335, 50); + this.tableLayoutPanel1.Size = new System.Drawing.Size(122, 72); this.tableLayoutPanel1.TabIndex = 2; // + // labelWithPseudoOpacity2 + // + this.labelWithPseudoOpacity2.Dock = System.Windows.Forms.DockStyle.Fill; + this.labelWithPseudoOpacity2.DoubleBuffered = true; + this.labelWithPseudoOpacity2.Font = new System.Drawing.Font("Microsoft Sans Serif", 21.75F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); + this.labelWithPseudoOpacity2.Location = new System.Drawing.Point(3, 20); + this.labelWithPseudoOpacity2.Name = "labelWithPseudoOpacity2"; + this.labelWithPseudoOpacity2.Size = new System.Drawing.Size(118, 52); + this.labelWithPseudoOpacity2.TabIndex = 2; + this.labelWithPseudoOpacity2.Text = "000.00"; + this.labelWithPseudoOpacity2.TextAlign = System.Drawing.ContentAlignment.MiddleCenter; + // // QuickView // this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; this.Controls.Add(this.tableLayoutPanel1); - this.MinimumSize = new System.Drawing.Size(100, 27); this.Name = "QuickView"; - this.Size = new System.Drawing.Size(335, 50); + this.Size = new System.Drawing.Size(122, 72); this.tableLayoutPanel1.ResumeLayout(false); this.tableLayoutPanel1.PerformLayout(); this.ResumeLayout(false); @@ -90,7 +90,7 @@ #endregion private LabelWithPseudoOpacity labelWithPseudoOpacity1; - private LabelWithPseudoOpacity labelWithPseudoOpacity2; private System.Windows.Forms.TableLayoutPanel tableLayoutPanel1; + private LabelWithPseudoOpacity labelWithPseudoOpacity2; } } diff --git a/Tools/ArdupilotMegaPlanner/Controls/QuickView.cs b/Tools/ArdupilotMegaPlanner/Controls/QuickView.cs index 78295aae74..4ab0911001 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/QuickView.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/QuickView.cs @@ -14,7 +14,15 @@ namespace ArdupilotMega.Controls [System.ComponentModel.Browsable(true)] public string desc { get { return labelWithPseudoOpacity1.Text; } set { if (labelWithPseudoOpacity1.Text == value) return; labelWithPseudoOpacity1.Text = value; } } [System.ComponentModel.Browsable(true)] - public string number { get { return labelWithPseudoOpacity2.Text; } set { if (labelWithPseudoOpacity2.Text == value) return; labelWithPseudoOpacity2.Text = value; } } + public double number { get { return double.Parse(labelWithPseudoOpacity2.Text); } + set { + string ans = (value).ToString("0.00"); + if (labelWithPseudoOpacity2.Text == ans) + return; + labelWithPseudoOpacity2.Text = ans; + GetFontSize(); + } + } [System.ComponentModel.Browsable(true)] public Color numberColor { get { return labelWithPseudoOpacity2.ForeColor; } set { if (labelWithPseudoOpacity2.ForeColor == value) return; labelWithPseudoOpacity2.ForeColor = value; } } @@ -24,6 +32,8 @@ namespace ArdupilotMega.Controls labelWithPseudoOpacity1.DoubleClick += new EventHandler(labelWithPseudoOpacity1_DoubleClick); labelWithPseudoOpacity2.DoubleClick += new EventHandler(labelWithPseudoOpacity2_DoubleClick); + + labelWithPseudoOpacity2.DoubleBuffered = true; } void labelWithPseudoOpacity2_DoubleClick(object sender, EventArgs e) @@ -54,10 +64,32 @@ namespace ArdupilotMega.Controls base.OnPaint(e); } + void GetFontSize() + { + + Size extent = TextRenderer.MeasureText(labelWithPseudoOpacity2.Text, this.Font); + + float hRatio = (this.Height) / (float)extent.Height; + float wRatio = this.Width / (float)extent.Width; + float ratio = (hRatio < wRatio) ? hRatio : wRatio; + + float newSize = this.Font.Size * ratio; + + if (newSize < 8) + newSize = 8; + + //return newSize; + + labelWithPseudoOpacity2.Font = new Font(labelWithPseudoOpacity2.Font.FontFamily, newSize - 2, labelWithPseudoOpacity2.Font.Style); + + extent = TextRenderer.MeasureText(labelWithPseudoOpacity2.Text, labelWithPseudoOpacity2.Font); + } + protected override void OnResize(EventArgs e) { - if (this.Height > 20) - labelWithPseudoOpacity2.Font = new Font(labelWithPseudoOpacity2.Font.FontFamily, this.Height * 0.7f); + this.ResizeRedraw = true; + + GetFontSize(); base.OnResize(e); } diff --git a/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs b/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs index f24440fb59..2daba901e3 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs @@ -12,6 +12,14 @@ namespace ArdupilotMega.Controls { public bool inOnPaint = false; string otherthread = ""; + int lastx = 0; + int lasty = 0; + + public myGMAP() + : base() + { + this.Text = "Map"; + } protected override void OnPaint(System.Windows.Forms.PaintEventArgs e) { @@ -38,6 +46,12 @@ namespace ArdupilotMega.Controls { try { + if (e.X == lastx && e.Y == lasty) + return; + + lastx = e.X; + lasty = e.Y; + base.OnMouseMove(e); } catch (Exception ex) { Console.WriteLine(ex.ToString()); } diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs index 8d921b06aa..391a30e293 100644 --- a/Tools/ArdupilotMegaPlanner/CurrentState.cs +++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs @@ -480,7 +480,7 @@ namespace ArdupilotMega gotwind = true; - wind_dir = wind.direction; + wind_dir = (wind.direction + 360) % 360; wind_vel = wind.speed; //MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] = null; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.Designer.cs new file mode 100644 index 0000000000..b57b30a3d1 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.Designer.cs @@ -0,0 +1,380 @@ +namespace ArdupilotMega.GCSViews.ConfigurationView +{ + partial class ConfigFailSafe + { + /// + /// 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.components = new System.ComponentModel.Container(); + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigFailSafe)); + this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components); + this.label2 = new System.Windows.Forms.Label(); + this.label1 = new System.Windows.Forms.Label(); + this.horizontalProgressBar9 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar10 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar11 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar12 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar13 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar14 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar15 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar16 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar8 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar7 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar6 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar5 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar4 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar3 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar2 = new ArdupilotMega.HorizontalProgressBar(); + this.horizontalProgressBar1 = new ArdupilotMega.HorizontalProgressBar(); + this.lbl_currentmode = new System.Windows.Forms.Label(); + this.mavlinkCheckBox1 = new ArdupilotMega.Controls.MavlinkCheckBox(); + this.mavlinkNumericUpDown1 = new ArdupilotMega.Controls.MavlinkNumericUpDown(); + ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown1)).BeginInit(); + this.SuspendLayout(); + // + // currentStateBindingSource + // + this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState); + // + // label2 + // + resources.ApplyResources(this.label2, "label2"); + this.label2.Name = "label2"; + // + // label1 + // + resources.ApplyResources(this.label1, "label1"); + this.label1.Name = "label1"; + // + // horizontalProgressBar9 + // + this.horizontalProgressBar9.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch8out", true)); + resources.ApplyResources(this.horizontalProgressBar9, "horizontalProgressBar9"); + this.horizontalProgressBar9.Label = "Radio 8"; + this.horizontalProgressBar9.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar9.Maximum = 2000; + this.horizontalProgressBar9.maxline = 0; + this.horizontalProgressBar9.Minimum = 1000; + this.horizontalProgressBar9.minline = 0; + this.horizontalProgressBar9.Name = "horizontalProgressBar9"; + this.horizontalProgressBar9.Step = 1; + this.horizontalProgressBar9.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar10 + // + this.horizontalProgressBar10.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch7out", true)); + resources.ApplyResources(this.horizontalProgressBar10, "horizontalProgressBar10"); + this.horizontalProgressBar10.Label = "Radio 7"; + this.horizontalProgressBar10.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar10.Maximum = 2000; + this.horizontalProgressBar10.maxline = 0; + this.horizontalProgressBar10.Minimum = 1000; + this.horizontalProgressBar10.minline = 0; + this.horizontalProgressBar10.Name = "horizontalProgressBar10"; + this.horizontalProgressBar10.Step = 1; + this.horizontalProgressBar10.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar11 + // + this.horizontalProgressBar11.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch6out", true)); + resources.ApplyResources(this.horizontalProgressBar11, "horizontalProgressBar11"); + this.horizontalProgressBar11.Label = "Radio 6"; + this.horizontalProgressBar11.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar11.Maximum = 2000; + this.horizontalProgressBar11.maxline = 0; + this.horizontalProgressBar11.Minimum = 1000; + this.horizontalProgressBar11.minline = 0; + this.horizontalProgressBar11.Name = "horizontalProgressBar11"; + this.horizontalProgressBar11.Step = 1; + this.horizontalProgressBar11.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar12 + // + this.horizontalProgressBar12.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch5out", true)); + resources.ApplyResources(this.horizontalProgressBar12, "horizontalProgressBar12"); + this.horizontalProgressBar12.Label = "Radio 5"; + this.horizontalProgressBar12.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar12.Maximum = 2000; + this.horizontalProgressBar12.maxline = 0; + this.horizontalProgressBar12.Minimum = 1000; + this.horizontalProgressBar12.minline = 0; + this.horizontalProgressBar12.Name = "horizontalProgressBar12"; + this.horizontalProgressBar12.Step = 1; + this.horizontalProgressBar12.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar13 + // + this.horizontalProgressBar13.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4out", true)); + resources.ApplyResources(this.horizontalProgressBar13, "horizontalProgressBar13"); + this.horizontalProgressBar13.Label = "Radio 4"; + this.horizontalProgressBar13.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar13.Maximum = 2000; + this.horizontalProgressBar13.maxline = 0; + this.horizontalProgressBar13.Minimum = 1000; + this.horizontalProgressBar13.minline = 0; + this.horizontalProgressBar13.Name = "horizontalProgressBar13"; + this.horizontalProgressBar13.Step = 1; + this.horizontalProgressBar13.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar14 + // + this.horizontalProgressBar14.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3out", true)); + resources.ApplyResources(this.horizontalProgressBar14, "horizontalProgressBar14"); + this.horizontalProgressBar14.Label = "Radio 3"; + this.horizontalProgressBar14.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar14.Maximum = 2000; + this.horizontalProgressBar14.maxline = 0; + this.horizontalProgressBar14.Minimum = 1000; + this.horizontalProgressBar14.minline = 0; + this.horizontalProgressBar14.Name = "horizontalProgressBar14"; + this.horizontalProgressBar14.Step = 1; + this.horizontalProgressBar14.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar15 + // + this.horizontalProgressBar15.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch1out", true)); + resources.ApplyResources(this.horizontalProgressBar15, "horizontalProgressBar15"); + this.horizontalProgressBar15.Label = "Radio 1"; + this.horizontalProgressBar15.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar15.Maximum = 2000; + this.horizontalProgressBar15.maxline = 0; + this.horizontalProgressBar15.Minimum = 1000; + this.horizontalProgressBar15.minline = 0; + this.horizontalProgressBar15.Name = "horizontalProgressBar15"; + this.horizontalProgressBar15.Step = 1; + this.horizontalProgressBar15.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar16 + // + this.horizontalProgressBar16.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch2out", true)); + resources.ApplyResources(this.horizontalProgressBar16, "horizontalProgressBar16"); + this.horizontalProgressBar16.Label = "Radio 2"; + this.horizontalProgressBar16.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar16.Maximum = 2000; + this.horizontalProgressBar16.maxline = 0; + this.horizontalProgressBar16.Minimum = 1000; + this.horizontalProgressBar16.minline = 0; + this.horizontalProgressBar16.Name = "horizontalProgressBar16"; + this.horizontalProgressBar16.Step = 1; + this.horizontalProgressBar16.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar8 + // + this.horizontalProgressBar8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch8in", true)); + resources.ApplyResources(this.horizontalProgressBar8, "horizontalProgressBar8"); + this.horizontalProgressBar8.Label = "Radio 8"; + this.horizontalProgressBar8.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar8.Maximum = 2000; + this.horizontalProgressBar8.maxline = 0; + this.horizontalProgressBar8.Minimum = 1000; + this.horizontalProgressBar8.minline = 0; + this.horizontalProgressBar8.Name = "horizontalProgressBar8"; + this.horizontalProgressBar8.Step = 1; + this.horizontalProgressBar8.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar7 + // + this.horizontalProgressBar7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch7in", true)); + resources.ApplyResources(this.horizontalProgressBar7, "horizontalProgressBar7"); + this.horizontalProgressBar7.Label = "Radio 7"; + this.horizontalProgressBar7.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar7.Maximum = 2000; + this.horizontalProgressBar7.maxline = 0; + this.horizontalProgressBar7.Minimum = 1000; + this.horizontalProgressBar7.minline = 0; + this.horizontalProgressBar7.Name = "horizontalProgressBar7"; + this.horizontalProgressBar7.Step = 1; + this.horizontalProgressBar7.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar6 + // + this.horizontalProgressBar6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch6in", true)); + resources.ApplyResources(this.horizontalProgressBar6, "horizontalProgressBar6"); + this.horizontalProgressBar6.Label = "Radio 6"; + this.horizontalProgressBar6.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar6.Maximum = 2000; + this.horizontalProgressBar6.maxline = 0; + this.horizontalProgressBar6.Minimum = 1000; + this.horizontalProgressBar6.minline = 0; + this.horizontalProgressBar6.Name = "horizontalProgressBar6"; + this.horizontalProgressBar6.Step = 1; + this.horizontalProgressBar6.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar5 + // + this.horizontalProgressBar5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch5in", true)); + resources.ApplyResources(this.horizontalProgressBar5, "horizontalProgressBar5"); + this.horizontalProgressBar5.Label = "Radio 5"; + this.horizontalProgressBar5.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar5.Maximum = 2000; + this.horizontalProgressBar5.maxline = 0; + this.horizontalProgressBar5.Minimum = 1000; + this.horizontalProgressBar5.minline = 0; + this.horizontalProgressBar5.Name = "horizontalProgressBar5"; + this.horizontalProgressBar5.Step = 1; + this.horizontalProgressBar5.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar4 + // + this.horizontalProgressBar4.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true)); + resources.ApplyResources(this.horizontalProgressBar4, "horizontalProgressBar4"); + this.horizontalProgressBar4.Label = "Radio 4"; + this.horizontalProgressBar4.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar4.Maximum = 2000; + this.horizontalProgressBar4.maxline = 0; + this.horizontalProgressBar4.Minimum = 1000; + this.horizontalProgressBar4.minline = 0; + this.horizontalProgressBar4.Name = "horizontalProgressBar4"; + this.horizontalProgressBar4.Step = 1; + this.horizontalProgressBar4.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar3 + // + this.horizontalProgressBar3.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true)); + resources.ApplyResources(this.horizontalProgressBar3, "horizontalProgressBar3"); + this.horizontalProgressBar3.Label = "Radio 3"; + this.horizontalProgressBar3.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar3.Maximum = 2000; + this.horizontalProgressBar3.maxline = 0; + this.horizontalProgressBar3.Minimum = 1000; + this.horizontalProgressBar3.minline = 0; + this.horizontalProgressBar3.Name = "horizontalProgressBar3"; + this.horizontalProgressBar3.Step = 1; + this.horizontalProgressBar3.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar2 + // + this.horizontalProgressBar2.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch1in", true)); + resources.ApplyResources(this.horizontalProgressBar2, "horizontalProgressBar2"); + this.horizontalProgressBar2.Label = "Radio 1"; + this.horizontalProgressBar2.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar2.Maximum = 2000; + this.horizontalProgressBar2.maxline = 0; + this.horizontalProgressBar2.Minimum = 1000; + this.horizontalProgressBar2.minline = 0; + this.horizontalProgressBar2.Name = "horizontalProgressBar2"; + this.horizontalProgressBar2.Step = 1; + this.horizontalProgressBar2.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // horizontalProgressBar1 + // + this.horizontalProgressBar1.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch2in", true)); + resources.ApplyResources(this.horizontalProgressBar1, "horizontalProgressBar1"); + this.horizontalProgressBar1.Label = "Radio 2"; + this.horizontalProgressBar1.MarqueeAnimationSpeed = 1; + this.horizontalProgressBar1.Maximum = 2000; + this.horizontalProgressBar1.maxline = 0; + this.horizontalProgressBar1.Minimum = 1000; + this.horizontalProgressBar1.minline = 0; + this.horizontalProgressBar1.Name = "horizontalProgressBar1"; + this.horizontalProgressBar1.Step = 1; + this.horizontalProgressBar1.Style = System.Windows.Forms.ProgressBarStyle.Continuous; + // + // lbl_currentmode + // + this.lbl_currentmode.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.currentStateBindingSource, "mode", true)); + resources.ApplyResources(this.lbl_currentmode, "lbl_currentmode"); + this.lbl_currentmode.Name = "lbl_currentmode"; + // + // mavlinkCheckBox1 + // + resources.ApplyResources(this.mavlinkCheckBox1, "mavlinkCheckBox1"); + this.mavlinkCheckBox1.Name = "mavlinkCheckBox1"; + this.mavlinkCheckBox1.OffValue = 0F; + this.mavlinkCheckBox1.OnValue = 1F; + this.mavlinkCheckBox1.param = null; + this.mavlinkCheckBox1.ParamName = null; + this.mavlinkCheckBox1.UseVisualStyleBackColor = true; + // + // mavlinkNumericUpDown1 + // + resources.ApplyResources(this.mavlinkNumericUpDown1, "mavlinkNumericUpDown1"); + this.mavlinkNumericUpDown1.Max = 1F; + this.mavlinkNumericUpDown1.Min = 0F; + this.mavlinkNumericUpDown1.Name = "mavlinkNumericUpDown1"; + this.mavlinkNumericUpDown1.param = null; + this.mavlinkNumericUpDown1.ParamName = null; + // + // ConfigFailSafe + // + resources.ApplyResources(this, "$this"); + this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.mavlinkNumericUpDown1); + this.Controls.Add(this.mavlinkCheckBox1); + this.Controls.Add(this.lbl_currentmode); + this.Controls.Add(this.label2); + this.Controls.Add(this.label1); + this.Controls.Add(this.horizontalProgressBar9); + this.Controls.Add(this.horizontalProgressBar10); + this.Controls.Add(this.horizontalProgressBar11); + this.Controls.Add(this.horizontalProgressBar12); + this.Controls.Add(this.horizontalProgressBar13); + this.Controls.Add(this.horizontalProgressBar14); + this.Controls.Add(this.horizontalProgressBar15); + this.Controls.Add(this.horizontalProgressBar16); + this.Controls.Add(this.horizontalProgressBar8); + this.Controls.Add(this.horizontalProgressBar7); + this.Controls.Add(this.horizontalProgressBar6); + this.Controls.Add(this.horizontalProgressBar5); + this.Controls.Add(this.horizontalProgressBar4); + this.Controls.Add(this.horizontalProgressBar3); + this.Controls.Add(this.horizontalProgressBar2); + this.Controls.Add(this.horizontalProgressBar1); + this.Name = "ConfigFailSafe"; + ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown1)).EndInit(); + this.ResumeLayout(false); + this.PerformLayout(); + + } + + #endregion + + private System.Windows.Forms.BindingSource currentStateBindingSource; + private System.Windows.Forms.Label label2; + private System.Windows.Forms.Label label1; + private HorizontalProgressBar horizontalProgressBar9; + private HorizontalProgressBar horizontalProgressBar10; + private HorizontalProgressBar horizontalProgressBar11; + private HorizontalProgressBar horizontalProgressBar12; + private HorizontalProgressBar horizontalProgressBar13; + private HorizontalProgressBar horizontalProgressBar14; + private HorizontalProgressBar horizontalProgressBar15; + private HorizontalProgressBar horizontalProgressBar16; + private HorizontalProgressBar horizontalProgressBar8; + private HorizontalProgressBar horizontalProgressBar7; + private HorizontalProgressBar horizontalProgressBar6; + private HorizontalProgressBar horizontalProgressBar5; + private HorizontalProgressBar horizontalProgressBar4; + private HorizontalProgressBar horizontalProgressBar3; + private HorizontalProgressBar horizontalProgressBar2; + private HorizontalProgressBar horizontalProgressBar1; + private System.Windows.Forms.Label lbl_currentmode; + private Controls.MavlinkCheckBox mavlinkCheckBox1; + private Controls.MavlinkNumericUpDown mavlinkNumericUpDown1; + } +} diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs new file mode 100644 index 0000000000..198b515600 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs @@ -0,0 +1,53 @@ +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; +using ArdupilotMega.Controls.BackstageView; +using ArdupilotMega.Controls; + +namespace ArdupilotMega.GCSViews.ConfigurationView +{ + public partial class ConfigFailSafe : UserControl, IActivate, IDeactivate + { + Timer timer = new Timer(); + + public ConfigFailSafe() + { + InitializeComponent(); + + mavlinkCheckBox1.setup(1, 0, "THR_FAILSAFE", MainV2.comPort.param); + mavlinkNumericUpDown1.setup(800, 1200, 1, 1, "THR_FS_VALUE", MainV2.comPort.param); + + // setup rc update + timer.Tick += new EventHandler(timer_Tick); + } + + public void Deactivate() + { + timer.Stop(); + } + + void timer_Tick(object sender, EventArgs e) + { + // update all linked controls - 10hz + try + { + MainV2.cs.UpdateCurrentSettings(currentStateBindingSource); + } + catch { } + } + + public void Activate() + { + timer.Enabled = true; + timer.Interval = 100; + timer.Start(); + + CustomMessageBox.Show("Ensure your props are not on the Plane/Quad","FailSafe",MessageBoxButtons.OK,MessageBoxIcon.Exclamation); + } + } +} diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.es-ES.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.es-ES.resx new file mode 100644 index 0000000000..70ad73f1af --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.es-ES.resx @@ -0,0 +1,315 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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 + + + 180 + + + Manual + + + PWM 0 - 1230 + + + PWM 1621 - 1749 + + + Modo actual: + + + Habilitar el flujo óptico + + + NOTA: Las imágenes son sólo para su presentación + + + Modo Simple + + + PWM 1750 + + + + Elevons CH1 Rev + + + PWM Actual: + + + APMSetup + + + Swash-Servo posición + + + Activar Compas + + + Modo Simple + + + ArduCopter2 + + + Modo Simple + + + Ajuste Chásis (+ or x) + + + 60 + + + 1 + + + Modo Simple + + + Modo Simple + + + 2 + + + Modos + + + Modo Simple + + + 3 + + + Reset + + + -60 + + + Superior + + + Swash de Viaje + + + Manual + + + Timón de Viaje + + + Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda. + + + Calibrar Radio + + + Max + + + Modo de Vuelo 2 + + + Alabeo Max + + + Modo de Vuelo 3 + + + Cabeceo Max + + + por ejemplo, en grados 2 ° 3 'W es -2,3 + + + Modo de Vuelo 1 + + + Nivel tu quad para establecer las compensaciones por defecto acel + + + Modo de Vuelo 6 + + + Capacidad + + + Declinación + + + Activar Sonar + + + PWM 1231 - 1360 + + + Entrada Radio + + + Calibración + + + 1500 + + + Modo de Vuelo 4 + + + Modo de Vuelo 5 + + + Gyro + + + PWM 1361 - 1490 + + + Hardware + + + PWM 1491 - 1620 + + + Sitio Web Declinación + + + 1500 + + + Batería + + + Cero + + + Activar Airspeed + + + 4500 + + + Restablecer los Ajustes de hardware APM + + + 1000 + + + Monitor + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.fr.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.fr.resx new file mode 100644 index 0000000000..1bd274beea --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.fr.resx @@ -0,0 +1,312 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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 + + + 180 + + + Manuel + + + PWM 0 - 1230 + + + PWM 1621 - 1749 + + + Mode Courant: + + + Activ. capteur optique + + + NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc... + + + Mode Simple + + + PWM 1750 + + + + Elevons CH1 Rev + + + PWM Actuel: + + + APMSetup + + + Swash-Servo position + + + Activ. Boussole + + + Mode Simple + + + ArduCopter2 + + + Mode Simple + + + type de châssis (+ ou x) + + + 60 + + + 1 + + + Mode Simple + + + Mode Simple + + + 2 + + + Modes + + + Mode Simple + + + 3 + + + Réinit. + + + -60 + + + Haut + + + Mouvement Swash + + + Manuel + + + Deplac. du Gouvernail + + + Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas + + + Calibrer Radio + + + Max + + + Mode de vol 2 + + + Roulis Max + + + Mode de vol 2 + + + Tangage Max + + + en degrés eg 2° 3' W est -2.3 + + + Mode de vol 1 + + + Niveler l'apareil pour copensation des accels + + + Mode de vol 6 + + + Capacité + + + Déclination + + + Activer Sonar + + + PWM 1231 - 1360 + + + Entrée Radio + + + 1500 + + + Mode de vol 4 + + + Mode de vol 5 + + + Gyro + + + PWM 1361 - 1490 + + + Matériel + + + PWM 1491 - 1620 + + + Site Web Déclination + + + 1500 + + + Batterie + + + Zéro + + + Activ. Airspeed + + + 4500 + + + RàZ tout parametres du APM + + + 1000 + + + Moniteur + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.it-IT.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.it-IT.resx new file mode 100644 index 0000000000..2b2636c813 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.it-IT.resx @@ -0,0 +1,318 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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 + + + 180 + + + Manuale + + + PWM 0 - 1230 + + + PWM 1621 - 1749 + + + Modo Corrente: + + + Abilita Flusso ottico + + + Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc. + + + Modo Semplice + + + PWM 1750 + + + + Elevatore CH1 Rev + + + PWM Corrente: + + + Imposta APM + + + Posizione del servo del piatto + + + Abilita Magnetometro + + + Modo Semplice + + + ArduCopter2 + + + Modo Semplice + + + Imposta Frame (+ or x) + + + 60 + + + 1 + + + Modo Semplice + + + Modo Semplice + + + 2 + + + Modi + + + Modo Semplice + + + 3 + + + Riavvia + + + -60 + + + Alto + + + Escursione del piatto + + + Manuale + + + Escursione Timone + + + Calibarzione del sensore di voltaggio: +1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto +2. Misura il voltaggio della batteria e inseriscilo nel box sotto +3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto + + + Calibrazione Radio + + + Massimo + + + Modo di volo 2 + + + Rollio massimo + + + Modo di volo 3 + + + Passo massimo + + + in gradi es 2° 3' W is -2.3 + + + Modo di volo 1 + + + Livella il quad per impostare gli accelerometri + + + Modo di volo 6 + + + Capacità + + + Declinazione + + + Attiva Sonar + + + PWM 1231 - 1360 + + + Ingresso Radio + + + Calibration + + + 1500 + + + Modo di volo 4 + + + Modo di volo 5 + + + Giroscopio + + + PWM 1361 - 1490 + + + Hardware + + + PWM 1491 - 1620 + + + Sito Web per la Declinazione + + + 1500 + + + Batteria + + + Zero + + + Attiva Sensore Velocità + + + 4500 + + + Resetta APM ai valori di Default + + + 1000 + + + Monitor + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.pl.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.pl.resx new file mode 100644 index 0000000000..057b932716 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.pl.resx @@ -0,0 +1,318 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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 + + + 180 + + + Ręczne + + + PWM 0 - 1230 + + + PWM 1621 - 1749 + + + Aktualny tryb: + + + Włącz Optical Flow + + + UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp. + + + Tryb prosty + + + PWM 1750 + + + + Odwr. Elevon CH1 + + + Aktualny PWM: + + + Ustawienia APM + + + Pozycja serwa płyty ster. + + + Włącz kompas + + + Tryb prosty + + + ArduCopter2 + + + Tryb prosty + + + Ustawienie ramy (+ lub x) + + + 60 + + + 1 + + + Tryb prosty + + + Tryb prosty + + + 2 + + + Tryby + + + Tryb prosty + + + 3 + + + Reset + + + -60 + + + Góra + + + Zakres ruchu płyty sterującej + + + Ręczne + + + Zakres steru kierunku + + + Kalibracja czujnika napięcia: +1. Zmierz napięcie wejściowe APM i wpisz poniżej +2. Zmierz napięcie baterii i wpisz poniżej +3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu + + + Kalibracja radia + + + Max + + + Tryb lotu 2 + + + Max przechylenie + + + Tryb lotu 3 + + + Max pochylenie + + + w stopniech np. 2° 3' W to -2.3 + + + Tryb lotu 1 + + + Wypoziomuj quada żeby stawić domyśle offsety przysp. + + + Tryb lotu 6 + + + Pojemność + + + Deklinacja + + + Włącz sonar + + + PWM 1231 - 1360 + + + Wejścia radia + + + Calibration + + + 1500 + + + Tryb lotu 4 + + + Tryb lotu 5 + + + Żyro + + + PWM 1361 - 1490 + + + Hardware + + + PWM 1491 - 1620 + + + Strona www deklinacji + + + 1500 + + + Bateria + + + Zero + + + Włącz prędkość powietrza + + + 4500 + + + Reset APM do stawień domyślnych + + + 1000 + + + Monitor + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.resx new file mode 100644 index 0000000000..04ea0521d6 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.resx @@ -0,0 +1,678 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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 + + + 17, 17 + + + + True + + + + NoControl + + + + 342, 5 + + + 93, 13 + + + 104 + + + Servo/Motor OUT + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + True + + + NoControl + + + 84, 5 + + + 49, 13 + + + 103 + + + Radio IN + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + NoControl + + + 297, 406 + + + 170, 25 + + + 102 + + + horizontalProgressBar9 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 5 + + + NoControl + + + 297, 351 + + + 170, 25 + + + 101 + + + horizontalProgressBar10 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 6 + + + NoControl + + + 297, 296 + + + 170, 25 + + + 100 + + + horizontalProgressBar11 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 7 + + + NoControl + + + 297, 241 + + + 170, 25 + + + 99 + + + horizontalProgressBar12 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 8 + + + NoControl + + + 297, 186 + + + 170, 25 + + + 98 + + + horizontalProgressBar13 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 9 + + + NoControl + + + 297, 131 + + + 170, 25 + + + 97 + + + horizontalProgressBar14 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 10 + + + NoControl + + + 297, 21 + + + 170, 25 + + + 96 + + + horizontalProgressBar15 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 11 + + + NoControl + + + 297, 76 + + + 170, 25 + + + 95 + + + horizontalProgressBar16 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 12 + + + NoControl + + + 15, 406 + + + 170, 25 + + + 94 + + + horizontalProgressBar8 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 13 + + + NoControl + + + 15, 351 + + + 170, 25 + + + 93 + + + horizontalProgressBar7 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 14 + + + NoControl + + + 15, 296 + + + 170, 25 + + + 92 + + + horizontalProgressBar6 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 15 + + + NoControl + + + 15, 241 + + + 170, 25 + + + 91 + + + horizontalProgressBar5 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 16 + + + NoControl + + + 15, 186 + + + 170, 25 + + + 90 + + + horizontalProgressBar4 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 17 + + + NoControl + + + 15, 131 + + + 170, 25 + + + 89 + + + horizontalProgressBar3 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 18 + + + NoControl + + + 15, 21 + + + 170, 25 + + + 88 + + + horizontalProgressBar2 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 19 + + + NoControl + + + 15, 76 + + + 170, 25 + + + 87 + + + horizontalProgressBar1 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 20 + + + Microsoft Sans Serif, 26.25pt + + + NoControl + + + 473, 21 + + + 275, 50 + + + 140 + + + Manual + + + MiddleCenter + + + lbl_currentmode + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + True + + + False + + + 556, 94 + + + 103, 17 + + + 141 + + + Throttle FailSafe + + + mavlinkCheckBox1 + + + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 1 + + + False + + + 556, 118 + + + 120, 20 + + + 142 + + + mavlinkNumericUpDown1 + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + + $this + + + 0 + + + True + + + 6, 13 + + + 751, 478 + + + currentStateBindingSource + + + System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + ConfigFailSafe + + + System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.zh-Hans.resx new file mode 100644 index 0000000000..fb781b45b1 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.zh-Hans.resx @@ -0,0 +1,169 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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 + + + + 115, 17 + + + Elevons CH2 逆转 + + + 91, 17 + + + Elevons 逆转 + + + 115, 17 + + + Elevons CH1 逆转 + + + 升降副翼 (Elevon) 配置 + + + 50, 17 + + + 逆转 + + + 50, 17 + + + 逆转 + + + 50, 17 + + + 逆转 + + + 50, 17 + + + 逆转 + + + 校准遥控 + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.zh-TW.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.zh-TW.resx new file mode 100644 index 0000000000..0c03fbf8ed --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.zh-TW.resx @@ -0,0 +1,460 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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 + + + 重置 + + + 遙控輸入 + + + 模式 + + + 硬件 + + + 電池 + + + 重置 APM 為默認設置 + + + + 50, 17 + + + 逆轉 + + + 50, 17 + + + 逆轉 + + + 50, 17 + + + 逆轉 + + + 50, 17 + + + 逆轉 + + + 校準遙控 + + + 74, 17 + + + 簡單模式 + + + 74, 17 + + + 簡單模式 + + + 74, 17 + + + 簡單模式 + + + 74, 17 + + + 簡單模式 + + + 74, 17 + + + 簡單模式 + + + 74, 17 + + + 簡單模式 + + + 64, 13 + + + 當前 PWM: + + + 58, 13 + + + 當前模式: + + + 64, 13 + + + 飛行模式 6 + + + 64, 13 + + + 飛行模式 5 + + + 64, 13 + + + 飛行模式 4 + + + 64, 13 + + + 飛行模式 3 + + + 64, 13 + + + 飛行模式 2 + + + 64, 13 + + + 飛行模式 1 + + + 保存模式 + + + 67, 13 + + + 磁偏角網站 + + + 磁偏角 + + + 啟用空速計 + + + 啟用聲納 + + + 啟用羅盤 + + + 63, 13 + + + 安培/伏特: + + + 52, 13 + + + 分 壓 比: + + + 58, 13 + + + 電池電壓: + + + 94, 13 + + + 測量的電池電壓: + + + 58, 13 + + + 輸入電壓: + + + 電壓傳感器校準: +1. 測量APM輸入電壓,輸入到下方的文本框中 +2. 測量電池電壓,輸入到下方的文本框中 +3. 從當前的傳感器的數據表中找到安培/伏特,輸入到下方的文本框中 + + + 31, 13 + + + 容量 + + + 48, 13 + + + 監控器 + + + 175, 13 + + + 設置水平面的默認加速度計偏移 + + + 261, 13 + + + 注: 圖片只是用於展示,設置可以用於六軸等機架 + + + 93, 13 + + + 機架設置 (+ 或 x) + + + 找平 + + + 31, 13 + + + 感度 + + + 31, 13 + + + 啟用 + + + 31, 13 + + + 微調 + + + 31, 13 + + + 逆轉 + + + 43, 13 + + + 方向舵 + + + 手動 + + + 31, 13 + + + 最大 + + + 31, 13 + + + 最小 + + + 手動 + + + 31, 13 + + + 最低 + + + 31, 13 + + + 最高 + + + 0度 + + + 31, 13 + + + 微調 + + + 31, 13 + + + 逆轉 + + + 31, 13 + + + 位置 + + + 31, 13 + + + 舵機 + + + 55, 13 + + + 最大俯仰 + + + 55, 13 + + + 最大側傾 + + + 55, 13 + + + 舵機行程 + + + 79, 13 + + + 斜盤水平微調 + + + 79, 13 + + + 斜盤舵機位置 + + + APM設置 + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs index ff68bcb6e6..7240b36e06 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs @@ -32,14 +32,14 @@ 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(); + this.CHK_enableoptflow = new ArdupilotMega.Controls.MavlinkCheckBox(); this.pictureBox2 = new System.Windows.Forms.PictureBox(); this.linkLabelmagdec = new System.Windows.Forms.LinkLabel(); this.label100 = new System.Windows.Forms.Label(); this.TXT_declination = new System.Windows.Forms.TextBox(); - this.CHK_enableairspeed = new System.Windows.Forms.CheckBox(); - this.CHK_enablesonar = new System.Windows.Forms.CheckBox(); - this.CHK_enablecompass = new System.Windows.Forms.CheckBox(); + this.CHK_enableairspeed = new ArdupilotMega.Controls.MavlinkCheckBox(); + this.CHK_enablesonar = new ArdupilotMega.Controls.MavlinkCheckBox(); + this.CHK_enablecompass = new ArdupilotMega.Controls.MavlinkCheckBox(); this.pictureBox4 = new System.Windows.Forms.PictureBox(); this.pictureBox3 = new System.Windows.Forms.PictureBox(); this.pictureBox1 = new System.Windows.Forms.PictureBox(); @@ -53,6 +53,7 @@ this.groupBox3 = new System.Windows.Forms.GroupBox(); this.label3 = new System.Windows.Forms.Label(); this.groupBox4 = new System.Windows.Forms.GroupBox(); + this.CHK_airspeeduse = new ArdupilotMega.Controls.MavlinkCheckBox(); ((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).BeginInit(); @@ -87,6 +88,10 @@ // resources.ApplyResources(this.CHK_enableoptflow, "CHK_enableoptflow"); this.CHK_enableoptflow.Name = "CHK_enableoptflow"; + this.CHK_enableoptflow.OffValue = 0F; + this.CHK_enableoptflow.OnValue = 1F; + this.CHK_enableoptflow.param = null; + this.CHK_enableoptflow.ParamName = null; this.CHK_enableoptflow.UseVisualStyleBackColor = true; this.CHK_enableoptflow.CheckedChanged += new System.EventHandler(this.CHK_enableoptflow_CheckedChanged); // @@ -121,6 +126,10 @@ // resources.ApplyResources(this.CHK_enableairspeed, "CHK_enableairspeed"); this.CHK_enableairspeed.Name = "CHK_enableairspeed"; + this.CHK_enableairspeed.OffValue = 0F; + this.CHK_enableairspeed.OnValue = 1F; + this.CHK_enableairspeed.param = null; + this.CHK_enableairspeed.ParamName = null; this.CHK_enableairspeed.UseVisualStyleBackColor = true; this.CHK_enableairspeed.CheckedChanged += new System.EventHandler(this.CHK_enableairspeed_CheckedChanged); // @@ -128,6 +137,10 @@ // resources.ApplyResources(this.CHK_enablesonar, "CHK_enablesonar"); this.CHK_enablesonar.Name = "CHK_enablesonar"; + this.CHK_enablesonar.OffValue = 0F; + this.CHK_enablesonar.OnValue = 1F; + this.CHK_enablesonar.param = null; + this.CHK_enablesonar.ParamName = null; this.CHK_enablesonar.UseVisualStyleBackColor = true; this.CHK_enablesonar.CheckedChanged += new System.EventHandler(this.CHK_enablesonar_CheckedChanged); // @@ -135,6 +148,10 @@ // resources.ApplyResources(this.CHK_enablecompass, "CHK_enablecompass"); this.CHK_enablecompass.Name = "CHK_enablecompass"; + this.CHK_enablecompass.OffValue = 0F; + this.CHK_enablecompass.OnValue = 1F; + this.CHK_enablecompass.param = null; + this.CHK_enablecompass.ParamName = null; this.CHK_enablecompass.UseVisualStyleBackColor = true; this.CHK_enablecompass.CheckedChanged += new System.EventHandler(this.CHK_enablecompass_CheckedChanged); // @@ -222,10 +239,21 @@ this.groupBox4.Name = "groupBox4"; this.groupBox4.TabStop = false; // + // CHK_airspeeduse + // + resources.ApplyResources(this.CHK_airspeeduse, "CHK_airspeeduse"); + this.CHK_airspeeduse.Name = "CHK_airspeeduse"; + this.CHK_airspeeduse.OffValue = 0F; + this.CHK_airspeeduse.OnValue = 1F; + this.CHK_airspeeduse.param = null; + this.CHK_airspeeduse.ParamName = null; + this.CHK_airspeeduse.UseVisualStyleBackColor = true; + // // ConfigHardwareOptions // resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.CHK_airspeeduse); this.Controls.Add(this.CHK_enableoptflow); this.Controls.Add(this.label3); this.Controls.Add(this.groupBox4); @@ -265,14 +293,14 @@ 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; + private ArdupilotMega.Controls.MavlinkCheckBox CHK_enableoptflow; private System.Windows.Forms.PictureBox pictureBox2; private System.Windows.Forms.LinkLabel linkLabelmagdec; private System.Windows.Forms.Label label100; private System.Windows.Forms.TextBox TXT_declination; - private System.Windows.Forms.CheckBox CHK_enableairspeed; - private System.Windows.Forms.CheckBox CHK_enablesonar; - private System.Windows.Forms.CheckBox CHK_enablecompass; + private ArdupilotMega.Controls.MavlinkCheckBox CHK_enableairspeed; + private ArdupilotMega.Controls.MavlinkCheckBox CHK_enablesonar; + private ArdupilotMega.Controls.MavlinkCheckBox CHK_enablecompass; private System.Windows.Forms.PictureBox pictureBox4; private System.Windows.Forms.PictureBox pictureBox3; private System.Windows.Forms.PictureBox pictureBox1; @@ -286,5 +314,6 @@ private System.Windows.Forms.GroupBox groupBox3; private System.Windows.Forms.Label label3; private System.Windows.Forms.GroupBox groupBox4; + private Controls.MavlinkCheckBox CHK_airspeeduse; } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs index 2afd0b7de5..8e89372292 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs @@ -247,21 +247,12 @@ namespace ArdupilotMega.GCSViews.ConfigurationView startup = true; - if (MainV2.comPort.param["ARSPD_ENABLE"] != null) - { - CHK_enableairspeed.Checked = MainV2.comPort.param["ARSPD_ENABLE"].ToString() == "1" ? true : false; - CHK_enableairspeed.Enabled = true; - } - if (MainV2.comPort.param["SONAR_ENABLE"] != null) - { - CHK_enablesonar.Checked = MainV2.comPort.param["SONAR_ENABLE"].ToString() == "1" ? true : false; - CHK_enablesonar.Enabled = true; - } - if (MainV2.comPort.param["MAG_ENABLE"] != null) - { - CHK_enablecompass.Checked = MainV2.comPort.param["MAG_ENABLE"].ToString() == "1" ? true : false; - CHK_enablecompass.Enabled = true; - } + CHK_airspeeduse.setup(1, 0, "ARSPD_USE", MainV2.comPort.param); + CHK_enableairspeed.setup(1, 0, "ARSPD_ENABLE", MainV2.comPort.param); + CHK_enablecompass.setup(1, 0, "MAG_ENABLE", MainV2.comPort.param, TXT_declination); + CHK_enableoptflow.setup(1,0,"FLOW_ENABLE", MainV2.comPort.param); + CHK_enablesonar.setup(1, 0, "SONAR_ENABLE", MainV2.comPort.param, CMB_sonartype); + if (MainV2.comPort.param["COMPASS_DEC"] != null) { TXT_declination.Text = (float.Parse(MainV2.comPort.param["COMPASS_DEC"].ToString()) * rad2deg).ToString(); @@ -270,11 +261,6 @@ namespace ArdupilotMega.GCSViews.ConfigurationView { CMB_sonartype.SelectedIndex = int.Parse(MainV2.comPort.param["SONAR_TYPE"].ToString()); } - if (MainV2.comPort.param["FLOW_ENABLE"] != null) - { - CHK_enableoptflow.Checked = MainV2.comPort.param["FLOW_ENABLE"].ToString() == "1" ? true : false; - CHK_enableoptflow.Enabled = true; - } if (MainV2.comPort.param["COMPASS_AUTODEC"] != null) { CHK_autodec.Checked = MainV2.comPort.param["COMPASS_AUTODEC"].ToString() == "1" ? true : false; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx index 43b9acdccb..b49e6872f3 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx @@ -139,13 +139,13 @@ BUT_MagCalibrationLive - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4592.29704, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4645.30967, Culture=neutral, PublicKeyToken=null $this - 14 + 15 NoControl @@ -172,7 +172,7 @@ $this - 15 + 16 XL-EZ0 @@ -205,7 +205,7 @@ $this - 16 + 17 False @@ -229,13 +229,13 @@ CHK_enableoptflow - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4645.30967, Culture=neutral, PublicKeyToken=null $this - 0 + 1 Zoom @@ -262,7 +262,7 @@ $this - 17 + 18 True @@ -292,7 +292,7 @@ $this - 18 + 19 NoControl @@ -319,7 +319,7 @@ $this - 19 + 20 False @@ -343,7 +343,7 @@ $this - 20 + 21 False @@ -352,10 +352,10 @@ NoControl - 92, 249 + 92, 248 - 103, 17 + 70, 18 39 @@ -367,13 +367,13 @@ CHK_enableairspeed - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4645.30967, Culture=neutral, PublicKeyToken=null $this - 3 + 4 False @@ -397,13 +397,13 @@ CHK_enablesonar - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4645.30967, Culture=neutral, PublicKeyToken=null $this - 6 + 7 False @@ -427,13 +427,13 @@ CHK_enablecompass - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4645.30967, Culture=neutral, PublicKeyToken=null $this - 9 + 10 Zoom @@ -460,7 +460,7 @@ $this - 21 + 22 Zoom @@ -487,7 +487,7 @@ $this - 22 + 23 Zoom @@ -520,7 +520,7 @@ $this - 23 + 24 NoControl @@ -541,13 +541,13 @@ BUT_MagCalibrationLog - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4592.29704, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4645.30967, Culture=neutral, PublicKeyToken=null $this - 13 + 14 False @@ -577,7 +577,7 @@ $this - 12 + 13 Microsoft Sans Serif, 12pt @@ -604,7 +604,7 @@ $this - 10 + 11 Top, Left, Right @@ -628,7 +628,7 @@ $this - 11 + 12 Microsoft Sans Serif, 12pt @@ -658,7 +658,7 @@ $this - 7 + 8 Top, Left, Right @@ -682,7 +682,7 @@ $this - 8 + 9 Microsoft Sans Serif, 12pt @@ -712,7 +712,7 @@ $this - 4 + 5 Top, Left, Right @@ -736,7 +736,7 @@ $this - 5 + 6 Microsoft Sans Serif, 12pt @@ -766,7 +766,7 @@ $this - 1 + 2 Top, Left, Right @@ -790,7 +790,37 @@ $this - 2 + 3 + + + False + + + NoControl + + + 168, 249 + + + 103, 17 + + + 73 + + + Use Airspeed + + + CHK_airspeeduse + + + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4645.30967, Culture=neutral, PublicKeyToken=null + + + $this + + + 0 True diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs index c55c7af88d..6beb848401 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs @@ -85,8 +85,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView enum Channelinput { Disable = 0, + RC5 = 5, RC6 = 6, - RC7 = 7 + RC7 = 7, + RC8 = 8 } public void Activate() diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.designer.cs index 4dad3df6bf..3541cf0112 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.designer.cs @@ -1,35 +1,35 @@ -using ArdupilotMega.Controls; -using ArdupilotMega.Presenter; - -namespace ArdupilotMega.GCSViews.ConfigurationView -{ - partial class ConfigMount - { - /// - /// Required designer variable. - /// - private System.ComponentModel.IContainer components = null; - - /// pi - /// 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() +using ArdupilotMega.Controls; +using ArdupilotMega.Presenter; + +namespace ArdupilotMega.GCSViews.ConfigurationView +{ + partial class ConfigMount + { + /// + /// Required designer variable. + /// + private System.ComponentModel.IContainer components = null; + + /// pi + /// 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() { System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigMount)); this.pictureBox1 = new System.Windows.Forms.PictureBox(); @@ -106,9 +106,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView // // pictureBox1 // - resources.ApplyResources(this.pictureBox1, "pictureBox1"); this.pictureBox1.BackColor = System.Drawing.Color.Transparent; this.pictureBox1.BackgroundImage = global::ArdupilotMega.Properties.Resources.cameraGimalPitch1; + resources.ApplyResources(this.pictureBox1, "pictureBox1"); this.pictureBox1.Name = "pictureBox1"; this.pictureBox1.TabStop = false; // @@ -120,8 +120,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView // // pictureBox2 // - resources.ApplyResources(this.pictureBox2, "pictureBox2"); this.pictureBox2.BackgroundImage = global::ArdupilotMega.Properties.Resources.cameraGimalRoll1; + resources.ApplyResources(this.pictureBox2, "pictureBox2"); this.pictureBox2.Name = "pictureBox2"; this.pictureBox2.TabStop = false; // @@ -180,8 +180,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView // // pictureBox3 // - resources.ApplyResources(this.pictureBox3, "pictureBox3"); this.pictureBox3.BackgroundImage = global::ArdupilotMega.Properties.Resources.cameraGimalYaw; + resources.ApplyResources(this.pictureBox3, "pictureBox3"); this.pictureBox3.Name = "pictureBox3"; this.pictureBox3.TabStop = false; // @@ -655,32 +655,32 @@ namespace ArdupilotMega.GCSViews.ConfigurationView // // mavlinkComboBoxTilt // - resources.ApplyResources(this.mavlinkComboBoxTilt, "mavlinkComboBoxTilt"); this.mavlinkComboBoxTilt.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.mavlinkComboBoxTilt.FormattingEnabled = true; + resources.ApplyResources(this.mavlinkComboBoxTilt, "mavlinkComboBoxTilt"); this.mavlinkComboBoxTilt.Name = "mavlinkComboBoxTilt"; this.mavlinkComboBoxTilt.SelectedIndexChanged += new System.EventHandler(this.mavlinkComboBox_SelectedIndexChanged); // // mavlinkComboBoxRoll // - resources.ApplyResources(this.mavlinkComboBoxRoll, "mavlinkComboBoxRoll"); this.mavlinkComboBoxRoll.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.mavlinkComboBoxRoll.FormattingEnabled = true; + resources.ApplyResources(this.mavlinkComboBoxRoll, "mavlinkComboBoxRoll"); this.mavlinkComboBoxRoll.Name = "mavlinkComboBoxRoll"; this.mavlinkComboBoxRoll.SelectedIndexChanged += new System.EventHandler(this.mavlinkComboBox_SelectedIndexChanged); // // mavlinkComboBoxPan // - resources.ApplyResources(this.mavlinkComboBoxPan, "mavlinkComboBoxPan"); this.mavlinkComboBoxPan.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.mavlinkComboBoxPan.FormattingEnabled = true; + resources.ApplyResources(this.mavlinkComboBoxPan, "mavlinkComboBoxPan"); this.mavlinkComboBoxPan.Name = "mavlinkComboBoxPan"; this.mavlinkComboBoxPan.SelectedIndexChanged += new System.EventHandler(this.mavlinkComboBox_SelectedIndexChanged); // // CMB_inputch_tilt // - resources.ApplyResources(this.CMB_inputch_tilt, "CMB_inputch_tilt"); this.CMB_inputch_tilt.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.CMB_inputch_tilt, "CMB_inputch_tilt"); this.CMB_inputch_tilt.FormattingEnabled = true; this.CMB_inputch_tilt.Name = "CMB_inputch_tilt"; this.CMB_inputch_tilt.param = null; @@ -698,8 +698,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView // // CMB_inputch_roll // - resources.ApplyResources(this.CMB_inputch_roll, "CMB_inputch_roll"); this.CMB_inputch_roll.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.CMB_inputch_roll, "CMB_inputch_roll"); this.CMB_inputch_roll.FormattingEnabled = true; this.CMB_inputch_roll.Name = "CMB_inputch_roll"; this.CMB_inputch_roll.param = null; @@ -712,8 +712,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView // // CMB_inputch_pan // - resources.ApplyResources(this.CMB_inputch_pan, "CMB_inputch_pan"); this.CMB_inputch_pan.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.CMB_inputch_pan, "CMB_inputch_pan"); this.CMB_inputch_pan.FormattingEnabled = true; this.CMB_inputch_pan.Name = "CMB_inputch_pan"; this.CMB_inputch_pan.param = null; @@ -721,7 +721,6 @@ namespace ArdupilotMega.GCSViews.ConfigurationView // // ConfigMount // - resources.ApplyResources(this, "$this"); this.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(38)))), ((int)(((byte)(39)))), ((int)(((byte)(40))))); this.Controls.Add(this.label24); this.Controls.Add(this.CMB_inputch_pan); @@ -778,6 +777,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView this.Controls.Add(this.pictureBox2); this.Controls.Add(this.pictureBox1); this.Name = "ConfigMount"; + resources.ApplyResources(this, "$this"); ((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.PBOX_WarningIcon)).EndInit(); @@ -797,64 +797,64 @@ namespace ArdupilotMega.GCSViews.ConfigurationView this.ResumeLayout(false); this.PerformLayout(); - } - - #endregion - - private System.Windows.Forms.PictureBox pictureBox1; - private System.Windows.Forms.PictureBox pictureBox2; - private System.Windows.Forms.GroupBox groupBox1; - private System.Windows.Forms.GroupBox groupBox2; - private System.Windows.Forms.Label label6; - private System.Windows.Forms.Label label5; - private PictureBoxWithPseudoOpacity PBOX_WarningIcon; - private LabelWithPseudoOpacity LBL_Error; - private System.Windows.Forms.LinkLabel LNK_wiki; - private System.Windows.Forms.Label label15; - private System.Windows.Forms.GroupBox groupBox3; - private System.Windows.Forms.PictureBox pictureBox3; - private System.Windows.Forms.Label label9; - private System.Windows.Forms.Label label10; - private System.Windows.Forms.Label label11; - private System.Windows.Forms.Label label12; - private MavlinkNumericUpDown mavlinkNumericUpDownRAM; - private MavlinkNumericUpDown mavlinkNumericUpDownRAMX; - private System.Windows.Forms.Label label13; - private System.Windows.Forms.Label label14; - private MavlinkNumericUpDown mavlinkNumericUpDownRSM; - private MavlinkNumericUpDown mavlinkNumericUpDownRSMX; - private MavlinkCheckBox mavlinkCheckBoxRR; - private System.Windows.Forms.Label label16; - private System.Windows.Forms.Label label17; - private System.Windows.Forms.Label label18; - private System.Windows.Forms.Label label19; - private MavlinkNumericUpDown mavlinkNumericUpDownPAM; - private MavlinkNumericUpDown mavlinkNumericUpDownPAMX; - private System.Windows.Forms.Label label20; - private System.Windows.Forms.Label label21; - private MavlinkNumericUpDown mavlinkNumericUpDownPSM; - private MavlinkNumericUpDown mavlinkNumericUpDownPSMX; - private MavlinkCheckBox mavlinkCheckBoxPR; - private System.Windows.Forms.Label label1; - private System.Windows.Forms.Label label2; - private System.Windows.Forms.Label label3; - private System.Windows.Forms.Label label4; - private MavlinkNumericUpDown mavlinkNumericUpDownTAM; - private MavlinkNumericUpDown mavlinkNumericUpDownTAMX; - private System.Windows.Forms.Label label7; - private System.Windows.Forms.Label label8; - private MavlinkNumericUpDown mavlinkNumericUpDownTSM; - private MavlinkNumericUpDown mavlinkNumericUpDownTSMX; - private MavlinkCheckBox mavlinkCheckBoxTR; - private System.Windows.Forms.ComboBox mavlinkComboBoxTilt; - private System.Windows.Forms.ComboBox mavlinkComboBoxRoll; - private System.Windows.Forms.ComboBox mavlinkComboBoxPan; - private MavlinkComboBox CMB_inputch_tilt; - private System.Windows.Forms.Label label22; - private System.Windows.Forms.Label label23; - private MavlinkComboBox CMB_inputch_roll; - private System.Windows.Forms.Label label24; - private MavlinkComboBox CMB_inputch_pan; - - } -} + } + + #endregion + + private System.Windows.Forms.PictureBox pictureBox1; + private System.Windows.Forms.PictureBox pictureBox2; + private System.Windows.Forms.GroupBox groupBox1; + private System.Windows.Forms.GroupBox groupBox2; + private System.Windows.Forms.Label label6; + private System.Windows.Forms.Label label5; + private PictureBoxWithPseudoOpacity PBOX_WarningIcon; + private LabelWithPseudoOpacity LBL_Error; + private System.Windows.Forms.LinkLabel LNK_wiki; + private System.Windows.Forms.Label label15; + private System.Windows.Forms.GroupBox groupBox3; + private System.Windows.Forms.PictureBox pictureBox3; + private System.Windows.Forms.Label label9; + private System.Windows.Forms.Label label10; + private System.Windows.Forms.Label label11; + private System.Windows.Forms.Label label12; + private MavlinkNumericUpDown mavlinkNumericUpDownRAM; + private MavlinkNumericUpDown mavlinkNumericUpDownRAMX; + private System.Windows.Forms.Label label13; + private System.Windows.Forms.Label label14; + private MavlinkNumericUpDown mavlinkNumericUpDownRSM; + private MavlinkNumericUpDown mavlinkNumericUpDownRSMX; + private MavlinkCheckBox mavlinkCheckBoxRR; + private System.Windows.Forms.Label label16; + private System.Windows.Forms.Label label17; + private System.Windows.Forms.Label label18; + private System.Windows.Forms.Label label19; + private MavlinkNumericUpDown mavlinkNumericUpDownPAM; + private MavlinkNumericUpDown mavlinkNumericUpDownPAMX; + private System.Windows.Forms.Label label20; + private System.Windows.Forms.Label label21; + private MavlinkNumericUpDown mavlinkNumericUpDownPSM; + private MavlinkNumericUpDown mavlinkNumericUpDownPSMX; + private MavlinkCheckBox mavlinkCheckBoxPR; + private System.Windows.Forms.Label label1; + private System.Windows.Forms.Label label2; + private System.Windows.Forms.Label label3; + private System.Windows.Forms.Label label4; + private MavlinkNumericUpDown mavlinkNumericUpDownTAM; + private MavlinkNumericUpDown mavlinkNumericUpDownTAMX; + private System.Windows.Forms.Label label7; + private System.Windows.Forms.Label label8; + private MavlinkNumericUpDown mavlinkNumericUpDownTSM; + private MavlinkNumericUpDown mavlinkNumericUpDownTSMX; + private MavlinkCheckBox mavlinkCheckBoxTR; + private System.Windows.Forms.ComboBox mavlinkComboBoxTilt; + private System.Windows.Forms.ComboBox mavlinkComboBoxRoll; + private System.Windows.Forms.ComboBox mavlinkComboBoxPan; + private MavlinkComboBox CMB_inputch_tilt; + private System.Windows.Forms.Label label22; + private System.Windows.Forms.Label label23; + private MavlinkComboBox CMB_inputch_roll; + private System.Windows.Forms.Label label24; + private MavlinkComboBox CMB_inputch_pan; + + } +} diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.resx index 38cd32f95a..dbbdcb099b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.resx @@ -117,1214 +117,836 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - mavlinkNumericUpDownRAMX + + + Zoom - - 27, 13 + + 33, 16 - - 12 - - - 246, 211 - - - 48 - - - Min - - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - 24, 13 - - - Max - - - 49 - - - 46 - - - $this - - - label15 - - - $this - - - label1 - - - Max - - - mavlinkNumericUpDownPSMX - - - mavlinkNumericUpDownRSMX - - - - 104 - - - $this - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + 203, 112 - - Microsoft Sans Serif, 12pt + + + 0 - - True + + pictureBox1 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 13 - - - 53 - - - True - - - True - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 276, 54 - - - 134 - - - 95, 20 - - - 103 - - - True - - - 114 - - - ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + $this - - True + + 53 + + + Top, Left, Right + + + 17, 150 635, 5 - - 18 + + 52 - - 100 + + groupBox1 - - 95, 20 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - label20 + + $this - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 51 - - Min + + Zoom - - True + + 33, 141 + + + 203, 112 + + + 53 + + + pictureBox2 System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 24, 13 - - - groupBox3 - - - 624, 9 - - - False - - - PBOX_WarningIcon - - + $this + + 52 + + + Top, Left, Right + + + 17, 23 + + + 635, 5 + + + 59 + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 50 + + + True + + + Microsoft Sans Serif, 12pt + + + 21, 4 + + + 29, 20 + + + 64 + + + Tilt + + + label5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 49 + + + True + + + Microsoft Sans Serif, 12pt + 20, 132 - - Max + + 36, 20 - - label10 + + 65 - + + Roll + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 48 + + + Bottom, Left, Right + + + 264, 389 + + + 32, 32 + + + 75 + + + PBOX_WarningIcon + + + ArdupilotMega.Controls.PictureBoxWithPseudoOpacity, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 47 + + + Bottom, Left, Right + + + True + + + 303, 402 + + + 138, 13 + + + 76 + + + Error Message of some kind + + + LBL_Error + + + ArdupilotMega.Controls.LabelWithPseudoOpacity, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 46 + + + Top, Right + + + True + + + 624, 9 + + + 28, 13 + + + 77 + + + Wiki + + + LNK_wiki + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 45 + + + True + + + Microsoft Sans Serif, 12pt + + + 20, 256 + + + 37, 20 + + + 80 + + + Pan + + + label15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 42 + + + Top, Left, Right + + + 17, 274 + + 635, 5 78 - - 276, 331 + + groupBox3 - - label21 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 106 - - - 385, 331 - - - 121, 21 - - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - True - - - ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - False - - - Max - - - 71, 3 - - - 118 - - - $this - - - 59 - - - ArdupilotMega.Controls.LabelWithPseudoOpacity, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - 130 - - - label11 - - - Input Ch - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 24, 13 - - - 131 - - - 6 - - - 59, 20 - - - $this - - + $this 43 - - 121, 21 - - - True - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 25 - - - 50 - - - $this - - - Microsoft Sans Serif, 12pt - - - True - - - mavlinkComboBoxRoll - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 117 - - - Reverse - - - False - - - 51 - - - 674, 432 - - - 95, 20 - - - 59, 20 - - - 59, 20 - - - 8 - - - 10 - - - 9 - - - $this - - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - 122 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 105 - - - label17 - - - $this - - - 267, 233 - - - $this - - - True - - - 66, 17 - - - 24, 13 - - - ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - True - - - 35 - - - False - - - $this - - - 251, 31 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 70, 20 - - - 355, 307 - - - 24, 13 - - - System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - $this - - - $this - - - 59, 20 - - - 385, 181 - - - 27, 13 - - - 59, 20 - - - 59, 20 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 352, 158 - - - 276, 181 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label22 - - - 80 - - - mavlinkNumericUpDownPAM - - - groupBox1 - - - mavlinkComboBoxPan - - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - 303, 402 - - - 41 - - - CMB_inputch_pan - - - $this - - - Microsoft Sans Serif, 12pt - - - - Zoom - - - True - - - 66, 17 - - - label12 - - - Min - - - True - - - 66, 17 - - - 38 - - - $this - - - 115 - - - 276, 80 - - - $this - - - 385, 80 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 267, 357 - - - 450, 181 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Min - - - 138, 13 - - - 0 - - - 29 - - - LNK_wiki - - - $this - - - label8 - - - label13 - - - 27, 13 - - - 136 - - - 42 - - - 14 - - - $this - - - True - - - 246, 183 - - - label9 - - - mavlinkCheckBoxRR - - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - 77 - - - ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - Top, Left, Right - - - 59, 20 - - - $this - - - 121 - - - mavlinkNumericUpDownTSMX - - - label7 - - - 119 - - - label2 - - - 267, 106 - - - $this - - - True - - - 450, 305 - - - 45 - - - Angle Limits - - - Top, Left, Right - - - label19 - - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - 36, 20 - - - ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - 36 - - - $this - - - Error Message of some kind - - - 17, 150 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 28 - - - True - - - 246, 335 - - - $this - - - $this - - - Zoom - - - 30 - Zoom - - 52 + + 33, 265 - - False - - - 21, 4 - - - 32 - - - $this - - - 17, 23 - - - $this - - - $this - - - 24, 13 - - - 635, 5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - True - - - True - - - 123 - - - 53 - - - 113 - - - Microsoft Sans Serif, 12pt - - - $this - - - 385, 54 - - - label23 - - - 33 - - - Servo Limits - - - $this - - - 71, 255 - - - $this - - - 1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - True - - - 17, 274 - - + 203, 112 - - 59, 20 - - - 27 - - - 125 - - - pictureBox2 - - - 20 - - - 264, 389 - - - Min - - - 116 - - - $this - - - False - - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - False - - - $this - - - 124 - - - 132 - - - 98 - - - 21 - - - Microsoft Sans Serif, 12pt - - - 120 - - - pictureBox1 - - - True - - - 29, 20 - - - 83, 21 - - - mavlinkNumericUpDownRSM - - - Reverse - - - 83, 21 - - - Microsoft Sans Serif, 12pt - - - True - - - 453, 158 - - - True - - - Input Ch - - - mavlinkNumericUpDownPSM - - - 99 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 352, 31 - - - 108 - - - 59, 20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - 79 - + + pictureBox3 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this - - 121, 21 - - - 97 - - - CMB_inputch_tilt - - - 355, 183 - - - Tilt - - - 24 - - - ConfigMount - - - 17 - - - 75 - - - $this - - - True - - - False - - - $this - - - 111 - - - Servo Limits - - - 40 - - - 64 - - - True - - - Input Ch - - - $this - - - Max - - - 59, 20 - - - Top, Left, Right - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Reverse - - - False - - - 27, 13 - - - 101 - - - 385, 305 - - - True - - - True - - - mavlinkCheckBoxTR - - - $this - - - Max - - - True - - - 71, 131 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - 44 - + True - - 70, 20 + + Microsoft Sans Serif, 12pt - - 135 + + 352, 158 - + + 95, 20 + + + 105 + + + Angle Limits + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this - - 37 + + 31 - - 129 + + True - - 96 + + Microsoft Sans Serif, 12pt - - 276, 207 + + 251, 158 - + + 95, 20 + + + 104 + + + Servo Limits + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 32 + + + True + + + 355, 211 + + + 27, 13 + + + 103 + + + Max + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 33 + + + True + + + 355, 183 + + + 24, 13 + + + 102 + + + Min + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 34 + + + False + + + 385, 181 + + + 59, 20 + + + 101 + + + mavlinkNumericUpDownRAM + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 35 + + False 385, 207 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 59, 20 - - 0 + + 100 - - mavlinkNumericUpDownPAMX + + mavlinkNumericUpDownRAMX - + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + $this - - Roll + + 36 - - $this - - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - 2 - - - mavlinkNumericUpDownTAM - - - 34 - - - 15 - - - Top, Right - - - 33, 265 - - - $this - - - 355, 335 - - - 22 - - - 126 - - - groupBox2 - - - 33, 141 - - - False - - - $this - - - 83, 21 - - - 102 - - - Pan - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - 450, 54 - - - 246, 84 - - - 16 - - - 246, 56 - - - $this - - - 7 - - + True - - pictureBox3 + + 246, 211 - - 31 + + 27, 13 - - 32, 32 + + 99 + + + Max + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 37 + + + True + + + 246, 183 + + + 24, 13 + + + 98 + + + Min + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 38 + + + False + + + 276, 181 + + + 59, 20 + + + 97 + + + mavlinkNumericUpDownRSM + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 39 + + + False + + + 276, 207 + + + 59, 20 + + + 96 + + + mavlinkNumericUpDownRSMX + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 40 + + + True + + + False + + + 267, 233 + + + 66, 17 95 - - mavlinkCheckBoxPR + + Reverse - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null + + mavlinkCheckBoxRR - - 355, 84 + + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null - - mavlinkComboBoxTilt + + $this - - Servo Limits + + 41 - - 127 + + True - - 95, 20 - - + Microsoft Sans Serif, 12pt - + + 352, 282 + + + 95, 20 + + + 116 + + + Angle Limits + + + label16 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this + + + 20 + + + True + + + Microsoft Sans Serif, 12pt + + + 251, 282 + + + 95, 20 + + + 115 + + + Servo Limits + + + label17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 21 + + + True + + + 355, 335 + + + 27, 13 + + + 114 + + + Max + + + label18 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 22 + + + True + + + 355, 307 + + + 24, 13 + + + 113 + + + Min + + + label19 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 23 + + + False + + + 385, 305 + + + 59, 20 + + + 112 + + + mavlinkNumericUpDownPAM + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 24 + + + False + + + 385, 331 + + + 59, 20 + + + 111 + + + mavlinkNumericUpDownPAMX + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 25 + + + True + + + 246, 335 + 27, 13 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - False - - - CMB_inputch_roll - - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - 70, 20 - 110 - - 133 + + Max - + + label20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this - - 52 + + 26 - - 128 + + True - - mavlinkNumericUpDownTAMX + + 246, 307 + + + 24, 13 + + + 109 + + + Min + + + label21 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 27 False @@ -1332,229 +954,607 @@ 276, 305 - - Microsoft Sans Serif, 12pt - - - 251, 158 - - - LBL_Error - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 76 - - - Wiki - - - 251, 282 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - + 59, 20 - - $this + + 108 - - mavlinkNumericUpDownRAM - - - 352, 282 - - - 19 - - - Angle Limits - - - 112 + + mavlinkNumericUpDownPSM - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null - - 109 - - - 33, 16 - - - False - - - 20, 256 - - - 39 - - - Microsoft Sans Serif, 12pt - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 5 - - + $this - - label5 + + 28 - + + False + + + 276, 331 + + 59, 20 - - $this - - - $this - - - 47 - - - Angle Limits - - - 203, 112 - - - label3 - - - $this - - - ArdupilotMega.Controls.PictureBoxWithPseudoOpacity, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - Microsoft Sans Serif, 12pt - - - 355, 56 - - - label4 - - - 23 - - - label16 - - - mavlinkNumericUpDownTSM - - - $this - - - False - - - 453, 31 - - - 355, 211 - - - $this - - - Microsoft Sans Serif, 12pt - - - Microsoft Sans Serif, 12pt - - - 246, 307 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 95, 20 - - - 3 - - - 37, 20 - - - Min - - - 4 - - - label24 - - - 95, 20 - - - Bottom, Left, Right - - - 11 - - - 28, 13 - - - Bottom, Left, Right - - - False - 107 - - 26 + + mavlinkNumericUpDownPSMX - - label6 + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this - - 27, 13 + + 29 - - label18 + + True - - 65 - - + False - + + 267, 357 + + + 66, 17 + + + 106 + + + Reverse + + + mavlinkCheckBoxPR + + + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + $this + + 30 + + + True + + + Microsoft Sans Serif, 12pt + + + 352, 31 + + + 95, 20 + + + 127 + + + Angle Limits + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + True + + + Microsoft Sans Serif, 12pt + + + 251, 31 + + + 95, 20 + + + 126 + + + Servo Limits + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + True + + + 355, 84 + + + 27, 13 + + + 125 + + + Max + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + True + + + 355, 56 + + + 24, 13 + + + 124 + + + Min + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 12 + + + False + + + 385, 54 + + + 59, 20 + + + 123 + + + mavlinkNumericUpDownTAM + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 13 + + + False + + + 385, 80 + + + 59, 20 + + + 122 + + + mavlinkNumericUpDownTAMX + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 14 + + + True + + + 246, 84 + + + 27, 13 + + + 121 + + + Max + + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + True + + + 246, 56 + + + 24, 13 + + + 120 + + + Min + + + label8 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 16 + False + + 276, 54 + + + 59, 20 + + + 119 + + + mavlinkNumericUpDownTSM + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 17 + + + False + + + 276, 80 + + + 59, 20 + + + 118 + + + mavlinkNumericUpDownTSMX + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 18 + + + True + + + False + + + 267, 106 + + + 66, 17 + + + 117 + + + Reverse + + + mavlinkCheckBoxTR + + + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 19 + + + 71, 3 + + + 121, 21 + + + 128 + + + mavlinkComboBoxTilt + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + 71, 131 + + + 121, 21 + + + 129 + + + mavlinkComboBoxRoll + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + 71, 255 + + + 121, 21 + + + 130 + + + mavlinkComboBoxPan + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 6 + + + False + + + 450, 54 + + + 83, 21 + + + 131 + + + CMB_inputch_tilt + + + ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 5 + + + True + + + Microsoft Sans Serif, 12pt + + + 453, 31 + + + 70, 20 + + + 132 + + + Input Ch + + + label22 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 4 + + + True + + + Microsoft Sans Serif, 12pt + + + 453, 158 + + + 70, 20 + + + 134 + + + Input Ch + + + label23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + False + + + 450, 181 + + + 83, 21 + + + 133 + + + CMB_inputch_roll + + + ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 3 + + + True + + + Microsoft Sans Serif, 12pt + 453, 282 - - label14 + + 70, 20 + + + 136 + + + Input Ch + + + label24 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + False + + + 450, 305 + + + 83, 21 + + + 135 + + + CMB_inputch_pan + + + ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4638.35097, Culture=neutral, PublicKeyToken=null + + + $this + + + 1 True + + 674, 432 + + + ConfigMount + + + System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs index e09399c222..f66f78a940 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs @@ -83,7 +83,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView CHK_revch3.Checked = MainV2.comPort.param["RC3_REV"].ToString() == "-1"; CHK_revch4.Checked = MainV2.comPort.param["RC4_REV"].ToString() == "-1"; } - catch (Exception ex) { CustomMessageBox.Show("Missing RC rev Param " + ex.ToString()); } + catch (Exception ex) { /*CustomMessageBox.Show("Missing RC rev Param " + ex.ToString());*/ } startup = false; } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs index dfd73c5c9d..d91a26e455 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs @@ -13,7 +13,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView { public partial class Setup : MyUserControl { - // remeber the last page accessed + // remember the last page accessed static string lastpagename = ""; public Setup() @@ -22,10 +22,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView ThemeManager.ApplyThemeTo(this); } - private void Setup_Load(object sender, EventArgs e) { - if (MainV2.comPort.BaseStream.IsOpen) { AddPagesForConnectedState(); @@ -35,7 +33,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView // These pages work when not connected to an APM AddBackstageViewPage(new ArdupilotMega._3DRradio(), "3DR Radio"); AddBackstageViewPage(new ArdupilotMega.Antenna.Tracker(), "Antenna Tracker"); -//backstageView.AddSpacer(15); + backstageView.AddSpacer(5); AddBackstageViewPage(new ConfigPlanner(), "Planner"); // remeber last page accessed @@ -67,14 +65,15 @@ If you are just setting up 3DR radios, you may continue without connecting."); AddBackstageViewPage(new ConfigRadioInput(), "Radio Calibration"); AddBackstageViewPage(new ConfigFlightModes(), "Flight Modes"); - AddBackstageViewPage(new ConfigHardwareOptions(), "Hardware Options"); - AddBackstageViewPage(new ConfigBatteryMonitoring(), "Battery Monitor"); + AddBackstageViewPage(new ConfigFailSafe(), "FailSafe"); + BackstageView.BackstageViewPage hardware = AddBackstageViewPage(new ConfigHardwareOptions(), "Hardware Options"); + AddBackstageViewPage(new ConfigBatteryMonitoring(), "Battery Monitor", hardware); /******************************HELI **************************/ if (MainV2.comPort.param["H_GYR_ENABLE"] != null) // heli { - AddBackstageViewPage(new ConfigMount(), "Camera Gimbal"); + AddBackstageViewPage(new ConfigMount(), "Camera Gimbal", hardware); AddBackstageViewPage(new ConfigAccelerometerCalibrationQuad(), "ArduCopter Level"); @@ -89,9 +88,7 @@ If you are just setting up 3DR radios, you may continue without connecting."); /****************************** ArduCopter **************************/ else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) { - //AddBackstageViewPage(new ConfigCameraStab(), "Camera Gimbal"); - - AddBackstageViewPage(new ConfigMount(), "Camera Gimbal"); + AddBackstageViewPage(new ConfigMount(), "Camera Gimbal", hardware); AddBackstageViewPage(new ConfigAccelerometerCalibrationQuad(), "ArduCopter Level"); @@ -104,7 +101,7 @@ If you are just setting up 3DR radios, you may continue without connecting."); /****************************** ArduPlane **************************/ else if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) { - AddBackstageViewPage(new ConfigMount(), "Camera Gimbal"); + AddBackstageViewPage(new ConfigMount(), "Camera Gimbal", hardware); AddBackstageViewPage(new ConfigAccelerometerCalibrationPlane(), "ArduPlane Level"); AddBackstageViewPage(new ConfigArduplane(), "ArduPlane Pids"); @@ -118,18 +115,18 @@ If you are just setting up 3DR radios, you may continue without connecting."); AddBackstageViewPage(new ConfigFriendlyParams { ParameterMode = ParameterMetaDataConstants.Standard }, "Standard Params"); AddBackstageViewPage(new ConfigFriendlyParams { ParameterMode = ParameterMetaDataConstants.Advanced }, "Advanced Params"); - AddBackstageViewPage(new ConfigRawParams(), "Parameter List"); + AddBackstageViewPage(new ConfigRawParams(), "Adv Parameter List"); } - private void AddBackstageViewPage(UserControl userControl, string headerText) + private BackstageView.BackstageViewPage AddBackstageViewPage(UserControl userControl, string headerText, BackstageView.BackstageViewPage Parent = null) { - backstageView.AddPage(userControl, headerText); + return backstageView.AddPage(userControl, headerText, Parent); } - private void Setup_FormClosing(object sender, FormClosingEventArgs e) { - lastpagename = backstageView.SelectedPage.LinkText; + if (backstageView.SelectedPage != null) + lastpagename = backstageView.SelectedPage.LinkText; backstageView.Close(); } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.Designer.cs new file mode 100644 index 0000000000..85045d9963 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.Designer.cs @@ -0,0 +1,60 @@ +namespace ArdupilotMega.GCSViews.ConfigurationView +{ + partial class SetupFresh + { + /// + /// 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.backstageView = new ArdupilotMega.Controls.BackstageView.BackstageView(); + this.SuspendLayout(); + // + // backstageView + // + this.backstageView.AutoSize = true; + this.backstageView.Dock = System.Windows.Forms.DockStyle.Fill; + this.backstageView.Location = new System.Drawing.Point(0, 0); + this.backstageView.Name = "backstageView"; + this.backstageView.Size = new System.Drawing.Size(1008, 506); + this.backstageView.TabIndex = 0; + // + // Setup + // + this.Controls.Add(this.backstageView); + this.MinimumSize = new System.Drawing.Size(1000, 450); + this.Name = "Setup"; + this.Size = new System.Drawing.Size(1008, 506); + this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Setup_FormClosing); + this.Load += new System.EventHandler(this.Setup_Load); + this.ResumeLayout(false); + this.PerformLayout(); + + } + + #endregion + + private Controls.BackstageView.BackstageView backstageView; + } +} diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.cs new file mode 100644 index 0000000000..f0546ddb6d --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.cs @@ -0,0 +1,110 @@ +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; +using ArdupilotMega.Controls.BackstageView; +using ArdupilotMega.Utilities; + +namespace ArdupilotMega.GCSViews.ConfigurationView +{ + public partial class SetupFresh : MyUserControl + { + // remember the last page accessed + static string lastpagename = ""; + + public SetupFresh() + { + InitializeComponent(); + ThemeManager.ApplyThemeTo(this); + } + + private void Setup_Load(object sender, EventArgs e) + { + if (MainV2.comPort.BaseStream.IsOpen) + { + AddPagesForConnectedState(); + // backstageView.AddSpacer(20); + } + + // remeber last page accessed + foreach (BackstageView.BackstageViewPage page in backstageView.Pages) { + if (page.LinkText == lastpagename) + { + this.backstageView.ActivatePage(page); + break; + } + } + + + //this.backstageView.ActivatePage(backstageView.Pages[0]); + + ThemeManager.ApplyThemeTo(this); + + if (!MainV2.comPort.BaseStream.IsOpen) + { + Common.MessageShowAgain("Config Connect", @"Please connect (click Connect Button) before using setup."); + } + } + + + // Add the pages that can only be shown when we are connected to an APM + private void AddPagesForConnectedState() + { + /****************************** Common **************************/ + + AddBackstageViewPage(new ConfigRadioInput(), "Step 1: Radio Calib"); + AddBackstageViewPage(new ConfigFlightModes(), "Step 2: Flight Modes"); + AddBackstageViewPage(new ConfigFailSafe(), "Step 3: FailSafe"); + BackstageView.BackstageViewPage hardware = AddBackstageViewPage(new ConfigHardwareOptions(), "Step 4: Hardware"); + AddBackstageViewPage(new ConfigBatteryMonitoring(), "Step 5: Battery"); + + + /******************************HELI **************************/ + if (MainV2.comPort.param["H_GYR_ENABLE"] != null) // heli + { + AddBackstageViewPage(new ConfigMount(), "Step 6: Gimbal"); + + AddBackstageViewPage(new ConfigAccelerometerCalibrationQuad(), "Step 7: Level"); + + AddBackstageViewPage(new ConfigTradHeli(), "Step 8: Heli Setup"); + } + /****************************** ArduCopter **************************/ + else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) + { + AddBackstageViewPage(new ConfigMount(), "Step 6: Gimbal"); + + AddBackstageViewPage(new ConfigAccelerometerCalibrationQuad(), "Step 7: Level"); + } + /****************************** ArduPlane **************************/ + else if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) + { + AddBackstageViewPage(new ConfigMount(), "Step 6: Gimbal"); + + AddBackstageViewPage(new ConfigAccelerometerCalibrationPlane(), "Step 7: Level"); + } + /****************************** ArduRover **************************/ + else if (MainV2.cs.firmware == MainV2.Firmwares.ArduRover) + { + + } + } + + private BackstageView.BackstageViewPage AddBackstageViewPage(UserControl userControl, string headerText, BackstageView.BackstageViewPage Parent = null) + { + return backstageView.AddPage(userControl, headerText, Parent); + } + + + private void Setup_FormClosing(object sender, FormClosingEventArgs e) + { + if (backstageView.SelectedPage != null) + lastpagename = backstageView.SelectedPage.LinkText; + + backstageView.Close(); + } + } +} \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.resx new file mode 100644 index 0000000000..7080a7d118 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/SetupFresh.resx @@ -0,0 +1,120 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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/GCSViews/Firmware.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.Designer.cs index 52528cbd32..3ef50a75a8 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.Designer.cs @@ -73,8 +73,11 @@ namespace ArdupilotMega.GCSViews this.pictureBoxACHHil = new System.Windows.Forms.PictureBox(); this.pictureBoxOcta = new ArdupilotMega.Controls.ImageLabel(); this.pictureBoxOctav = new ArdupilotMega.Controls.ImageLabel(); + this.pictureBoxRover = new ArdupilotMega.Controls.ImageLabel(); this.label1 = new System.Windows.Forms.Label(); this.CMB_history = new System.Windows.Forms.ComboBox(); + this.CMB_history_label = new System.Windows.Forms.Label(); + this.Custom_firmware_label = new System.Windows.Forms.Label(); ((System.ComponentModel.ISupportInitialize)(this.pictureBoxHilimage)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.pictureBoxAPHil)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.pictureBoxACHil)).BeginInit(); @@ -173,8 +176,6 @@ namespace ArdupilotMega.GCSViews this.pictureBoxAPHil.Name = "pictureBoxAPHil"; this.pictureBoxAPHil.TabStop = false; this.pictureBoxAPHil.Click += new System.EventHandler(this.pictureBoxAPHil_Click); - this.pictureBoxAPHil.MouseEnter += new System.EventHandler(this.pictureBoxAPHil_MouseEnter); - this.pictureBoxAPHil.MouseLeave += new System.EventHandler(this.pictureBoxAPHil_MouseLeave); // // pictureBoxACHil // @@ -210,6 +211,15 @@ namespace ArdupilotMega.GCSViews this.pictureBoxOctav.TabStop = false; this.pictureBoxOctav.Click += new System.EventHandler(this.pictureBoxOctav_Click); // + // pictureBoxRover + // + this.pictureBoxRover.Cursor = System.Windows.Forms.Cursors.Hand; + this.pictureBoxRover.Image = null; + resources.ApplyResources(this.pictureBoxRover, "pictureBoxRover"); + this.pictureBoxRover.Name = "pictureBoxRover"; + this.pictureBoxRover.TabStop = false; + this.pictureBoxRover.Click += new System.EventHandler(this.pictureBoxRover_Click); + // // label1 // resources.ApplyResources(this.label1, "label1"); @@ -223,10 +233,27 @@ namespace ArdupilotMega.GCSViews this.CMB_history.Name = "CMB_history"; this.CMB_history.SelectedIndexChanged += new System.EventHandler(this.CMB_history_SelectedIndexChanged); // + // CMB_history_label + // + resources.ApplyResources(this.CMB_history_label, "CMB_history_label"); + this.CMB_history_label.Cursor = System.Windows.Forms.Cursors.Hand; + this.CMB_history_label.Name = "CMB_history_label"; + this.CMB_history_label.Click += new System.EventHandler(this.CMB_history_label_Click); + // + // Custom_firmware_label + // + resources.ApplyResources(this.Custom_firmware_label, "Custom_firmware_label"); + this.Custom_firmware_label.Cursor = System.Windows.Forms.Cursors.Hand; + this.Custom_firmware_label.Name = "Custom_firmware_label"; + this.Custom_firmware_label.Click += new System.EventHandler(this.Custom_firmware_label_Click); + // // Firmware // resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.Custom_firmware_label); + this.Controls.Add(this.CMB_history_label); + this.Controls.Add(this.pictureBoxRover); this.Controls.Add(this.CMB_history); this.Controls.Add(this.label1); this.Controls.Add(this.BUT_setup); @@ -258,6 +285,9 @@ namespace ArdupilotMega.GCSViews } private ComboBox CMB_history; + private Controls.ImageLabel pictureBoxRover; + private Label CMB_history_label; + private Label Custom_firmware_label; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs index f9dc599338..622b9b4553 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs @@ -21,33 +21,9 @@ namespace ArdupilotMega.GCSViews protected override bool ProcessCmdKey(ref Message msg, Keys keyData) { - if (keyData == (Keys.Control | Keys.C)) - { - var fd = new OpenFileDialog {Filter = "Firmware (*.hex)|*.hex"}; - fd.ShowDialog(); - if (File.Exists(fd.FileName)) - { - UploadFlash(fd.FileName, ArduinoDetect.DetectBoard(MainV2.comPortName)); - } - return true; - } - - if (keyData == (Keys.Control | Keys.R)) - { - findfirmware("AR2"); - return true; - } - - if (keyData == (Keys.Control | Keys.O)) - { - CMB_history.Enabled = false; - - CMB_history.DataSource = oldurls; - - CMB_history.Enabled = true; - CMB_history.Visible = true; - } - + //CTRL+R moved to pictureBoxRover_Click + //CTRL+O moved to CMB_history_label_Click + //CTRL+C moved to Custom_firmware_label_Click return base.ProcessCmdKey(ref msg, keyData); } @@ -78,6 +54,7 @@ namespace ArdupilotMega.GCSViews WebRequest.DefaultWebProxy.Credentials = System.Net.CredentialCache.DefaultCredentials; this.pictureBoxAPM.Image = ArdupilotMega.Properties.Resources.APM_airframes_001; + this.pictureBoxRover.Image = ArdupilotMega.Properties.Resources.APM_rover_firmware; this.pictureBoxQuad.Image = ArdupilotMega.Properties.Resources.quad; this.pictureBoxHexa.Image = ArdupilotMega.Properties.Resources.hexa; this.pictureBoxTri.Image = ArdupilotMega.Properties.Resources.tri; @@ -178,6 +155,10 @@ namespace ArdupilotMega.GCSViews void updateDisplayName(software temp) { + if (temp.url.ToLower().Contains("AR2".ToLower())) + { + pictureBoxRover.Text = temp.name; + } if (temp.url.ToLower().Contains("firmware/AP-1".ToLower())) { pictureBoxAPM.Text = temp.name; @@ -259,6 +240,10 @@ namespace ArdupilotMega.GCSViews } } + private void pictureBoxRover_Click(object sender, EventArgs e) + { + findfirmware("AR2"); + } private void pictureBoxAPM_Click(object sender, EventArgs e) { findfirmware("firmware/AP-1"); @@ -710,7 +695,7 @@ namespace ArdupilotMega.GCSViews private void BUT_setup_Click(object sender, EventArgs e) { Form temp = new Form(); - MyUserControl configview = new GCSViews.ConfigurationView.Setup(); + MyUserControl configview = new GCSViews.ConfigurationView.SetupFresh(); temp.Controls.Add(configview); ThemeManager.ApplyThemeTo(temp); // fix title @@ -747,21 +732,34 @@ namespace ArdupilotMega.GCSViews findfirmware("AC2-HELHIL-"); } - private void pictureBoxAPHil_MouseEnter(object sender, EventArgs e) - { - - } - - private void pictureBoxAPHil_MouseLeave(object sender, EventArgs e) - { - - } - private void CMB_history_SelectedIndexChanged(object sender, EventArgs e) { firmwareurl = oldurl.Replace("!Hash!", CMB_history.Text); Firmware_Load(null, null); } + + //Show list of previous firmware versions (old CTRL+O shortcut) + private void CMB_history_label_Click(object sender, EventArgs e) + { + CMB_history.Enabled = false; + + CMB_history.DataSource = oldurls; + + CMB_history.Enabled = true; + CMB_history.Visible = true; + CMB_history_label.Visible = false; + } + + //Load custom firmware (old CTRL+C shortcut) + private void Custom_firmware_label_Click(object sender, EventArgs e) + { + var fd = new OpenFileDialog { Filter = "Firmware (*.hex)|*.hex" }; + fd.ShowDialog(); + if (File.Exists(fd.FileName)) + { + UploadFlash(fd.FileName, ArduinoDetect.DetectBoard(MainV2.comPortName)); + } + } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx index c12f1f8df9..a3c410f451 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx @@ -123,7 +123,7 @@ - 94, 0 + 237, 0 170, 170 @@ -136,19 +136,19 @@ pictureBoxAPM - ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4620.38627, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4645.32344, Culture=neutral, PublicKeyToken=null $this - 17 + 20 NoControl - 304, 0 + 413, 0 170, 170 @@ -160,19 +160,19 @@ pictureBoxQuad - ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4620.38627, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4645.32344, Culture=neutral, PublicKeyToken=null $this - 16 + 19 NoControl - 500, 0 + 589, 0 170, 170 @@ -184,19 +184,19 @@ pictureBoxHexa - ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4620.38627, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4645.32344, Culture=neutral, PublicKeyToken=null $this - 15 + 18 NoControl - 304, 176 + 413, 176 170, 170 @@ -208,19 +208,19 @@ pictureBoxTri - ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4620.38627, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4645.32344, Culture=neutral, PublicKeyToken=null $this - 14 + 17 NoControl - 500, 176 + 589, 176 170, 170 @@ -232,13 +232,13 @@ pictureBoxY6 - ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4620.38627, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4645.32344, Culture=neutral, PublicKeyToken=null $this - 13 + 16 True @@ -268,7 +268,7 @@ $this - 4 + 7 NoControl @@ -292,7 +292,7 @@ $this - 5 + 8 True @@ -301,16 +301,16 @@ NoControl - 886, 443 + 812, 443 - 113, 13 + 185, 13 9 - Images by Max Levine + Images by Max Levine and Marooned label2 @@ -322,13 +322,13 @@ $this - 3 + 6 NoControl - 94, 176 + 237, 176 170, 170 @@ -340,13 +340,13 @@ pictureBoxHeli - ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4620.38627, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4645.32344, Culture=neutral, PublicKeyToken=null $this - 12 + 15 NoControl @@ -367,13 +367,13 @@ BUT_setup - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4620.38627, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4645.32344, Culture=neutral, PublicKeyToken=null $this - 2 + 5 @@ -400,7 +400,7 @@ $this - 9 + 12 NoControl @@ -427,7 +427,7 @@ $this - 8 + 11 NoControl @@ -454,7 +454,7 @@ $this - 7 + 10 NoControl @@ -481,10 +481,10 @@ $this - 6 + 9 - 696, 176 + 765, 176 170, 170 @@ -496,16 +496,16 @@ pictureBoxOcta - ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4620.38627, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4645.32344, Culture=neutral, PublicKeyToken=null $this - 11 + 14 - 696, 0 + 765, 0 170, 170 @@ -517,13 +517,34 @@ pictureBoxOctav - ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4620.38627, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4645.32344, Culture=neutral, PublicKeyToken=null $this - 10 + 13 + + + 61, 0 + + + 170, 170 + + + 0 + + + pictureBoxRover + + + ArdupilotMega.Controls.ImageLabel, ArdupilotMegaPlanner10, Version=1.1.4645.32344, Culture=neutral, PublicKeyToken=null + + + $this + + + 2 True @@ -550,7 +571,7 @@ $this - 1 + 4 878, 387 @@ -574,6 +595,63 @@ $this + 3 + + + True + + + 886, 392 + + + 113, 13 + + + 28 + + + Pick previous firmware + + + CMB_history_label + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + True + + + NoControl + + + 889, 371 + + + 110, 13 + + + 29 + + + Load custom firmware + + + Custom_firmware_label + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + 0 @@ -589,6 +667,6 @@ Firmware - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4620.38627, Culture=neutral, PublicKeyToken=null + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4645.32344, Culture=neutral, PublicKeyToken=null \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs index 6e4b6116df..4a00d3b8d2 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs @@ -10,10 +10,15 @@ System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightData)); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle(); System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle(); + this.contextMenuStripMap = new System.Windows.Forms.ContextMenuStrip(this.components); + this.goHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); + this.flyToHereAltToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); + this.pointCameraHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); + this.flightPlannerToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.MainH = new System.Windows.Forms.SplitContainer(); this.SubMainLeft = new System.Windows.Forms.SplitContainer(); this.hud1 = new ArdupilotMega.Controls.HUD(); - this.contextMenuStrip2 = new System.Windows.Forms.ContextMenuStrip(this.components); + this.contextMenuStripHud = new System.Windows.Forms.ContextMenuStrip(this.components); this.recordHudToAVIToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.stopRecordToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.setMJPEGSourceToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); @@ -62,11 +67,6 @@ this.tableMap = new System.Windows.Forms.TableLayoutPanel(); this.splitContainer1 = new System.Windows.Forms.SplitContainer(); this.zg1 = new ZedGraph.ZedGraphControl(); - this.contextMenuStrip1 = new System.Windows.Forms.ContextMenuStrip(this.components); - this.goHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); - this.flyToHereAltToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); - this.pointCameraHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); - this.flightPlannerToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.lbl_winddir = new ArdupilotMega.Controls.MyLabel(); this.lbl_windvel = new ArdupilotMega.Controls.MyLabel(); this.lbl_hdop = new ArdupilotMega.Controls.MyLabel(); @@ -84,14 +84,17 @@ 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.Controls.MyLabel(); + this.dockContainer1 = new Crom.Controls.Docking.DockContainer(); + this.contextMenuStripDockContainer = new System.Windows.Forms.ContextMenuStrip(this.components); + this.resetToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); + this.contextMenuStripMap.SuspendLayout(); this.MainH.Panel1.SuspendLayout(); this.MainH.Panel2.SuspendLayout(); this.MainH.SuspendLayout(); this.SubMainLeft.Panel1.SuspendLayout(); this.SubMainLeft.Panel2.SuspendLayout(); this.SubMainLeft.SuspendLayout(); - this.contextMenuStrip2.SuspendLayout(); + this.contextMenuStripHud.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.bindingSource1)).BeginInit(); this.tabControl1.SuspendLayout(); this.tabQuick.SuspendLayout(); @@ -104,11 +107,45 @@ this.splitContainer1.Panel1.SuspendLayout(); this.splitContainer1.Panel2.SuspendLayout(); this.splitContainer1.SuspendLayout(); - this.contextMenuStrip1.SuspendLayout(); this.panel1.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).BeginInit(); + this.contextMenuStripDockContainer.SuspendLayout(); this.SuspendLayout(); // + // contextMenuStripMap + // + this.contextMenuStripMap.Items.AddRange(new System.Windows.Forms.ToolStripItem[] { + this.goHereToolStripMenuItem, + this.flyToHereAltToolStripMenuItem, + this.pointCameraHereToolStripMenuItem, + this.flightPlannerToolStripMenuItem}); + this.contextMenuStripMap.Name = "contextMenuStrip1"; + resources.ApplyResources(this.contextMenuStripMap, "contextMenuStripMap"); + // + // goHereToolStripMenuItem + // + this.goHereToolStripMenuItem.Name = "goHereToolStripMenuItem"; + resources.ApplyResources(this.goHereToolStripMenuItem, "goHereToolStripMenuItem"); + this.goHereToolStripMenuItem.Click += new System.EventHandler(this.goHereToolStripMenuItem_Click); + // + // flyToHereAltToolStripMenuItem + // + this.flyToHereAltToolStripMenuItem.Name = "flyToHereAltToolStripMenuItem"; + resources.ApplyResources(this.flyToHereAltToolStripMenuItem, "flyToHereAltToolStripMenuItem"); + this.flyToHereAltToolStripMenuItem.Click += new System.EventHandler(this.flyToHereAltToolStripMenuItem_Click); + // + // pointCameraHereToolStripMenuItem + // + this.pointCameraHereToolStripMenuItem.Name = "pointCameraHereToolStripMenuItem"; + resources.ApplyResources(this.pointCameraHereToolStripMenuItem, "pointCameraHereToolStripMenuItem"); + this.pointCameraHereToolStripMenuItem.Click += new System.EventHandler(this.pointCameraHereToolStripMenuItem_Click); + // + // flightPlannerToolStripMenuItem + // + this.flightPlannerToolStripMenuItem.Name = "flightPlannerToolStripMenuItem"; + resources.ApplyResources(this.flightPlannerToolStripMenuItem, "flightPlannerToolStripMenuItem"); + this.flightPlannerToolStripMenuItem.Click += new System.EventHandler(this.flightPlannerToolStripMenuItem_Click); + // // MainH // this.MainH.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; @@ -122,7 +159,6 @@ // MainH.Panel2 // this.MainH.Panel2.Controls.Add(this.tableMap); - this.MainH.SplitterMoved += new System.Windows.Forms.SplitterEventHandler(this.MainH_SplitterMoved); // // SubMainLeft // @@ -133,7 +169,6 @@ // SubMainLeft.Panel1 // this.SubMainLeft.Panel1.Controls.Add(this.hud1); - this.SubMainLeft.Panel1.Resize += new System.EventHandler(this.SubMainHT_Panel1_Resize); // // SubMainLeft.Panel2 // @@ -147,7 +182,7 @@ this.hud1.BackColor = System.Drawing.Color.Transparent; this.hud1.batterylevel = 0F; this.hud1.batteryremaining = 0F; - this.hud1.ContextMenuStrip = this.contextMenuStrip2; + this.hud1.ContextMenuStrip = this.contextMenuStripHud; this.hud1.current = 0F; this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("airspeed", this.bindingSource1, "airspeed", true)); this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("alt", this.bindingSource1, "alt", true)); @@ -205,18 +240,19 @@ this.hud1.wpno = 0; this.hud1.xtrack_error = 0F; this.hud1.DoubleClick += new System.EventHandler(this.hud1_DoubleClick); + this.hud1.Resize += new System.EventHandler(this.hud1_Resize); // - // contextMenuStrip2 + // contextMenuStripHud // - this.contextMenuStrip2.Items.AddRange(new System.Windows.Forms.ToolStripItem[] { + this.contextMenuStripHud.Items.AddRange(new System.Windows.Forms.ToolStripItem[] { this.recordHudToAVIToolStripMenuItem, this.stopRecordToolStripMenuItem, this.setMJPEGSourceToolStripMenuItem, this.setAspectRatioToolStripMenuItem, this.displayBatteryInfoToolStripMenuItem, this.userItemsToolStripMenuItem}); - this.contextMenuStrip2.Name = "contextMenuStrip2"; - resources.ApplyResources(this.contextMenuStrip2, "contextMenuStrip2"); + this.contextMenuStripHud.Name = "contextMenuStrip2"; + resources.ApplyResources(this.contextMenuStripHud, "contextMenuStripHud"); // // recordHudToAVIToolStripMenuItem // @@ -291,7 +327,7 @@ resources.ApplyResources(this.quickView6, "quickView6"); this.quickView6.MinimumSize = new System.Drawing.Size(100, 27); this.quickView6.Name = "quickView6"; - this.quickView6.number = "0.0"; + this.quickView6.number = 0D; this.quickView6.numberColor = System.Drawing.Color.FromArgb(((int)(((byte)(0)))), ((int)(((byte)(255)))), ((int)(((byte)(252))))); this.quickView6.DoubleClick += new System.EventHandler(this.quickView_DoubleClick); // @@ -302,7 +338,7 @@ resources.ApplyResources(this.quickView5, "quickView5"); this.quickView5.MinimumSize = new System.Drawing.Size(100, 27); this.quickView5.Name = "quickView5"; - this.quickView5.number = "0.0"; + this.quickView5.number = 0D; this.quickView5.numberColor = System.Drawing.Color.FromArgb(((int)(((byte)(254)))), ((int)(((byte)(254)))), ((int)(((byte)(86))))); this.quickView5.DoubleClick += new System.EventHandler(this.quickView_DoubleClick); // @@ -313,7 +349,7 @@ resources.ApplyResources(this.quickView4, "quickView4"); this.quickView4.MinimumSize = new System.Drawing.Size(100, 27); this.quickView4.Name = "quickView4"; - this.quickView4.number = "0.0"; + this.quickView4.number = 0D; this.quickView4.numberColor = System.Drawing.Color.FromArgb(((int)(((byte)(0)))), ((int)(((byte)(255)))), ((int)(((byte)(83))))); this.quickView4.DoubleClick += new System.EventHandler(this.quickView_DoubleClick); // @@ -324,7 +360,7 @@ resources.ApplyResources(this.quickView3, "quickView3"); this.quickView3.MinimumSize = new System.Drawing.Size(100, 27); this.quickView3.Name = "quickView3"; - this.quickView3.number = "0.0"; + this.quickView3.number = 0D; this.quickView3.numberColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(96)))), ((int)(((byte)(91))))); this.quickView3.DoubleClick += new System.EventHandler(this.quickView_DoubleClick); // @@ -335,7 +371,7 @@ resources.ApplyResources(this.quickView2, "quickView2"); this.quickView2.MinimumSize = new System.Drawing.Size(100, 27); this.quickView2.Name = "quickView2"; - this.quickView2.number = "0.0"; + this.quickView2.number = 0D; this.quickView2.numberColor = System.Drawing.Color.FromArgb(((int)(((byte)(254)))), ((int)(((byte)(132)))), ((int)(((byte)(46))))); this.quickView2.DoubleClick += new System.EventHandler(this.quickView_DoubleClick); // @@ -346,7 +382,7 @@ resources.ApplyResources(this.quickView1, "quickView1"); this.quickView1.MinimumSize = new System.Drawing.Size(100, 27); this.quickView1.Name = "quickView1"; - this.quickView1.number = "0.0"; + this.quickView1.number = 0D; this.quickView1.numberColor = System.Drawing.Color.FromArgb(((int)(((byte)(209)))), ((int)(((byte)(151)))), ((int)(((byte)(248))))); this.quickView1.DoubleClick += new System.EventHandler(this.quickView_DoubleClick); // @@ -985,10 +1021,12 @@ // NUM_playbackspeed // resources.ApplyResources(this.NUM_playbackspeed, "NUM_playbackspeed"); - this.NUM_playbackspeed.LargeChange = 1; + this.NUM_playbackspeed.LargeChange = 10; this.NUM_playbackspeed.Maximum = 10D; this.NUM_playbackspeed.Minimum = 0.01D; this.NUM_playbackspeed.Name = "NUM_playbackspeed"; + this.NUM_playbackspeed.SmallChange = 10; + this.NUM_playbackspeed.TickFrequency = 100; this.toolTip1.SetToolTip(this.NUM_playbackspeed, resources.GetString("NUM_playbackspeed.ToolTip")); this.NUM_playbackspeed.Value = 1D; this.NUM_playbackspeed.Scroll += new System.EventHandler(this.NUM_playbackspeed_Scroll); @@ -1041,7 +1079,7 @@ // // splitContainer1.Panel2 // - this.splitContainer1.Panel2.ContextMenuStrip = this.contextMenuStrip1; + this.splitContainer1.Panel2.ContextMenuStrip = this.contextMenuStripMap; this.splitContainer1.Panel2.Controls.Add(this.lbl_winddir); this.splitContainer1.Panel2.Controls.Add(this.lbl_windvel); this.splitContainer1.Panel2.Controls.Add(this.lbl_hdop); @@ -1061,40 +1099,6 @@ this.zg1.ScrollMinY2 = 0D; this.zg1.DoubleClick += new System.EventHandler(this.zg1_DoubleClick); // - // contextMenuStrip1 - // - this.contextMenuStrip1.Items.AddRange(new System.Windows.Forms.ToolStripItem[] { - this.goHereToolStripMenuItem, - this.flyToHereAltToolStripMenuItem, - this.pointCameraHereToolStripMenuItem, - this.flightPlannerToolStripMenuItem}); - this.contextMenuStrip1.Name = "contextMenuStrip1"; - resources.ApplyResources(this.contextMenuStrip1, "contextMenuStrip1"); - // - // goHereToolStripMenuItem - // - this.goHereToolStripMenuItem.Name = "goHereToolStripMenuItem"; - resources.ApplyResources(this.goHereToolStripMenuItem, "goHereToolStripMenuItem"); - this.goHereToolStripMenuItem.Click += new System.EventHandler(this.goHereToolStripMenuItem_Click); - // - // flyToHereAltToolStripMenuItem - // - this.flyToHereAltToolStripMenuItem.Name = "flyToHereAltToolStripMenuItem"; - resources.ApplyResources(this.flyToHereAltToolStripMenuItem, "flyToHereAltToolStripMenuItem"); - this.flyToHereAltToolStripMenuItem.Click += new System.EventHandler(this.flyToHereAltToolStripMenuItem_Click); - // - // pointCameraHereToolStripMenuItem - // - this.pointCameraHereToolStripMenuItem.Name = "pointCameraHereToolStripMenuItem"; - resources.ApplyResources(this.pointCameraHereToolStripMenuItem, "pointCameraHereToolStripMenuItem"); - this.pointCameraHereToolStripMenuItem.Click += new System.EventHandler(this.pointCameraHereToolStripMenuItem_Click); - // - // flightPlannerToolStripMenuItem - // - this.flightPlannerToolStripMenuItem.Name = "flightPlannerToolStripMenuItem"; - resources.ApplyResources(this.flightPlannerToolStripMenuItem, "flightPlannerToolStripMenuItem"); - this.flightPlannerToolStripMenuItem.Click += new System.EventHandler(this.flightPlannerToolStripMenuItem_Click); - // // lbl_winddir // this.lbl_winddir.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_dir", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Dir: 0")); @@ -1114,7 +1118,7 @@ // lbl_hdop // resources.ApplyResources(this.lbl_hdop, "lbl_hdop"); - this.lbl_hdop.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "gpshdop", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "hdop: 0")); + this.lbl_hdop.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "gpshdop", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "hdop: 0.0")); this.lbl_hdop.Name = "lbl_hdop"; this.lbl_hdop.resize = true; this.toolTip1.SetToolTip(this.lbl_hdop, resources.GetString("lbl_hdop.ToolTip")); @@ -1132,7 +1136,7 @@ this.gMapControl1.BackColor = System.Drawing.Color.Transparent; this.gMapControl1.Bearing = 0F; this.gMapControl1.CanDragMap = true; - this.gMapControl1.ContextMenuStrip = this.contextMenuStrip1; + this.gMapControl1.ContextMenuStrip = this.contextMenuStripMap; resources.ApplyResources(this.gMapControl1, "gMapControl1"); this.gMapControl1.GrayScaleMode = false; this.gMapControl1.LevelsKeepInMemmory = 5; @@ -1264,31 +1268,52 @@ this.toolTip1.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(205)))), ((int)(((byte)(226)))), ((int)(((byte)(150))))); this.toolTip1.ForeColor = System.Drawing.Color.FromArgb(((int)(((byte)(121)))), ((int)(((byte)(148)))), ((int)(((byte)(41))))); // - // label6 + // dockContainer1 // - resources.ApplyResources(this.label6, "label6"); - this.label6.Name = "label6"; - this.label6.resize = false; + this.dockContainer1.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(118)))), ((int)(((byte)(118)))), ((int)(((byte)(118))))); + this.dockContainer1.CanMoveByMouseFilledForms = true; + this.dockContainer1.ContextMenuStrip = this.contextMenuStripDockContainer; + resources.ApplyResources(this.dockContainer1, "dockContainer1"); + this.dockContainer1.Name = "dockContainer1"; + this.dockContainer1.TitleBarGradientColor1 = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31))))); + this.dockContainer1.TitleBarGradientColor2 = System.Drawing.Color.FromArgb(((int)(((byte)(205)))), ((int)(((byte)(226)))), ((int)(((byte)(150))))); + this.dockContainer1.TitleBarGradientSelectedColor1 = System.Drawing.Color.DarkGray; + this.dockContainer1.TitleBarGradientSelectedColor2 = System.Drawing.Color.White; + this.dockContainer1.TitleBarTextColor = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); + // + // contextMenuStripDockContainer + // + this.contextMenuStripDockContainer.Items.AddRange(new System.Windows.Forms.ToolStripItem[] { + this.resetToolStripMenuItem}); + this.contextMenuStripDockContainer.Name = "contextMenuStripDockContainer"; + resources.ApplyResources(this.contextMenuStripDockContainer, "contextMenuStripDockContainer"); + // + // resetToolStripMenuItem + // + this.resetToolStripMenuItem.Name = "resetToolStripMenuItem"; + resources.ApplyResources(this.resetToolStripMenuItem, "resetToolStripMenuItem"); + this.resetToolStripMenuItem.Click += new System.EventHandler(this.resetToolStripMenuItem_Click); // // FlightData // resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; this.Controls.Add(this.MainH); - this.Controls.Add(this.label6); + this.Controls.Add(this.dockContainer1); this.MinimumSize = new System.Drawing.Size(1008, 461); this.Name = "FlightData"; this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.FlightData_FormClosing); this.Load += new System.EventHandler(this.FlightData_Load); this.Resize += new System.EventHandler(this.FlightData_Resize); this.ParentChanged += new System.EventHandler(this.FlightData_ParentChanged); + this.contextMenuStripMap.ResumeLayout(false); this.MainH.Panel1.ResumeLayout(false); this.MainH.Panel2.ResumeLayout(false); this.MainH.ResumeLayout(false); this.SubMainLeft.Panel1.ResumeLayout(false); this.SubMainLeft.Panel2.ResumeLayout(false); this.SubMainLeft.ResumeLayout(false); - this.contextMenuStrip2.ResumeLayout(false); + this.contextMenuStripHud.ResumeLayout(false); ((System.ComponentModel.ISupportInitialize)(this.bindingSource1)).EndInit(); this.tabControl1.ResumeLayout(false); this.tabQuick.ResumeLayout(false); @@ -1302,22 +1327,21 @@ this.splitContainer1.Panel1.ResumeLayout(false); this.splitContainer1.Panel2.ResumeLayout(false); this.splitContainer1.ResumeLayout(false); - this.contextMenuStrip1.ResumeLayout(false); this.panel1.ResumeLayout(false); this.panel1.PerformLayout(); ((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).EndInit(); + this.contextMenuStripDockContainer.ResumeLayout(false); this.ResumeLayout(false); } private System.Windows.Forms.DataGridViewImageColumn dataGridViewImageColumn1; private System.Windows.Forms.DataGridViewImageColumn dataGridViewImageColumn2; - 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.ContextMenuStrip contextMenuStripMap; private System.Windows.Forms.ToolStripMenuItem goHereToolStripMenuItem; private ArdupilotMega.Controls.HUD hud1; private ArdupilotMega.Controls.MyButton BUT_clear_track; @@ -1361,7 +1385,7 @@ private ArdupilotMega.Controls.MyButton BUT_joystick; private System.Windows.Forms.ToolTip toolTip1; private ArdupilotMega.Controls.MyTrackBar NUM_playbackspeed; - private System.Windows.Forms.ContextMenuStrip contextMenuStrip2; + private System.Windows.Forms.ContextMenuStrip contextMenuStripHud; private System.Windows.Forms.ToolStripMenuItem recordHudToAVIToolStripMenuItem; private System.Windows.Forms.ToolStripMenuItem stopRecordToolStripMenuItem; private ArdupilotMega.Controls.MyLabel lbl_logpercent; @@ -1385,5 +1409,8 @@ private System.Windows.Forms.ToolStripMenuItem flyToHereAltToolStripMenuItem; private System.Windows.Forms.ToolStripMenuItem flightPlannerToolStripMenuItem; private System.Windows.Forms.ToolStripMenuItem userItemsToolStripMenuItem; + private Crom.Controls.Docking.DockContainer dockContainer1; + private System.Windows.Forms.ContextMenuStrip contextMenuStripDockContainer; + private System.Windows.Forms.ToolStripMenuItem resetToolStripMenuItem; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs index 16977aed56..f07ae2150c 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs @@ -19,6 +19,9 @@ using System.Drawing.Drawing2D; using ArdupilotMega.Controls; using ArdupilotMega.Utilities; using ArdupilotMega.Controls.BackstageView; +using Crom.Controls.Docking; + +using System.Reflection; // written by michael oborne namespace ArdupilotMega.GCSViews @@ -65,9 +68,14 @@ namespace ArdupilotMega.GCSViews internal static GMapOverlay kmlpolygons; internal static GMapOverlay geofence; + Dictionary formguids = new Dictionary(); + bool huddropout = false; bool huddropoutresize = false; + private DockStateSerializer _serializer = null; + DockableFormInfo dockhud; + List trackPoints = new List(); const float rad2deg = (float)(180 / Math.PI); @@ -90,7 +98,9 @@ namespace ArdupilotMega.GCSViews { threadrun = 0; MainV2.comPort.logreadmode = false; - MainV2.config["FlightSplitter"] = MainH.SplitterDistance.ToString(); + MainV2.config["FlightSplitter"] = hud1.Width; + _serializer.Save(); + SaveWindowLayout(); System.Threading.Thread.Sleep(100); base.Dispose(disposing); } @@ -100,6 +110,9 @@ namespace ArdupilotMega.GCSViews InitializeComponent(); instance = this; + _serializer = new DockStateSerializer(dockContainer1); + _serializer.SavePath = Application.StartupPath + Path.DirectorySeparatorChar + "FDscreen.xml"; + dockContainer1.PreviewRenderer = new PreviewRenderer(); mymap = gMapControl1; myhud = hud1; @@ -123,7 +136,7 @@ namespace ArdupilotMega.GCSViews chk_box_CheckedChanged((object)(new CheckBox() { Name = "nav_pitch", Checked = true }), new EventArgs()); } - for (int f = 1; f < 10; f++ ) + for (int f = 1; f < 10; f++) { // load settings if (MainV2.config["quickView" + f] != null) @@ -141,32 +154,36 @@ namespace ArdupilotMega.GCSViews } } + foreach (string item in MainV2.config.Keys) + { + if (item.StartsWith("hud1_useritem_")) + { + string selection = item.Replace("hud1_useritem_", ""); + + CheckBox chk = new CheckBox(); + chk.Name = selection; + chk.Checked = true; + + HUD.Custom cust = new HUD.Custom(); + cust.Header = MainV2.config[item].ToString(); + + addHudUserItem(ref cust, chk); + } + } + List list = new List(); - //foreach (object obj in Enum.GetValues(typeof(MAVLink09.MAV_ACTION))) -#if MAVLINK10 { list.Add("LOITER_UNLIM"); list.Add("RETURN_TO_LAUNCH"); list.Add("PREFLIGHT_CALIBRATION"); + list.Add("MISSION_START"); + list.Add("PREFLIGHT_REBOOT_SHUTDOWN"); + //DO_SET_SERVO + //DO_REPEAT_SERVO } -#else - { - list.Add("RETURN"); - list.Add("HALT"); - list.Add("CONTINUE"); - list.Add("SET_MANUAL"); - list.Add("SET_AUTO"); - list.Add("STORAGE_READ"); - list.Add("STORAGE_WRITE"); - list.Add("CALIBRATE_RC"); - list.Add("NAVIGATE"); - list.Add("LOITER"); - list.Add("TAKEOFF"); - list.Add("CALIBRATE_GYRO"); - } -#endif + CMB_action.DataSource = list; @@ -212,6 +229,295 @@ namespace ArdupilotMega.GCSViews } } catch { } + + SetupDocking(); + + if (File.Exists(_serializer.SavePath) == true) + { + try + { + _serializer.Load(true, GetFormFromGuid); + } + catch { } + } + + cleanupDocks(); + } + + void SetupDocking() + { + this.SuspendLayout(); + + dockhud = CreateFormAndGuid(dockContainer1, hud1, "fd_hud_guid"); + DockableFormInfo dockmap = CreateFormAndGuid(dockContainer1, tableMap, "fd_map_guid"); + DockableFormInfo dockquick = CreateFormAndGuid(dockContainer1, tabQuick, "fd_quick_guid"); + DockableFormInfo dockactions = CreateFormAndGuid(dockContainer1, tabActions, "fd_actions_guid"); + DockableFormInfo dockguages = CreateFormAndGuid(dockContainer1, tabGauges, "fd_guages_guid"); + DockableFormInfo dockstatus = CreateFormAndGuid(dockContainer1, tabStatus, "fd_status_guid"); + DockableFormInfo docktlogs = CreateFormAndGuid(dockContainer1, tabTLogs, "fd_tlogs_guid"); + + + dockContainer1.DockForm(dockmap, DockStyle.Fill, zDockMode.Outer); + dockContainer1.DockForm(dockquick, DockStyle.Right, zDockMode.Outer); + dockContainer1.DockForm(dockhud, DockStyle.Left, zDockMode.Outer); + + dockContainer1.DockForm(dockactions, dockhud, DockStyle.Bottom, zDockMode.Outer); + dockContainer1.DockForm(dockguages, dockactions, DockStyle.Fill, zDockMode.Inner); + dockContainer1.DockForm(dockstatus, dockactions, DockStyle.Fill, zDockMode.Inner); + dockContainer1.DockForm(docktlogs, dockactions, DockStyle.Fill, zDockMode.Inner); + + dockactions.IsSelected = true; + + if (MainV2.config["FlightSplitter"] != null) + { + dockContainer1.SetWidth(dockhud, int.Parse(MainV2.config["FlightSplitter"].ToString())); + } + + dockContainer1.SetHeight(dockhud, hud1.Height); + + this.ResumeLayout(); + } + + void cleanupDocks() + { + // cleanup from load + for (int a = 0; a < dockContainer1.Count; a++) + { + DockableFormInfo info = dockContainer1.GetFormInfoAt(a); + + info.ShowCloseButton = false; + + info.ShowContextMenuButton = false; + } + dockContainer1.Invalidate(); + } + + void SaveWindowLayout() + { + XmlTextWriter xmlwriter = new XmlTextWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"FDLayout.xml", Encoding.ASCII); + xmlwriter.Formatting = Formatting.Indented; + + xmlwriter.WriteStartDocument(); + + xmlwriter.WriteStartElement("ScreenLayout"); + + //xmlwriter.WriteElementString("comport", comPortName); + + + for (int a = 0; a < dockContainer1.Count; a++) + { + DockableFormInfo info = dockContainer1.GetFormInfoAt(a); + + xmlwriter.WriteStartElement("Form"); + + object thisBoxed = info; + Type test = thisBoxed.GetType(); + + foreach (var field in test.GetProperties()) + { + // field.Name has the field's name. + object fieldValue; + try + { + fieldValue = field.GetValue(thisBoxed,null); // Get value + } + catch { continue; } + + // Get the TypeCode enumeration. Multiple types get mapped to a common typecode. + TypeCode typeCode = Type.GetTypeCode(fieldValue.GetType()); + + xmlwriter.WriteElementString(field.Name, fieldValue.ToString()); + } + + // DockableContainer dockcont = info as DockableContainer; + + // dockContainer1. + + xmlwriter.WriteEndElement(); + } + + xmlwriter.WriteEndElement(); + + xmlwriter.WriteEndDocument(); + xmlwriter.Close(); + } + + DockableFormInfo CreateFormAndGuid(DockContainer dock, Control ctl, string configguidref) + { + Guid gu = GetOrCreateGuid(configguidref); + Form frm; + if (formguids.ContainsKey(gu)) + { + frm = formguids[gu]; + } + else + { + frm = CreateFormFromControl(ctl); + frm.AutoScroll = true; + formguids[gu] = frm; + } + + return dock.Add(frm, Crom.Controls.Docking.zAllowedDock.All, gu); + } + + Guid GetOrCreateGuid(string configname) + { + if (!MainV2.config.ContainsKey(configname)) + { + MainV2.config[configname] = Guid.NewGuid().ToString(); + } + + return new Guid(MainV2.config[configname].ToString()); + } + + Form GetFormFromGuid(Guid id) + { + return formguids[id]; + } + + Form CreateFormFromControl(Control ctl) + { + ctl.Dock = DockStyle.Fill; + Form newform = new Form(); + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2)); + newform.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon"))); + try + { + if (ctl is TabPage) + { + TabPage tp = ctl as TabPage; + newform.Text = ctl.Text; + while (tp.Controls.Count > 0) + { + newform.Controls.Add(tp.Controls[0]); + } + if (tp == tabQuick) + { + newform.Resize += tabQuick_Resize; + } + if (tp == tabStatus) + { + newform.Resize += tabStatus_Resize; + newform.Load += tabStatus_Resize; + //newform.Resize += tab1 + } + if (tp == tabGauges) + { + newform.Resize += tabPage1_Resize; + } + } + else if (ctl is Form) + { + return (Form)ctl; + } + else + { + newform.Text = ctl.Text; + newform.Controls.Add(ctl); + if (ctl is HUD) + { + newform.Text = "Hud"; + } + if (ctl is myGMAP) + { + newform.Text = "Map"; + } + } + } + catch { } + return newform; + } + + void tabStatus_Resize(object sender, EventArgs e) + { + // localise it + Control tabStatus = sender as Control; + + // tabStatus.SuspendLayout(); + + //foreach (Control temp in tabStatus.Controls) + { + // temp.DataBindings.Clear(); + //temp.Dispose(); + } + //tabStatus.Controls.Clear(); + + int x = 10; + int y = 10; + + object thisBoxed = MainV2.cs; + Type test = thisBoxed.GetType(); + + foreach (var field in test.GetProperties()) + { + // field.Name has the field's name. + object fieldValue; + try + { + fieldValue = field.GetValue(thisBoxed, null); // Get value + } + catch { continue; } + + // Get the TypeCode enumeration. Multiple types get mapped to a common typecode. + TypeCode typeCode = Type.GetTypeCode(fieldValue.GetType()); + + bool add = true; + + MyLabel lbl1 = new MyLabel(); + MyLabel lbl2 = new MyLabel(); + try + { + lbl1 = (MyLabel)tabStatus.Controls.Find(field.Name, false)[0]; + + lbl2 = (MyLabel)tabStatus.Controls.Find(field.Name + "value", false)[0]; + + add = false; + } + catch { } + + if (add) + { + + lbl1.Location = new Point(x, y); + lbl1.Size = new System.Drawing.Size(75, 13); + lbl1.Text = field.Name; + lbl1.Name = field.Name; + lbl1.Visible = true; + lbl2.AutoSize = false; + + lbl2.Location = new Point(lbl1.Right + 5, y); + lbl2.Size = new System.Drawing.Size(50, 13); + //if (lbl2.Name == "") + lbl2.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, field.Name, false, System.Windows.Forms.DataSourceUpdateMode.OnValidation, "0")); + lbl2.Name = field.Name + "value"; + lbl2.Visible = true; + //lbl2.Text = fieldValue.ToString(); + + + tabStatus.Controls.Add(lbl1); + tabStatus.Controls.Add(lbl2); + } + else + { + lbl1.Location = new Point(x, y); + lbl2.Location = new Point(lbl1.Right + 5, y); + } + + //Application.DoEvents(); + + x += 0; + y += 15; + + if (y > tabStatus.Height - 30) + { + x += 140; + y = 10; + } + } + + tabStatus.Width = x; + + // tabStatus.ResumeLayout(); } public void Activate() @@ -1054,13 +1360,6 @@ namespace ArdupilotMega.GCSViews } } - private void SubMainHT_Panel1_Resize(object sender, EventArgs e) - { - hud1.Width = MainH.SplitterDistance; - - SubMainLeft.SplitterDistance = hud1.Height + 2; - } - private void BUT_RAWSensor_Click(object sender, EventArgs e) { Form temp = new RAW_Sensor(); @@ -1266,22 +1565,13 @@ namespace ArdupilotMega.GCSViews catch { } // ignore any invalid } - bool loaded = false; - - private void MainH_SplitterMoved(object sender, SplitterEventArgs e) - { - if (loaded == true) - { // startup check - MainV2.config["FlightSplitter"] = MainH.SplitterDistance.ToString(); - } - loaded = true; - hud1.Width = MainH.Panel1.Width; - } - private void tabPage1_Resize(object sender, EventArgs e) { int mywidth, myheight; + // localize it + Control tabGauges = sender as Control; + float scale = tabGauges.Width / (float)tabGauges.Height; if (scale > 0.5 && scale < 1.9) @@ -1444,10 +1734,8 @@ namespace ArdupilotMega.GCSViews if (huddropout) return; - SubMainLeft.Panel1Collapsed = true; Form dropout = new Form(); dropout.Size = new System.Drawing.Size(hud1.Width, hud1.Height + 20); - SubMainLeft.Panel1.Controls.Remove(hud1); dropout.Controls.Add(hud1); dropout.Resize += new EventHandler(dropout_Resize); dropout.FormClosed += new FormClosedEventHandler(dropout_FormClosed); @@ -1457,8 +1745,7 @@ namespace ArdupilotMega.GCSViews void dropout_FormClosed(object sender, FormClosedEventArgs e) { - SubMainLeft.Panel1.Controls.Add(hud1); - SubMainLeft.Panel1Collapsed = false; + dockhud.DockableForm.Controls.Add(hud1); huddropout = false; } @@ -1492,93 +1779,10 @@ namespace ArdupilotMega.GCSViews private void tabControl1_SelectedIndexChanged(object sender, EventArgs e) { + /* if (tabControl1.SelectedTab == tabStatus) { - tabControl1.SuspendLayout(); - - foreach (Control temp in tabStatus.Controls) - { - // temp.DataBindings.Clear(); - //temp.Dispose(); - } - //tabStatus.Controls.Clear(); - - int x = 10; - int y = 10; - - object thisBoxed = MainV2.cs; - Type test = thisBoxed.GetType(); - - foreach (var field in test.GetProperties()) - { - // field.Name has the field's name. - object fieldValue; - try - { - fieldValue = field.GetValue(thisBoxed, null); // Get value - } - catch { continue; } - - // Get the TypeCode enumeration. Multiple types get mapped to a common typecode. - TypeCode typeCode = Type.GetTypeCode(fieldValue.GetType()); - - bool add = true; - - MyLabel lbl1 = new MyLabel(); - MyLabel lbl2 = new MyLabel(); - try - { - lbl1 = (MyLabel)tabStatus.Controls.Find(field.Name, false)[0]; - - lbl2 = (MyLabel)tabStatus.Controls.Find(field.Name + "value", false)[0]; - - add = false; - } - catch { } - - if (add) - { - - lbl1.Location = new Point(x, y); - lbl1.Size = new System.Drawing.Size(75, 13); - lbl1.Text = field.Name; - lbl1.Name = field.Name; - lbl1.Visible = true; - lbl2.AutoSize = false; - - lbl2.Location = new Point(lbl1.Right + 5, y); - lbl2.Size = new System.Drawing.Size(50, 13); - //if (lbl2.Name == "") - lbl2.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, field.Name, false, System.Windows.Forms.DataSourceUpdateMode.OnValidation, "0")); - lbl2.Name = field.Name + "value"; - lbl2.Visible = true; - //lbl2.Text = fieldValue.ToString(); - - - tabStatus.Controls.Add(lbl1); - tabStatus.Controls.Add(lbl2); - } - else - { - lbl1.Location = new Point(x, y); - lbl2.Location = new Point(lbl1.Right + 5, y); - } - - //Application.DoEvents(); - - x += 0; - y += 15; - - if (y > tabStatus.Height - 30) - { - x += 140; - y = 10; - } - } - - tabStatus.Width = x; - - tabControl1.ResumeLayout(); + } else { @@ -1591,15 +1795,10 @@ namespace ArdupilotMega.GCSViews if (tabControl1.SelectedTab == tabQuick) { - int height = tabQuick.Height / 6; - quickView1.Size = new System.Drawing.Size(tabQuick.Width, height); - quickView2.Size = new System.Drawing.Size(tabQuick.Width, height); - quickView3.Size = new System.Drawing.Size(tabQuick.Width, height); - quickView4.Size = new System.Drawing.Size(tabQuick.Width, height); - quickView5.Size = new System.Drawing.Size(tabQuick.Width, height); - quickView6.Size = new System.Drawing.Size(tabQuick.Width, height); + } } + */ } private void Gspeed_DoubleClick(object sender, EventArgs e) @@ -1810,6 +2009,15 @@ namespace ArdupilotMega.GCSViews selectform.Show(); } + void addHudUserItem(ref HUD.Custom cust, CheckBox sender) + { + setupPropertyInfo(ref cust.Item, (sender).Name, MainV2.cs); + + hud1.CustomItems.Add((sender).Name, cust); + + hud1.Invalidate(); + } + void chk_box_hud_UserItem_CheckedChanged(object sender, EventArgs e) { if (((CheckBox)sender).Checked) @@ -1825,11 +2033,8 @@ namespace ArdupilotMega.GCSViews MainV2.config["hud1_useritem_" + ((CheckBox)sender).Name] = prefix; cust.Header = prefix; - setupPropertyInfo(ref cust.Item, ((CheckBox)sender).Name, MainV2.cs); - hud1.CustomItems.Add(((CheckBox)sender).Name, cust); - - hud1.Invalidate(); + addHudUserItem(ref cust, (CheckBox)sender); } else { @@ -1837,6 +2042,7 @@ namespace ArdupilotMega.GCSViews { hud1.CustomItems.Remove(((CheckBox)sender).Name); } + MainV2.config.Remove("hud1_useritem_" + ((CheckBox)sender).Name); hud1.Invalidate(); } } @@ -2195,8 +2401,7 @@ print 'Roll complete' private void setAspectRatioToolStripMenuItem_Click(object sender, EventArgs e) { hud1.SixteenXNine = !hud1.SixteenXNine; - // force a redraw - SubMainHT_Panel1_Resize(null, null); + hud1.Invalidate(); } private void displayBatteryInfoToolStripMenuItem_Click(object sender, EventArgs e) @@ -2382,7 +2587,32 @@ print 'Roll complete' private void tabQuick_Resize(object sender, EventArgs e) { - tabControl1_SelectedIndexChanged(null, null); + int height = ((Control)sender).Height / 6; + quickView1.Size = new System.Drawing.Size(tabQuick.Width, height); + quickView2.Size = new System.Drawing.Size(tabQuick.Width, height); + quickView3.Size = new System.Drawing.Size(tabQuick.Width, height); + quickView4.Size = new System.Drawing.Size(tabQuick.Width, height); + quickView5.Size = new System.Drawing.Size(tabQuick.Width, height); + quickView6.Size = new System.Drawing.Size(tabQuick.Width, height); + } + + private void hud1_Resize(object sender, EventArgs e) + { + Console.WriteLine("HUD resize "+ hud1.Width + " " + hud1.Height); + + try + { + // dockContainer1.SetHeight(dockhud, hud1.Height); + } + catch { } + } + + private void resetToolStripMenuItem_Click(object sender, EventArgs e) + { + dockContainer1.Clear(); + SetupDocking(); + cleanupDocks(); + this.Refresh(); } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx index 3637f0f2ed..7325e52b19 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx @@ -117,14 +117,47 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Fill - + + 290, 17 + - - 0, 0 + + 174, 22 + + Fly To Here + + + 174, 22 + + + Fly To Here Alt + + + 174, 22 + + + Point Camera Here + + + 174, 22 + + + Flight Planner + + + 175, 92 + + + contextMenuStripMap + + + System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 186, 70 + + 0, 0, 0, 0 @@ -140,7 +173,7 @@ Horizontal - + 542, 17 @@ -179,13 +212,13 @@ User Items - + 177, 158 - - contextMenuStrip2 + + contextMenuStripHud - + System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 @@ -198,7 +231,7 @@ 0, 0 - 415, 311 + 358, 263 @@ -208,7 +241,7 @@ hud1 - ArdupilotMega.Controls.HUD, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.HUD, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null SubMainLeft.Panel1 @@ -238,7 +271,7 @@ 3, 278 - 384, 55 + 327, 55 5 @@ -247,7 +280,7 @@ quickView6 - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabQuick @@ -262,7 +295,7 @@ 3, 223 - 384, 55 + 327, 55 4 @@ -271,7 +304,7 @@ quickView5 - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabQuick @@ -286,7 +319,7 @@ 3, 168 - 384, 55 + 327, 55 3 @@ -295,7 +328,7 @@ quickView4 - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabQuick @@ -310,7 +343,7 @@ 3, 113 - 384, 55 + 327, 55 2 @@ -319,7 +352,7 @@ quickView3 - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabQuick @@ -334,7 +367,7 @@ 3, 58 - 384, 55 + 327, 55 1 @@ -343,7 +376,7 @@ quickView2 - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabQuick @@ -358,7 +391,7 @@ 3, 3 - 384, 55 + 327, 55 0 @@ -367,7 +400,7 @@ quickView1 - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabQuick @@ -382,7 +415,7 @@ 3, 3, 3, 3 - 407, 116 + 350, 94 4 @@ -421,7 +454,7 @@ BUT_script - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -454,7 +487,7 @@ BUT_joystick - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -484,7 +517,7 @@ BUT_quickmanual - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -514,7 +547,7 @@ BUT_quickrtl - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -544,7 +577,7 @@ BUT_quickauto - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -598,7 +631,7 @@ BUT_setwp - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -649,7 +682,7 @@ BUT_setmode - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -679,7 +712,7 @@ BUT_clear_track - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -730,7 +763,7 @@ BUT_Homealt - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -760,7 +793,7 @@ BUT_RAWSensor - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -790,7 +823,7 @@ BUTrestartmission - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -820,7 +853,7 @@ BUTactiondo - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabActions @@ -832,7 +865,7 @@ 4, 22 - 407, 116 + 350, 94 2 @@ -874,7 +907,7 @@ Gvspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabGauges @@ -904,7 +937,7 @@ Gheading - ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabGauges @@ -934,7 +967,7 @@ Galt - AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabGauges @@ -967,7 +1000,7 @@ Gspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabGauges @@ -982,7 +1015,7 @@ 3, 3, 3, 3 - 407, 116 + 350, 94 0 @@ -1012,7 +1045,7 @@ 3, 3, 3, 3 - 407, 116 + 350, 94 1 @@ -1036,7 +1069,7 @@ Top, Right - 353, 54 + 253, 54 51, 20 @@ -1051,7 +1084,7 @@ lbl_playbackspeed - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1063,7 +1096,7 @@ Top, Right - 353, 32 + 253, 32 51, 20 @@ -1078,7 +1111,7 @@ lbl_logpercent - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1087,13 +1120,13 @@ 1 - Top, Bottom, Left, Right + Top, Left, Right 178, 40 - 169, 45 + 73, 45 77 @@ -1105,7 +1138,7 @@ NUM_playbackspeed - ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1132,7 +1165,7 @@ BUT_log2kml - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1150,7 +1183,7 @@ 178, 3 - 226, 45 + 110, 45 75 @@ -1186,7 +1219,7 @@ BUT_playlog - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1213,7 +1246,7 @@ BUT_loadtelem - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1225,7 +1258,7 @@ 4, 22 - 407, 116 + 350, 94 3 @@ -1255,7 +1288,7 @@ 0, 0 - 415, 142 + 358, 120 84 @@ -1285,10 +1318,10 @@ 1 - 417, 461 + 360, 391 - 313 + 265 0 @@ -1345,7 +1378,7 @@ 4, 4, 4, 4 - 577, 210 + 448, 210 67 @@ -1377,42 +1410,6 @@ 0 - - 290, 17 - - - 174, 22 - - - Fly To Here - - - 174, 22 - - - Fly To Here Alt - - - 174, 22 - - - Point Camera Here - - - 174, 22 - - - Flight Planner - - - 175, 92 - - - contextMenuStrip1 - - - System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - NoControl @@ -1435,7 +1432,7 @@ lbl_winddir - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1465,7 +1462,7 @@ lbl_windvel - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1480,7 +1477,7 @@ NoControl - -1, 390 + -1, 320 43, 12 @@ -1498,7 +1495,7 @@ lbl_hdop - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1513,7 +1510,7 @@ NoControl - -1, 408 + -1, 338 40, 12 @@ -1531,7 +1528,7 @@ lbl_sats - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1549,7 +1546,7 @@ 0, 0, 0, 0 - 577, 420 + 448, 350 @@ -1703,7 +1700,7 @@ gMapControl1 - ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1724,7 +1721,7 @@ 1 - 577, 420 + 448, 350 210 @@ -1766,7 +1763,7 @@ TXT_lat - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null panel1 @@ -1823,7 +1820,7 @@ label1 - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null panel1 @@ -1853,7 +1850,7 @@ TXT_long - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null panel1 @@ -1883,7 +1880,7 @@ TXT_alt - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null panel1 @@ -1967,13 +1964,13 @@ Fill - 1, 428 + 1, 358 0, 0, 0, 0 - 583, 30 + 454, 30 0 @@ -2000,7 +1997,7 @@ 2 - 585, 459 + 456, 389 75 @@ -2033,14 +2030,17 @@ 1 - 1008, 461 + 822, 391 - 417 + 360 68 + + False + MainH @@ -2051,7 +2051,7 @@ $this - 2 + 3 Up @@ -2068,29 +2068,47 @@ 17, 17 - - NoControl + + 714, 17 + + + 152, 22 - + + Reset + + + 103, 26 + + + contextMenuStripDockContainer + + + System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Fill + + 0, 0 - - 100, 23 + + 1008, 461 - - 47 + + 69 - - label6 + + dockContainer1 - - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + + Crom.Controls.Docking.DockContainer, Crom.Controls, Version=2.0.5.21, Culture=neutral, PublicKeyToken=null - + $this - - 3 + + 4 True @@ -2104,6 +2122,30 @@ 1008, 461 + + goHereToolStripMenuItem + + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + flyToHereAltToolStripMenuItem + + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + pointCameraHereToolStripMenuItem + + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + flightPlannerToolStripMenuItem + + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + recordHudToAVIToolStripMenuItem @@ -2146,30 +2188,6 @@ System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - goHereToolStripMenuItem - - - System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - flyToHereAltToolStripMenuItem - - - System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - pointCameraHereToolStripMenuItem - - - System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - flightPlannerToolStripMenuItem - - - System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - dataGridViewImageColumn1 @@ -2194,10 +2212,16 @@ System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + resetToolStripMenuItem + + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + FlightData - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4639.27099, Culture=neutral, PublicKeyToken=null + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4646.13106, 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 6a3f4151b2..8ea54d7650 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs @@ -31,14 +31,14 @@ { this.components = new System.ComponentModel.Container(); System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightPlanner)); - System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle(); - System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle5 = new System.Windows.Forms.DataGridViewCellStyle(); - System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle6 = new System.Windows.Forms.DataGridViewCellStyle(); - System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle(); - System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle(); - System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle4 = new System.Windows.Forms.DataGridViewCellStyle(); - System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle7 = new System.Windows.Forms.DataGridViewCellStyle(); - System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle8 = new System.Windows.Forms.DataGridViewCellStyle(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle9 = new System.Windows.Forms.DataGridViewCellStyle(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle13 = new System.Windows.Forms.DataGridViewCellStyle(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle14 = new System.Windows.Forms.DataGridViewCellStyle(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle10 = new System.Windows.Forms.DataGridViewCellStyle(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle11 = new System.Windows.Forms.DataGridViewCellStyle(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle12 = new System.Windows.Forms.DataGridViewCellStyle(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle15 = new System.Windows.Forms.DataGridViewCellStyle(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle16 = new System.Windows.Forms.DataGridViewCellStyle(); this.CHK_altmode = new System.Windows.Forms.CheckBox(); this.CHK_holdalt = new System.Windows.Forms.CheckBox(); this.Commands = new System.Windows.Forms.DataGridView(); @@ -134,6 +134,7 @@ this.reverseWPsToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.fileLoadSaveToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.loadWPFileToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); + this.loadAndAppendToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.saveWPFileToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.trackerHomeToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.flyToHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); @@ -142,7 +143,8 @@ this.panelBASE = new System.Windows.Forms.Panel(); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); this.timer1 = new System.Windows.Forms.Timer(this.components); - this.loadAndAppendToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); + this.savePolygonToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); + this.loadPolygonToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); ((System.ComponentModel.ISupportInitialize)(this.Commands)).BeginInit(); this.panel5.SuspendLayout(); this.panel1.SuspendLayout(); @@ -174,14 +176,14 @@ // this.Commands.AllowUserToAddRows = false; resources.ApplyResources(this.Commands, "Commands"); - dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft; - dataGridViewCellStyle1.BackColor = System.Drawing.SystemColors.Control; - dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); - dataGridViewCellStyle1.ForeColor = System.Drawing.SystemColors.WindowText; - dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight; - dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText; - dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True; - this.Commands.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1; + dataGridViewCellStyle9.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft; + dataGridViewCellStyle9.BackColor = System.Drawing.SystemColors.Control; + dataGridViewCellStyle9.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); + dataGridViewCellStyle9.ForeColor = System.Drawing.SystemColors.WindowText; + dataGridViewCellStyle9.SelectionBackColor = System.Drawing.SystemColors.Highlight; + dataGridViewCellStyle9.SelectionForeColor = System.Drawing.SystemColors.HighlightText; + dataGridViewCellStyle9.WrapMode = System.Windows.Forms.DataGridViewTriState.True; + this.Commands.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle9; this.Commands.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] { this.Command, this.Param1, @@ -195,17 +197,17 @@ this.Up, this.Down}); this.Commands.Name = "Commands"; - dataGridViewCellStyle5.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft; - dataGridViewCellStyle5.BackColor = System.Drawing.SystemColors.Control; - dataGridViewCellStyle5.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); - dataGridViewCellStyle5.ForeColor = System.Drawing.SystemColors.WindowText; - dataGridViewCellStyle5.Format = "N0"; - dataGridViewCellStyle5.NullValue = "0"; - dataGridViewCellStyle5.SelectionBackColor = System.Drawing.SystemColors.Highlight; - dataGridViewCellStyle5.SelectionForeColor = System.Drawing.SystemColors.HighlightText; - this.Commands.RowHeadersDefaultCellStyle = dataGridViewCellStyle5; - dataGridViewCellStyle6.ForeColor = System.Drawing.Color.Black; - this.Commands.RowsDefaultCellStyle = dataGridViewCellStyle6; + dataGridViewCellStyle13.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft; + dataGridViewCellStyle13.BackColor = System.Drawing.SystemColors.Control; + dataGridViewCellStyle13.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0))); + dataGridViewCellStyle13.ForeColor = System.Drawing.SystemColors.WindowText; + dataGridViewCellStyle13.Format = "N0"; + dataGridViewCellStyle13.NullValue = "0"; + dataGridViewCellStyle13.SelectionBackColor = System.Drawing.SystemColors.Highlight; + dataGridViewCellStyle13.SelectionForeColor = System.Drawing.SystemColors.HighlightText; + this.Commands.RowHeadersDefaultCellStyle = dataGridViewCellStyle13; + dataGridViewCellStyle14.ForeColor = System.Drawing.Color.Black; + this.Commands.RowsDefaultCellStyle = dataGridViewCellStyle14; this.Commands.CellContentClick += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellContentClick); this.Commands.CellEndEdit += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellEndEdit); this.Commands.DataError += new System.Windows.Forms.DataGridViewDataErrorEventHandler(this.Commands_DataError); @@ -217,9 +219,9 @@ // // Command // - dataGridViewCellStyle2.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69))))); - dataGridViewCellStyle2.ForeColor = System.Drawing.Color.White; - this.Command.DefaultCellStyle = dataGridViewCellStyle2; + dataGridViewCellStyle10.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69))))); + dataGridViewCellStyle10.ForeColor = System.Drawing.Color.White; + this.Command.DefaultCellStyle = dataGridViewCellStyle10; this.Command.DisplayStyle = System.Windows.Forms.DataGridViewComboBoxDisplayStyle.ComboBox; resources.ApplyResources(this.Command, "Command"); this.Command.Name = "Command"; @@ -285,7 +287,7 @@ // // Up // - this.Up.DefaultCellStyle = dataGridViewCellStyle3; + this.Up.DefaultCellStyle = dataGridViewCellStyle11; resources.ApplyResources(this.Up, "Up"); this.Up.Image = global::ArdupilotMega.Properties.Resources.up; this.Up.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; @@ -293,8 +295,8 @@ // // Down // - dataGridViewCellStyle4.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; - this.Down.DefaultCellStyle = dataGridViewCellStyle4; + dataGridViewCellStyle12.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; + this.Down.DefaultCellStyle = dataGridViewCellStyle12; resources.ApplyResources(this.Down, "Down"); this.Down.Image = global::ArdupilotMega.Properties.Resources.down; this.Down.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; @@ -418,8 +420,8 @@ // // dataGridViewImageColumn1 // - dataGridViewCellStyle7.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; - this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle7; + dataGridViewCellStyle15.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; + this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle15; resources.ApplyResources(this.dataGridViewImageColumn1, "dataGridViewImageColumn1"); this.dataGridViewImageColumn1.Image = global::ArdupilotMega.Properties.Resources.up; this.dataGridViewImageColumn1.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; @@ -427,8 +429,8 @@ // // dataGridViewImageColumn2 // - dataGridViewCellStyle8.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; - this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle8; + dataGridViewCellStyle16.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; + this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle16; resources.ApplyResources(this.dataGridViewImageColumn2, "dataGridViewImageColumn2"); this.dataGridViewImageColumn2.Image = global::ArdupilotMega.Properties.Resources.down; this.dataGridViewImageColumn2.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; @@ -765,7 +767,9 @@ // this.polygonToolStripMenuItem.DropDownItems.AddRange(new System.Windows.Forms.ToolStripItem[] { this.addPolygonPointToolStripMenuItem, - this.clearPolygonToolStripMenuItem}); + this.clearPolygonToolStripMenuItem, + this.savePolygonToolStripMenuItem, + this.loadPolygonToolStripMenuItem}); this.polygonToolStripMenuItem.Name = "polygonToolStripMenuItem"; resources.ApplyResources(this.polygonToolStripMenuItem, "polygonToolStripMenuItem"); // @@ -938,6 +942,12 @@ resources.ApplyResources(this.loadWPFileToolStripMenuItem, "loadWPFileToolStripMenuItem"); this.loadWPFileToolStripMenuItem.Click += new System.EventHandler(this.loadWPFileToolStripMenuItem_Click); // + // loadAndAppendToolStripMenuItem + // + this.loadAndAppendToolStripMenuItem.Name = "loadAndAppendToolStripMenuItem"; + resources.ApplyResources(this.loadAndAppendToolStripMenuItem, "loadAndAppendToolStripMenuItem"); + this.loadAndAppendToolStripMenuItem.Click += new System.EventHandler(this.loadAndAppendToolStripMenuItem_Click); + // // saveWPFileToolStripMenuItem // this.saveWPFileToolStripMenuItem.Name = "saveWPFileToolStripMenuItem"; @@ -990,11 +1000,17 @@ this.timer1.Interval = 1000; this.timer1.Tick += new System.EventHandler(this.timer1_Tick); // - // loadAndAppendToolStripMenuItem + // savePolygonToolStripMenuItem // - this.loadAndAppendToolStripMenuItem.Name = "loadAndAppendToolStripMenuItem"; - resources.ApplyResources(this.loadAndAppendToolStripMenuItem, "loadAndAppendToolStripMenuItem"); - this.loadAndAppendToolStripMenuItem.Click += new System.EventHandler(this.loadAndAppendToolStripMenuItem_Click); + this.savePolygonToolStripMenuItem.Name = "savePolygonToolStripMenuItem"; + resources.ApplyResources(this.savePolygonToolStripMenuItem, "savePolygonToolStripMenuItem"); + this.savePolygonToolStripMenuItem.Click += new System.EventHandler(this.savePolygonToolStripMenuItem_Click); + // + // loadPolygonToolStripMenuItem + // + this.loadPolygonToolStripMenuItem.Name = "loadPolygonToolStripMenuItem"; + resources.ApplyResources(this.loadPolygonToolStripMenuItem, "loadPolygonToolStripMenuItem"); + this.loadPolygonToolStripMenuItem.Click += new System.EventHandler(this.loadPolygonToolStripMenuItem_Click); // // FlightPlanner // @@ -1131,5 +1147,7 @@ private System.Windows.Forms.ToolStripMenuItem gridV2ToolStripMenuItem; private System.Windows.Forms.ToolStripMenuItem reverseWPsToolStripMenuItem; private System.Windows.Forms.ToolStripMenuItem loadAndAppendToolStripMenuItem; + private System.Windows.Forms.ToolStripMenuItem savePolygonToolStripMenuItem; + private System.Windows.Forms.ToolStripMenuItem loadPolygonToolStripMenuItem; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs index feaf8ea5ac..9ace26ea96 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs @@ -1419,7 +1419,7 @@ namespace ArdupilotMega.GCSViews return; } - int i = -1; + int i = Commands.Rows.Count - 1; foreach (Locationwp temp in cmds) { i++; @@ -1920,11 +1920,39 @@ namespace ArdupilotMega.GCSViews rc.Pen.Color = Color.Red; MainMap.Invalidate(false); + int answer; + if (int.TryParse(item.Tag.ToString(), out answer)) + { + try + { + Commands.CurrentCell = Commands[0, answer - 1]; + item.ToolTipText = "Alt: " + Commands[Alt.Index, answer - 1].Value.ToString(); + item.ToolTipMode = MarkerTooltipMode.OnMouseOver; + } + catch { } + } + CurentRectMarker = rc; } } } + // click on some marker + void MainMap_OnMarkerClick(GMapMarker item, MouseEventArgs e) + { + int answer; + try // when dragging item can sometimes be null + { + if (int.TryParse(item.Tag.ToString(), out answer)) + { + + Commands.CurrentCell = Commands[0, answer - 1]; + } + } + catch { } + return; + } + void MainMap_OnMapTypeChanged(MapType type) { comboBoxMapType.SelectedItem = MainMap.MapType; @@ -1949,6 +1977,8 @@ namespace ArdupilotMega.GCSViews { end = MainMap.FromLocalToLatLng(e.X, e.Y); + // Console.WriteLine("MainMap MU"); + if (e.Button == MouseButtons.Right) // ignore right clicks { return; @@ -2001,6 +2031,8 @@ namespace ArdupilotMega.GCSViews { start = MainMap.FromLocalToLatLng(e.X, e.Y); + // Console.WriteLine("MainMap MD"); + if (e.Button == MouseButtons.Left && Control.ModifierKeys != Keys.Alt) { isMouseDown = true; @@ -2018,6 +2050,11 @@ namespace ArdupilotMega.GCSViews { PointLatLng point = MainMap.FromLocalToLatLng(e.X, e.Y); + if (start == point) + return; + + // Console.WriteLine("MainMap MM " + point); + currentMarker.Position = point; if (!isMouseDown) @@ -2108,22 +2145,7 @@ namespace ArdupilotMega.GCSViews } } - // click on some marker - void MainMap_OnMarkerClick(GMapMarker item, MouseEventArgs e) - { - int answer; - try // when dragging item can sometimes be null - { - if (int.TryParse(item.Tag.ToString(), out answer)) - { - Commands.CurrentCell = Commands[0, answer - 1]; - - } - } - catch { } - return; - } // loader start loading tiles void MainMap_OnTileLoadStart() @@ -4204,5 +4226,89 @@ namespace ArdupilotMega.GCSViews readQGC110wpfile(file, true); } } + + private void savePolygonToolStripMenuItem_Click(object sender, EventArgs e) + { + if (drawnpolygon.Points.Count == 0) + { + return; + } + + + SaveFileDialog sf = new SaveFileDialog(); + sf.Filter = "Polygon (*.poly)|*.poly"; + sf.ShowDialog(); + if (sf.FileName != "") + { + try + { + StreamWriter sw = new StreamWriter(sf.OpenFile()); + + sw.WriteLine("#saved by APM Planner " + Application.ProductVersion); + + if (drawnpolygon.Points.Count > 0) + { + foreach (var pll in drawnpolygon.Points) + { + sw.WriteLine(pll.Lat + " " + pll.Lng); + } + + PointLatLng pll2 = drawnpolygon.Points[0]; + + sw.WriteLine(pll2.Lat + " " + pll2.Lng); + } + + sw.Close(); + } + catch { CustomMessageBox.Show("Failed to write fence file"); } + } + } + + private void loadPolygonToolStripMenuItem_Click(object sender, EventArgs e) + { + OpenFileDialog fd = new OpenFileDialog(); + fd.Filter = "Polygon (*.poly)|*.poly"; + fd.ShowDialog(); + if (File.Exists(fd.FileName)) + { + StreamReader sr = new StreamReader(fd.OpenFile()); + + drawnpolygons.Markers.Clear(); + drawnpolygons.Polygons.Clear(); + drawnpolygon.Points.Clear(); + + int a = 0; + + while (!sr.EndOfStream) + { + string line = sr.ReadLine(); + if (line.StartsWith("#")) + { + continue; + } + else + { + string[] items = line.Split(new char[] { ' ', '\t' }, StringSplitOptions.RemoveEmptyEntries); + + drawnpolygon.Points.Add(new PointLatLng(double.Parse(items[0]), double.Parse(items[1]))); + addpolygonmarkergrid(drawnpolygon.Points.Count.ToString(), double.Parse(items[1]), double.Parse(items[0]), 0); + + a++; + } + } + + // remove loop close + if (drawnpolygon.Points[0] == drawnpolygon.Points[drawnpolygon.Points.Count - 1]) + { + drawnpolygon.Points.RemoveAt(drawnpolygon.Points.Count - 1); + } + + drawnpolygons.Polygons.Add(drawnpolygon); + + MainMap.UpdatePolygonLocalPosition(drawnpolygon); + + MainMap.Invalidate(); + } + } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx index 5c85b8b4f5..428a650e8b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx @@ -537,26 +537,11 @@ Bottom, Right - - NoControl - - - 7, 32 - - - 107, 23 - - - 8 - - - Write WPs - BUT_write - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4627.35768, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4637.40284, Culture=neutral, PublicKeyToken=null panel5 @@ -564,26 +549,11 @@ 0 - - NoControl - - - 6, 4 - - - 107, 23 - - - 7 - - - Read WPs - BUT_read - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4627.35768, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4637.40284, Culture=neutral, PublicKeyToken=null panel5 @@ -612,9 +582,168 @@ 0 + + NoControl + + + 7, 32 + + + 107, 23 + + + 8 + + + Write WPs + + + BUT_write + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4637.40284, Culture=neutral, PublicKeyToken=null + + + panel5 + + + 0 + + + NoControl + + + 6, 4 + + + 107, 23 + + + 7 + + + Read WPs + + + BUT_read + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4637.40284, Culture=neutral, PublicKeyToken=null + + + panel5 + + + 1 + Bottom, Right + + label4 + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 0 + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 1 + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 2 + + + Label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 3 + + + TXT_homealt + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 4 + + + TXT_homelng + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 5 + + + TXT_homelat + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 6 + + + 8, 365 + + + 117, 89 + + + 31 + + + panel1 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panelAction + + + 1 + True @@ -798,27 +927,6 @@ 6 - - 8, 365 - - - 117, 89 - - - 31 - - - panel1 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panelAction - - - 1 - Up @@ -858,6 +966,111 @@ Bottom, Right + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel2 + + + 0 + + + label8 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel2 + + + 1 + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel2 + + + 2 + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel2 + + + 3 + + + TXT_mousealt + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel2 + + + 4 + + + TXT_mouselong + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel2 + + + 5 + + + TXT_mouselat + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel2 + + + 6 + + + 8, 177 + + + 114, 79 + + + 38 + + + panel2 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panelAction + + + 2 + True @@ -1041,27 +1254,6 @@ 6 - - 8, 177 - - - 114, 79 - - - 38 - - - panel2 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panelAction - - - 2 - Bottom, Right @@ -1122,6 +1314,9 @@ 0 + + 172, 17 + NoControl @@ -1137,9 +1332,6 @@ Add Below - - 172, 17 - Add a line to the grid bellow @@ -1147,7 +1339,7 @@ BUT_Add - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4627.35768, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4637.40284, Culture=neutral, PublicKeyToken=null panelWaypoints @@ -1338,42 +1530,12 @@ Delete WP - - 113, 22 - - - Forever - - - 113, 22 - - - Time - - - 113, 22 - - - Circles - 152, 22 Loiter - - 102, 22 - - - Start - - - 102, 22 - - - WP # - 152, 22 @@ -1425,153 +1587,42 @@ Clear Polygon + + 174, 22 + + + Save Polygon + + + 174, 22 + + + Load Polygon + 152, 22 Draw Polygon - - 177, 22 - - - Complex - - - 174, 6 - - - 177, 22 - - - Upload - - - 177, 22 - - - Download - - - 177, 22 - - - Set Return Location - - - 177, 22 - - - Load from File - - - 177, 22 - - - Save to File - 152, 22 Geo-Fence - - 162, 22 - - - Create Wp Circle - - - 162, 22 - - - Grid - - - 162, 22 - - - GridV2 - 152, 22 Auto WP - - 167, 22 - - - Measure Distance - - - 167, 22 - - - Rotate Map - - - 167, 22 - - - Zoom To - - - 167, 22 - - - Prefetch - - - 167, 22 - - - KML Overlay - - - 167, 22 - - - Elevation Graph - - - 167, 22 - - - Camera - - - 167, 22 - - - Reverse WPs - 152, 22 Map Tool - - 168, 22 - - - Load WP File - - - 168, 22 - - - Load and Append - - - 168, 22 - - - Save WP File - 152, 22 @@ -1760,7 +1811,7 @@ MainMap - ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4627.35768, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4637.40284, Culture=neutral, PublicKeyToken=null panelMap @@ -1790,7 +1841,7 @@ trackBar1 - ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4627.35768, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4637.40284, Culture=neutral, PublicKeyToken=null panelMap @@ -1858,6 +1909,159 @@ 1 + + 113, 22 + + + Forever + + + 113, 22 + + + Time + + + 113, 22 + + + Circles + + + 102, 22 + + + Start + + + 102, 22 + + + WP # + + + 177, 22 + + + Complex + + + 174, 6 + + + 177, 22 + + + Upload + + + 177, 22 + + + Download + + + 177, 22 + + + Set Return Location + + + 177, 22 + + + Load from File + + + 177, 22 + + + Save to File + + + 162, 22 + + + Create Wp Circle + + + 162, 22 + + + Grid + + + 162, 22 + + + GridV2 + + + 167, 22 + + + Measure Distance + + + 167, 22 + + + Rotate Map + + + 167, 22 + + + Zoom To + + + 167, 22 + + + Prefetch + + + 167, 22 + + + KML Overlay + + + 167, 22 + + + Elevation Graph + + + 167, 22 + + + Camera + + + 167, 22 + + + Reverse WPs + + + 168, 22 + + + Load WP File + + + 168, 22 + + + Load and Append + + + 168, 22 + + + Save WP File + Fill @@ -1882,6 +2086,9 @@ 1 + + 172, 17 + 269, 17 @@ -2215,6 +2422,12 @@ System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + loadAndAppendToolStripMenuItem + + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + saveWPFileToolStripMenuItem @@ -2245,16 +2458,22 @@ System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - loadAndAppendToolStripMenuItem + + savePolygonToolStripMenuItem - + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + loadPolygonToolStripMenuItem + + System.Windows.Forms.ToolStripMenuItem, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 FlightPlanner - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4627.35768, Culture=neutral, PublicKeyToken=null + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4637.40284, Culture=neutral, PublicKeyToken=null \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs index 2b945ef5ea..c583701f2f 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs @@ -336,7 +336,7 @@ namespace ArdupilotMega.GCSViews System.Threading.Thread t11 = new System.Threading.Thread(new System.Threading.ThreadStart(mainloop)) { - Name = "Main Serial/UDP listener", + Name = "Main simu Serial/UDP listener", IsBackground = true }; t11.Start(); @@ -638,7 +638,7 @@ namespace ArdupilotMega.GCSViews if (hzcounttime.Second != DateTime.Now.Second) { - Console.WriteLine("SIM hz {0}", hzcount); + // Console.WriteLine("SIM hz {0}", hzcount); hzcount = 0; hzcounttime = DateTime.Now; } diff --git a/Tools/ArdupilotMegaPlanner/HIL/AeroSimRC.cs b/Tools/ArdupilotMegaPlanner/HIL/AeroSimRC.cs new file mode 100644 index 0000000000..e107929b29 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/HIL/AeroSimRC.cs @@ -0,0 +1,11 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; + +namespace ArdupilotMega.HIL +{ + class AeroSimRC : Hil + { + } +} diff --git a/Tools/ArdupilotMegaPlanner/HIL/FlightGear.cs b/Tools/ArdupilotMegaPlanner/HIL/FlightGear.cs new file mode 100644 index 0000000000..29ab14dd82 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/HIL/FlightGear.cs @@ -0,0 +1,11 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; + +namespace ArdupilotMega.HIL +{ + class FlightGear : Hil + { + } +} diff --git a/Tools/ArdupilotMegaPlanner/HIL/Hil.cs b/Tools/ArdupilotMegaPlanner/HIL/Hil.cs new file mode 100644 index 0000000000..43f17da700 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/HIL/Hil.cs @@ -0,0 +1,93 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; +using log4net; +using System.Reflection; +using System.Runtime.InteropServices; + +namespace ArdupilotMega.HIL +{ + public delegate void ProgressEventHandler(int progress, string status); + + public abstract class Hil + { + internal static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType); + + [StructLayout(LayoutKind.Sequential, Pack = 1)] + public struct sitl_fdm + { + // this is the packet sent by the simulator + // to the APM executable to update the simulator state + // All values are little-endian + public double latitude, longitude; // degrees + public double altitude; // MSL + public double heading; // degrees + public double speedN, speedE; // m/s + public double xAccel, yAccel, zAccel; // m/s/s in body frame + public double rollRate, pitchRate, yawRate; // degrees/s/s in earth frame + public double rollDeg, pitchDeg, yawDeg; // euler angles, degrees + public double airspeed; // m/s + public UInt32 magic; // 0x4c56414e + }; + + public const float ft2m = (float)(1.0 / 3.2808399); + public const float rad2deg = (float)(180 / Math.PI); + public const float deg2rad = (float)(1.0 / rad2deg); + public const float kts2fps = (float)1.68780986; + + internal DateTime lastgpsupdate = DateTime.Now; + internal sitl_fdm[] sitl_fdmbuffer = new sitl_fdm[5]; + internal sitl_fdm oldgps = new sitl_fdm(); + + // gps buffer + internal int gpsbufferindex = 0; + + internal int REV_pitch = 1; + internal int REV_roll = 1; + internal int REV_rudder = 1; + internal int GPS_rate = 200; + + internal int rollgain = 10000; + internal int pitchgain = 10000; + internal int ruddergain = 10000; + internal int throttlegain = 10000; + + public float roll_out, pitch_out, throttle_out, rudder_out, collective_out; + + public event ProgressEventHandler Status; + + public bool sitl { get; set; } + public bool heli { get; set; } + public bool quad { get; set; } + public bool xplane10 { get; set; } + + public abstract void SetupSockets(int Recvport, int SendPort, string SimIP); + public abstract void Shutdown(); + + public abstract void GetFromSim(ref sitl_fdm data); + public abstract void SendToSim(); + public abstract void SendToAP(sitl_fdm data); + public abstract void GetFromAP(); + + internal void UpdateStatus(int progress, string status) + { + if (Status != null) + Status(progress, status); + } + + internal float Constrain(float value, float min, float max) + { + if (value > max) { value = max; } + if (value < min) { value = min; } + return value; + } + + internal short Constrain(double value, double min, double max) + { + if (value > max) { value = max; } + if (value < min) { value = min; } + return (short)value; + } + } +} diff --git a/Tools/ArdupilotMegaPlanner/HIL/JSBSim.cs b/Tools/ArdupilotMegaPlanner/HIL/JSBSim.cs new file mode 100644 index 0000000000..9d7cd5476c --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/HIL/JSBSim.cs @@ -0,0 +1,11 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; + +namespace ArdupilotMega.HIL +{ + class JSBSim : Hil + { + } +} diff --git a/Tools/ArdupilotMegaPlanner/HIL/XPlane.cs b/Tools/ArdupilotMegaPlanner/HIL/XPlane.cs new file mode 100644 index 0000000000..84c4b51bf8 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/HIL/XPlane.cs @@ -0,0 +1,360 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; +using System.Net; +using System.Net.Sockets; + +namespace ArdupilotMega.HIL +{ + class XPlane : Hil + { + Socket SimulatorRECV; + UdpClient XplanesSEND; + EndPoint Remote = (EndPoint)(new IPEndPoint(IPAddress.Any, 0)); + + // place to store the xplane packet data + float[][] DATA = new float[113][]; + + public override void SetupSockets(int recvPort, int SendPort, string simIP) + { + // setup receiver + IPEndPoint ipep = new IPEndPoint(IPAddress.Any, recvPort); + + SimulatorRECV = new Socket(AddressFamily.InterNetwork, + SocketType.Dgram, ProtocolType.Udp); + + SimulatorRECV.Bind(ipep); + + UpdateStatus(-1, "Listerning on port UDP " + recvPort + " (sim->planner)\n"); + + + // setup sender + XplanesSEND = new UdpClient(simIP, SendPort); + + UpdateStatus(-1, "Sending to port UDP " + SendPort + " (planner->sim)\n"); + + setupXplane(); + + UpdateStatus(-1, "Sent xplane settings\n"); + } + public override void Shutdown() + { + try + { + SimulatorRECV.Close(); + } + catch { } + try + { + XplanesSEND.Close(); + } + catch { } + } + + public override void GetFromSim(ref sitl_fdm sitldata) + { + if (SimulatorRECV.Available > 0) + { + byte[] udpdata = new byte[1500]; + int receviedbytes = 0; + try + { + while (SimulatorRECV.Available > 0) + { + receviedbytes = SimulatorRECV.ReceiveFrom(udpdata, ref Remote); + } + } + catch { } + + if (udpdata[0] == 'D' && udpdata[1] == 'A') + { + // Xplanes sends + // 5 byte header + // 1 int for the index - numbers on left of output + // 8 floats - might be useful. or 0 if not + int count = 5; + while (count < receviedbytes) + { + int index = BitConverter.ToInt32(udpdata, count); + + DATA[index] = new float[8]; + + DATA[index][0] = BitConverter.ToSingle(udpdata, count + 1 * 4); ; + DATA[index][1] = BitConverter.ToSingle(udpdata, count + 2 * 4); ; + DATA[index][2] = BitConverter.ToSingle(udpdata, count + 3 * 4); ; + DATA[index][3] = BitConverter.ToSingle(udpdata, count + 4 * 4); ; + DATA[index][4] = BitConverter.ToSingle(udpdata, count + 5 * 4); ; + DATA[index][5] = BitConverter.ToSingle(udpdata, count + 6 * 4); ; + DATA[index][6] = BitConverter.ToSingle(udpdata, count + 7 * 4); ; + DATA[index][7] = BitConverter.ToSingle(udpdata, count + 8 * 4); ; + + count += 36; // 8 * float + } + + bool xplane9 = !xplane10; + + if (xplane9) + { + sitldata.pitchDeg = (DATA[18][0]); + sitldata.rollDeg = (DATA[18][1]); + sitldata.yawDeg = (DATA[18][2]); + sitldata.pitchRate = (DATA[17][0] * rad2deg); + sitldata.rollRate = (DATA[17][1] * rad2deg); + sitldata.yawRate = (DATA[17][2] * rad2deg); + + sitldata.heading = ((float)DATA[19][2]); + } + else + { + sitldata.pitchDeg = (DATA[17][0]); + sitldata.rollDeg = (DATA[17][1]); + sitldata.yawDeg = (DATA[17][2]); + sitldata.pitchRate = (DATA[16][0] * rad2deg); + sitldata.rollRate = (DATA[16][1] * rad2deg); + sitldata.yawRate = (DATA[16][2] * rad2deg); + + sitldata.heading = (DATA[18][2]); + } + + sitldata.airspeed = ((DATA[3][5] * .44704)); + + sitldata.latitude = (DATA[20][0]); + sitldata.longitude = (DATA[20][1]); + sitldata.altitude = (DATA[20][2] * ft2m); + + sitldata.speedN = DATA[21][3];// (DATA[3][7] * 0.44704 * Math.Sin(sitldata.heading * deg2rad)); + sitldata.speedE = -DATA[21][5];// (DATA[3][7] * 0.44704 * Math.Cos(sitldata.heading * deg2rad)); + + Matrix3 dcm = new Matrix3(); + dcm.from_euler(sitldata.rollDeg * deg2rad, sitldata.pitchDeg * deg2rad, sitldata.yawDeg * deg2rad); + + // rad = tas^2 / (tan(angle) * G) + float turnrad = (float)(((DATA[3][7] * 0.44704) * (DATA[3][7] * 0.44704)) / (float)(9.8f * Math.Tan(sitldata.rollDeg * deg2rad))); + + float gload = (float)(1 / Math.Cos(sitldata.rollDeg * deg2rad)); // calculated Gs + + // a = v^2/r + float centripaccel = (float)((DATA[3][7] * 0.44704) * (DATA[3][7] * 0.44704)) / turnrad; + + Vector3 accel_body = dcm.transposed() * (new Vector3(0, 0, -9.8)); + + Vector3 centrip_accel = new Vector3(0, centripaccel * Math.Cos(sitldata.rollDeg * deg2rad), centripaccel * Math.Sin(sitldata.rollDeg * deg2rad)); + + accel_body -= centrip_accel; + + sitldata.xAccel = DATA[4][5] * 9.8; + sitldata.yAccel = DATA[4][6] * 9.8; + sitldata.zAccel = (0 - DATA[4][4]) * 9.8; + + // Console.WriteLine(accel_body.ToString()); + // Console.WriteLine(" {0} {1} {2}",sitldata.xAccel, sitldata.yAccel, sitldata.zAccel); + + } + } + } + public override void SendToSim() + { + roll_out = (float)MainV2.cs.hilch1 / rollgain; + pitch_out = (float)MainV2.cs.hilch2 / pitchgain; + throttle_out = ((float)MainV2.cs.hilch3) / throttlegain; + rudder_out = (float)MainV2.cs.hilch4 / ruddergain; + + // Limit min and max + roll_out = Constrain(roll_out, -1, 1); + pitch_out = Constrain(pitch_out, -1, 1); + rudder_out = Constrain(rudder_out, -1, 1); + throttle_out = Constrain(throttle_out, 0, 1); + + // sending only 1 packet instead of many. + + byte[] Xplane = new byte[5 + 36 + 36]; + + if (heli) + { + Xplane = new byte[5 + 36 + 36 + 36]; + } + + Xplane[0] = (byte)'D'; + Xplane[1] = (byte)'A'; + Xplane[2] = (byte)'T'; + Xplane[3] = (byte)'A'; + Xplane[4] = 0; + + Array.Copy(BitConverter.GetBytes((int)25), 0, Xplane, 5, 4); // packet index + + Array.Copy(BitConverter.GetBytes((float)throttle_out), 0, Xplane, 9, 4); // start data + Array.Copy(BitConverter.GetBytes((float)throttle_out), 0, Xplane, 13, 4); + Array.Copy(BitConverter.GetBytes((float)throttle_out), 0, Xplane, 17, 4); + Array.Copy(BitConverter.GetBytes((float)throttle_out), 0, Xplane, 21, 4); + + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 25, 4); + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 29, 4); + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 33, 4); + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 37, 4); + + // NEXT ONE - control surfaces + + Array.Copy(BitConverter.GetBytes((int)11), 0, Xplane, 41, 4); // packet index + + Array.Copy(BitConverter.GetBytes((float)(pitch_out * REV_pitch)), 0, Xplane, 45, 4); // start data + Array.Copy(BitConverter.GetBytes((float)(roll_out * REV_roll)), 0, Xplane, 49, 4); + Array.Copy(BitConverter.GetBytes((float)(rudder_out * REV_rudder)), 0, Xplane, 53, 4); + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 57, 4); + + Array.Copy(BitConverter.GetBytes((float)(roll_out * REV_roll * 0.5)), 0, Xplane, 61, 4); + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 65, 4); + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 69, 4); + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, 73, 4); + + if (heli) + { + Array.Copy(BitConverter.GetBytes((float)(0)), 0, Xplane, 53, 4); + + + int a = 73 + 4; + Array.Copy(BitConverter.GetBytes((int)39), 0, Xplane, a, 4); // packet index + a += 4; + Array.Copy(BitConverter.GetBytes((float)(12 * collective_out)), 0, Xplane, a, 4); // main rotor 0 - 12 + a += 4; + Array.Copy(BitConverter.GetBytes((float)(12 * rudder_out)), 0, Xplane, a, 4); // tail rotor -12 - 12 + a += 4; + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, a, 4); + a += 4; + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, a, 4); + a += 4; + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, a, 4); + a += 4; + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, a, 4); + a += 4; + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, a, 4); + a += 4; + Array.Copy(BitConverter.GetBytes((int)-999), 0, Xplane, a, 4); + } + + try + { + XplanesSEND.Send(Xplane, Xplane.Length); + + } + catch (Exception e) { log.Info("Xplanes udp send error " + e.Message); } + } + public override void SendToAP(sitl_fdm sitldata) + { + TimeSpan gpsspan = DateTime.Now - lastgpsupdate; + + // add gps delay + if (gpsspan.TotalMilliseconds >= GPS_rate) + { + lastgpsupdate = DateTime.Now; + + // save current fix = 3 + sitl_fdmbuffer[gpsbufferindex % sitl_fdmbuffer.Length] = sitldata; + + // Console.WriteLine((gpsbufferindex % gpsbuffer.Length) + " " + ((gpsbufferindex + (gpsbuffer.Length - 1)) % gpsbuffer.Length)); + + // return buffer index + 5 = (3 + 5) = 8 % 6 = 2 + oldgps = sitl_fdmbuffer[(gpsbufferindex + (sitl_fdmbuffer.Length - 1)) % sitl_fdmbuffer.Length]; + + //comPort.sendPacket(oldgps); + + gpsbufferindex++; + } + + MAVLink.mavlink_hil_state_t hilstate = new MAVLink.mavlink_hil_state_t(); + + hilstate.time_usec = (UInt64)DateTime.Now.Ticks; // microsec + + hilstate.lat = (int)(oldgps.latitude * 1e7); // * 1E7 + hilstate.lon = (int)(oldgps.longitude * 1e7); // * 1E7 + hilstate.alt = (int)(oldgps.altitude * 1000); // mm + + // Console.WriteLine(hilstate.alt); + + hilstate.pitch = (float)sitldata.pitchDeg * deg2rad; // (rad) + hilstate.pitchspeed = (float)sitldata.pitchRate * deg2rad; // (rad/s) + hilstate.roll = (float)sitldata.rollDeg * deg2rad; // (rad) + hilstate.rollspeed = (float)sitldata.rollRate * deg2rad; // (rad/s) + hilstate.yaw = (float)sitldata.yawDeg * deg2rad; // (rad) + hilstate.yawspeed = (float)sitldata.yawRate * deg2rad; // (rad/s) + + hilstate.vx = (short)(sitldata.speedN * 100); // m/s * 100 + hilstate.vy = (short)(sitldata.speedE * 100); // m/s * 100 + hilstate.vz = 0; // m/s * 100 + + hilstate.xacc = (short)(sitldata.xAccel * 1000); // (mg) + hilstate.yacc = (short)(sitldata.yAccel * 1000); // (mg) + hilstate.zacc = (short)(sitldata.zAccel * 1000); // (mg) + + MainV2.comPort.sendPacket(hilstate); + + MainV2.comPort.sendPacket(new MAVLink.mavlink_vfr_hud_t() + { + airspeed = (float)sitldata.airspeed + }); + } + public override void GetFromAP() { } + + void setupXplane() + { + // sending only 1 packet instead of many. + + byte[] Xplane = new byte[5 + 4 * 8]; + + Xplane[0] = (byte)'D'; + Xplane[1] = (byte)'S'; + Xplane[2] = (byte)'E'; + Xplane[3] = (byte)'L'; + Xplane[4] = 0; + + if (xplane10) + { + int pos = 5; + Xplane[pos] = 0x3; + pos += 4; + Xplane[pos] = 0x4; + pos += 4; + Xplane[pos] = 0x6; + pos += 4; + Xplane[pos] = 0x10; + pos += 4; + Xplane[pos] = 0x11; + pos += 4; + Xplane[pos] = 0x12; + pos += 4; + Xplane[pos] = 0x14; + pos += 4; + Xplane[pos] = 0x15; + pos += 4; + } + else + { + int pos = 5; + Xplane[pos] = 0x3; + pos += 4; + Xplane[pos] = 0x4; + pos += 4; + Xplane[pos] = 0x6; + pos += 4; + Xplane[pos] = 0x11; + pos += 4; + Xplane[pos] = 0x12; + pos += 4; + Xplane[pos] = 0x13; + pos += 4; + Xplane[pos] = 0x14; + pos += 4; + Xplane[pos] = 0x15; + pos += 4; + } + + try + { + XplanesSEND.Send(Xplane, Xplane.Length); + + } + catch (Exception e) { log.Info("Xplanes udp send error " + e.Message); } + + } + } +} \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index 73d9b54298..c4536d0712 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -260,7 +260,15 @@ namespace ArdupilotMega // preload Python.CreateEngine(); } - catch (Exception e) { CustomMessageBox.Show("A Major error has occured : " + e.ToString()); this.Close(); } + catch (ArgumentException e) { + //http://www.microsoft.com/en-us/download/details.aspx?id=16083 + //System.ArgumentException: Font 'Arial' does not support style 'Regular'. + + log.Fatal(e); + CustomMessageBox.Show(e.ToString() + "\n\n Please install this http://www.microsoft.com/en-us/download/details.aspx?id=16083"); + this.Close(); + } + catch (Exception e) { log.Fatal(e); CustomMessageBox.Show("A Major error has occured : " + e.ToString()); this.Close(); } if (MainV2.config["CHK_GDIPlus"] != null) GCSViews.FlightData.myhud.UseOpenGL = !bool.Parse(MainV2.config["CHK_GDIPlus"].ToString()); @@ -294,7 +302,7 @@ namespace ArdupilotMega if (config["CMB_rateattitude"] != null) MainV2.cs.rateattitude = byte.Parse(config["CMB_rateattitude"].ToString()); - if (config["rateposition"] != null) + if (config["CMB_rateposition"] != null) MainV2.cs.rateposition = byte.Parse(config["CMB_rateposition"].ToString()); if (config["CMB_ratestatus"] != null) MainV2.cs.ratestatus = byte.Parse(config["CMB_ratestatus"].ToString()); @@ -434,12 +442,6 @@ namespace ArdupilotMega private void MenuFlightData_Click(object sender, EventArgs e) { MyView.ShowScreen("FlightData"); - - if (MainV2.config["FlightSplitter"] != null) - { - FlightData.MainHcopy.SplitterDistance = int.Parse(MainV2.config["FlightSplitter"].ToString()) - 1; - FlightData.MainHcopy.SplitterDistance = int.Parse(MainV2.config["FlightSplitter"].ToString()); - } } private void MenuFlightPlanner_Click(object sender, EventArgs e) @@ -571,17 +573,22 @@ namespace ArdupilotMega comPort.BaseStream.DtrEnable = false; comPort.BaseStream.RtsEnable = false; + // prevent serialreader from doing anything + giveComport = true; + // reset on connect logic. if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true) comPort.BaseStream.toggleDTR(); + giveComport = false; + // setup to record new logs try { Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs"); - comPort.logfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".tlog", FileMode.CreateNew, FileAccess.ReadWrite, FileShare.Read)); + comPort.logfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".tlog", FileMode.CreateNew, FileAccess.ReadWrite, FileShare.None)); - comPort.rawlogfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".rlog", FileMode.CreateNew, FileAccess.ReadWrite, FileShare.Read)); + comPort.rawlogfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".rlog", FileMode.CreateNew, FileAccess.ReadWrite, FileShare.None)); } catch (Exception exp2) { log.Error(exp2); CustomMessageBox.Show("Failed to create log - wont log this session"); } // soft fail @@ -611,6 +618,13 @@ namespace ArdupilotMega // save the baudrate for this port config[_connectionControl.CMB_serialport.Text + "_BAUD"] = _connectionControl.CMB_baudrate.Text; + // refresh config window if needed + if (MyView.current != null && MyView.current.Name == "Config") + { + MyView.ShowScreen("Config"); + } + + // load wps on connect option. if (config["loadwpsonconnect"] != null && bool.Parse(config["loadwpsonconnect"].ToString()) == true) { @@ -671,7 +685,7 @@ namespace ArdupilotMega } } catch (Exception exp3) { log.Error(exp3); } - //MessageBox.Show("Can not establish a connection\n\n" + ex.ToString()); + MessageBox.Show("Can not establish a connection\n\n" + ex.Message); return; } } @@ -1124,7 +1138,11 @@ namespace ArdupilotMega // actauly read the packets while (comPort.BaseStream.BytesToRead > minbytes && giveComport == false) { - comPort.readPacket(); + try + { + comPort.readPacket(); + } + catch { } } } catch (Exception e) diff --git a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs index c93f913a5c..db01a3040b 100644 --- a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs +++ b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs @@ -87,15 +87,11 @@ namespace ArdupilotMega /// /// used as a serial port write lock /// - object objlock = new object(); + volatile object objlock = new object(); /// /// used for a readlock on readpacket /// - object readlock = new object(); - /// - /// used for tlog file lock - /// - object logwritelock = new object(); + volatile object readlock = new object(); /// /// time seen of last mavlink packet /// @@ -157,7 +153,6 @@ namespace ArdupilotMega this.WhenPacketLost = new Subject(); this.WhenPacketReceived = new Subject(); this.readlock = new object(); - this.logwritelock = new object(); this.lastvalidpacket = DateTime.Now; this.oldlogformat = false; this.mavlinkversion = 0; @@ -183,6 +178,22 @@ namespace ArdupilotMega public void Close() { + try + { + logfile.Close(); + } + catch { } + try + { + rawlogfile.Close(); + } + catch { } + try + { + logplaybackfile.Close(); + } + catch { } + BaseStream.Close(); } @@ -443,104 +454,100 @@ namespace ArdupilotMega /// struct of data void generatePacket(byte messageType, object indata) { - byte[] data; + lock (objlock) + { + byte[] data; - if (mavlinkversion == 3) - { - data = MavlinkUtil.StructureToByteArray(indata); - } - else - { - data = MavlinkUtil.StructureToByteArrayBigEndian(indata); - } + if (mavlinkversion == 3) + { + data = MavlinkUtil.StructureToByteArray(indata); + } + else + { + data = MavlinkUtil.StructureToByteArrayBigEndian(indata); + } - //Console.WriteLine(DateTime.Now + " PC Doing req "+ messageType + " " + this.BytesToRead); - byte[] packet = new byte[data.Length + 6 + 2]; + //Console.WriteLine(DateTime.Now + " PC Doing req "+ messageType + " " + this.BytesToRead); + byte[] packet = new byte[data.Length + 6 + 2]; - if (mavlinkversion == 3) - { - packet[0] = 254; - } - else if (mavlinkversion == 2) - { - packet[0] = (byte)'U'; - } - packet[1] = (byte)data.Length; - packet[2] = packetcount; - packet[3] = 255; // this is always 255 - MYGCS + if (mavlinkversion == 3) + { + packet[0] = 254; + } + else if (mavlinkversion == 2) + { + packet[0] = (byte)'U'; + } + packet[1] = (byte)data.Length; + packet[2] = packetcount; + + packetcount++; + + packet[3] = 255; // this is always 255 - MYGCS #if MAVLINK10 - packet[4] = (byte)MAV_COMPONENT.MAV_COMP_ID_MISSIONPLANNER; + packet[4] = (byte)MAV_COMPONENT.MAV_COMP_ID_MISSIONPLANNER; #else packet[4] = (byte)MAV_COMPONENT.MAV_COMP_ID_WAYPOINTPLANNER; #endif - packet[5] = messageType; + packet[5] = messageType; - int i = 6; - foreach (byte b in data) - { - packet[i] = b; - i++; - } - - ushort checksum = MavlinkCRC.crc_calculate(packet, packet[1] + 6); - - if (mavlinkversion == 3) - { - checksum = MavlinkCRC.crc_accumulate(MAVLINK_MESSAGE_CRCS[messageType], checksum); - } - - byte ck_a = (byte)(checksum & 0xFF); ///< High byte - byte ck_b = (byte)(checksum >> 8); ///< Low byte - - packet[i] = ck_a; - i += 1; - packet[i] = ck_b; - i += 1; - - if (BaseStream.IsOpen) - { - lock (objlock) + int i = 6; + foreach (byte b in data) { - BaseStream.Write(packet, 0, i); - } - _bytesSentSubj.OnNext(i); - } - - try - { - if (logfile != null && logfile.BaseStream.CanWrite) - { - lock (logwritelock) - { - byte[] datearray = BitConverter.GetBytes((UInt64)((DateTime.UtcNow - new DateTime(1970, 1, 1)).TotalMilliseconds * 1000)); //ASCIIEncoding.ASCII.GetBytes(DateTime.Now.ToBinary() + ":"); - Array.Reverse(datearray); - logfile.Write(datearray, 0, datearray.Length); - logfile.Write(packet, 0, i); - // logfile.Flush(); - } + packet[i] = b; + i++; } - } - catch { } + ushort checksum = MavlinkCRC.crc_calculate(packet, packet[1] + 6); + + if (mavlinkversion == 3) + { + checksum = MavlinkCRC.crc_accumulate(MAVLINK_MESSAGE_CRCS[messageType], checksum); + } + + byte ck_a = (byte)(checksum & 0xFF); ///< High byte + byte ck_b = (byte)(checksum >> 8); ///< Low byte + + packet[i] = ck_a; + i += 1; + packet[i] = ck_b; + i += 1; + + if (BaseStream.IsOpen) + { + BaseStream.Write(packet, 0, i); + _bytesSentSubj.OnNext(i); + } - if (messageType == ArdupilotMega.MAVLink.MAVLINK_MSG_ID_REQUEST_DATA_STREAM) - { try { - BinaryWriter bw = new BinaryWriter(File.OpenWrite("serialsent.raw")); - bw.Seek(0, SeekOrigin.End); - bw.Write(packet, 0, i); - bw.Write((byte)'\n'); - bw.Close(); + if (logfile != null && logfile.BaseStream.CanWrite) + { + lock (logfile) + { + byte[] datearray = BitConverter.GetBytes((UInt64)((DateTime.UtcNow - new DateTime(1970, 1, 1)).TotalMilliseconds * 1000)); + Array.Reverse(datearray); + logfile.Write(datearray, 0, datearray.Length); + logfile.Write(packet, 0, i); + } + } + } - catch { } // been getting errors from this. people must have it open twice. - } - - packetcount++; - - - - //System.Threading.Thread.Sleep(1); + catch { } + /* + if (messageType == ArdupilotMega.MAVLink.MAVLINK_MSG_ID_REQUEST_DATA_STREAM) + { + try + { + BinaryWriter bw = new BinaryWriter(File.OpenWrite("serialsent.raw")); + bw.Seek(0, SeekOrigin.End); + bw.Write(packet, 0, i); + bw.Write((byte)'\n'); + bw.Close(); + } + catch { } // been getting errors from this. people must have it open twice. + }*/ + } } public bool Write(string line) @@ -1621,7 +1628,7 @@ namespace ArdupilotMega byte compid = datin[4]; byte messid = datin[5]; - textoutput = string.Format("{0:X}{6}{1:X}{6}{2:X}{6}{3:X}{6}{4:X}{6}{5:X}{6}", header, length, seq, sysid, compid, messid, delimeter); + textoutput = string.Format("{0,2:X}{6}{1,2:X}{6}{2,2:X}{6}{3,2:X}{6}{4,2:X}{6}{5,2:X}{6}", header, length, seq, sysid, compid, messid, delimeter); object data = Activator.CreateInstance(MAVLINK_MESSAGE_INFO[messid]); @@ -1892,11 +1899,11 @@ namespace ArdupilotMega #endif DateTime start = DateTime.Now; - int retrys = 6; + int retrys = 10; while (true) { - if (!(start.AddMilliseconds(200) > DateTime.Now)) + if (!(start.AddMilliseconds(150) > DateTime.Now)) { if (retrys > 0) { @@ -2193,7 +2200,7 @@ namespace ArdupilotMega catch (Exception e) { log.Info("MAVLink readpacket read error: " + e.ToString()); break; } // check if looks like a mavlink packet and check for exclusions and write to console - if (buffer[0] != 254 && buffer[0] != 'U' || lastbad[0] == 'I' && lastbad[1] == 'M' || lastbad[1] == 'G' || lastbad[1] == 'A') // out of sync "AUTO" "GUIDED" "IMU" + if (buffer[0] != 254) { if (buffer[0] >= 0x20 && buffer[0] <= 127 || buffer[0] == '\n' || buffer[0] == '\r') { @@ -2213,7 +2220,7 @@ namespace ArdupilotMega //Console.WriteLine(DateTime.Now.Millisecond + " SR2 " + BaseStream.BytesToRead); // check for a header - if (buffer[0] == 'U' || buffer[0] == 254) + if (buffer[0] == 254) { // if we have the header, and no other chars, get the length and packet identifiers if (count == 0 && !logreadmode) @@ -2467,15 +2474,15 @@ namespace ArdupilotMega { if (logfile != null && logfile.BaseStream.CanWrite && !logreadmode) { - lock (logwritelock) + lock (logfile) { - byte[] datearray = BitConverter.GetBytes((UInt64)((DateTime.UtcNow - new DateTime(1970, 1, 1)).TotalMilliseconds * 1000)); //ASCIIEncoding.ASCII.GetBytes(DateTime.Now.ToBinary() + ":"); + byte[] datearray = BitConverter.GetBytes((UInt64)((DateTime.UtcNow - new DateTime(1970, 1, 1)).TotalMilliseconds * 1000)); Array.Reverse(datearray); logfile.Write(datearray, 0, datearray.Length); logfile.Write(buffer, 0, buffer.Length); if (buffer[5] == 0) {// flush on heartbeat - 1 seconds - logfile.Flush(); + logfile.BaseStream.Flush(); rawlogfile.BaseStream.Flush(); } } @@ -2671,7 +2678,7 @@ namespace ArdupilotMega byte[] datearray = new byte[8]; - logplaybackfile.BaseStream.Read(datearray, 0, datearray.Length); + int tem = logplaybackfile.BaseStream.Read(datearray, 0, datearray.Length); Array.Reverse(datearray); @@ -2679,9 +2686,13 @@ namespace ArdupilotMega UInt64 dateint = BitConverter.ToUInt64(datearray, 0); - date1 = date1.AddMilliseconds(dateint / 1000); + try + { + date1 = date1.AddMilliseconds(dateint / 1000); - lastlogread = date1.ToLocalTime(); + lastlogread = date1.ToLocalTime(); + } + catch { } MainV2.cs.datetime = lastlogread; diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs index 1de47d2ad8..81c5c160fb 100644 --- a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs +++ b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs @@ -2,14 +2,14 @@ - + - - + + @@ -31,7 +31,7 @@ - + @@ -81,178 +81,177 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - + + + - - - - - - - - - - + + + + + + + + + + - - - - - + + + + + - - - - + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - + + + + - - - - - - - - - + + + + + + + + + - - - - - - - + + + + + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - - + + + + - - - - - - - + + + + + + + - - - + + + - - - - + + + + - - - + + + - - - + + + - - - + + + @@ -296,26 +295,26 @@ - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + diff --git a/Tools/ArdupilotMegaPlanner/OpenGLtest.cs b/Tools/ArdupilotMegaPlanner/OpenGLtest.cs new file mode 100644 index 0000000000..5e7a43599a --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/OpenGLtest.cs @@ -0,0 +1,377 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; +using OpenTK; +using OpenTK.Graphics.OpenGL; +using System.Drawing.Imaging; +using System.Drawing; +using GMap.NET; +using GMap.NET.WindowsForms; + +namespace ArdupilotMega.Controls +{ + public class OpenGLtest : GLControl + { + public static OpenGLtest instance; + + // terrain image + Bitmap _terrain = new Bitmap(640,480); + int texture = 0; + + float _angle = 0; + double cameraX, cameraY, cameraZ; // camera coordinates + double lookX, lookY, lookZ; // camera look-at coordinates + + double step = 1 / 1200.0; + + // image zoom level + int zoom = 11; + + RectLatLng area = new RectLatLng(-35.04286,117.84262,0.1,0.1); + + double _alt = 0; + public PointLatLngAlt LocationCenter { + get { + return new PointLatLngAlt(area.LocationMiddle.Lat, area.LocationMiddle.Lng,_alt,""); + } + set { + + if (area.LocationMiddle.Lat == value.Lat && area.LocationMiddle.Lng == value.Lng) + return; + + if (value.Lat == 0 && value.Lng == 0) + return; + + _alt = value.Alt; + area = new RectLatLng(value.Lat + 0.15, value.Lng - 0.15, 0.3, 0.3); + // Console.WriteLine(area.LocationMiddle + " " + value.ToString()); + this.Invalidate(); + } + } + + public Vector3 rpy = new Vector3(); + + public OpenGLtest() + { + instance = this; + + InitializeComponent(); + + GL.GenTextures(1, out texture); + } + + void getImage() + { + MapType type = MapType.GoogleSatellite; + PureProjection prj = null; + int maxZoom; + + GMaps.Instance.AdjustProjection(type, ref prj, out maxZoom); + //int zoom = 14; // 12 + if (!area.IsEmpty) + { + try + { + List tileArea = prj.GetAreaTileList(area, zoom, 0); + //string bigImage = zoom + "-" + type + "-vilnius.png"; + + //Console.WriteLine("Preparing: " + bigImage); + //Console.WriteLine("Zoom: " + zoom); + //Console.WriteLine("Type: " + type.ToString()); + //Console.WriteLine("Area: " + area); + + var types = GMaps.Instance.GetAllLayersOfType(type); + + // current area + GPoint topLeftPx = prj.FromLatLngToPixel(area.LocationTopLeft, zoom); + GPoint rightButtomPx = prj.FromLatLngToPixel(area.Bottom, area.Right, zoom); + GPoint pxDelta = new GPoint(rightButtomPx.X - topLeftPx.X, rightButtomPx.Y - topLeftPx.Y); + + DateTime startimage = DateTime.Now; + + int padding = 0; + { + using (Bitmap bmpDestination = new Bitmap(pxDelta.X + padding * 2, pxDelta.Y + padding * 2)) + { + using (Graphics gfx = Graphics.FromImage(bmpDestination)) + { + gfx.CompositingMode = System.Drawing.Drawing2D.CompositingMode.SourceOver; + + // get tiles & combine into one + foreach (var p in tileArea) + { + Console.WriteLine("Downloading[" + p + "]: " + tileArea.IndexOf(p) + " of " + tileArea.Count); + + foreach (MapType tp in types) + { + Exception ex; + WindowsFormsImage tile = GMaps.Instance.GetImageFrom(tp, p, zoom, out ex) as WindowsFormsImage; + if (tile != null) + { + using (tile) + { + int x = p.X * prj.TileSize.Width - topLeftPx.X + padding; + int y = p.Y * prj.TileSize.Width - topLeftPx.Y + padding; + { + gfx.DrawImage(tile.Img, x, y, prj.TileSize.Width, prj.TileSize.Height); + } + } + } + } + if ((DateTime.Now - startimage).TotalMilliseconds > 200) + break; + } + } + _terrain = new Bitmap(bmpDestination, 512, 512); + + + GL.BindTexture(TextureTarget.Texture2D, texture); + + BitmapData data = _terrain.LockBits(new System.Drawing.Rectangle(0, 0, _terrain.Width, _terrain.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); + + _terrain.UnlockBits(data); + + GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear); + GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)TextureMagFilter.Linear); + + + } + } + if ((DateTime.Now - startimage).TotalMilliseconds > 200) + { + zoom--; + } + else + { + //zoom++; + } + } + catch { } + } + } + + const float rad2deg = (float)(180 / Math.PI); + const float deg2rad = (float)(1.0 / rad2deg); + + public Vector3 Normal(Vector3 a, Vector3 b, Vector3 c) + { + var dir = Vector3.Cross(b - a, c - a); + var norm = Vector3.Normalize(dir); + return norm; + } + + + protected override void OnPaint(System.Windows.Forms.PaintEventArgs e) + { + if (this.DesignMode) + return; + + if (area.LocationMiddle.Lat == 0 && area.LocationMiddle.Lng == 0) + return; + + _angle+=1f; + + // area.LocationTopLeft = new PointLatLng(area.LocationTopLeft.Lat + 0.0001,area.LocationTopLeft.Lng); + + //area.Size = new SizeLatLng(0.1, 0.1); + + try + { + base.OnPaint(e); + + } + catch { return; } + + double heightscale = (step / 90.0) * 4; + + float scale = 1.0f; + + float radians = (float)(Math.PI * (rpy.Z * -1) / 180.0f); + + //radians = 0; + + float mouseY = (float)(0.1 * scale); + + cameraX = area.LocationMiddle.Lng; // multiplying by mouseY makes the + cameraZ = area.LocationMiddle.Lat; // camera get closer/farther away with mouseY + cameraY = (LocationCenter.Alt < srtm.getAltitude(cameraZ, cameraX, 20)) ? (srtm.getAltitude(cameraZ, cameraX, 20)+ 0.2) * heightscale : LocationCenter.Alt * heightscale;// (srtm.getAltitude(lookZ, lookX, 20) + 100) * heighscale; + + + lookX = area.LocationMiddle.Lng + Math.Sin(radians) * mouseY; ; + lookY = cameraY; + lookZ = area.LocationMiddle.Lat + Math.Cos(radians) * mouseY; ; + + + MakeCurrent(); + + + GL.MatrixMode(MatrixMode.Projection); + + OpenTK.Matrix4 projection = OpenTK.Matrix4.CreatePerspectiveFieldOfView(60 * deg2rad, 1f, 0.00001f, 5000.0f); + GL.LoadMatrix(ref projection); + + Matrix4 modelview = Matrix4.LookAt((float)cameraX, (float)cameraY, (float)cameraZ, (float)lookX, (float)lookY, (float)lookZ, 0,1,0); + GL.MatrixMode(MatrixMode.Modelview); + + // roll + modelview = Matrix4.Mult(modelview,Matrix4.CreateRotationZ (rpy.X * deg2rad)); + // pitch + modelview = Matrix4.Mult(modelview, Matrix4.CreateRotationX(rpy.Y * -deg2rad)); + + GL.LoadMatrix(ref modelview); + + GL.ClearColor(Color.Blue); + + GL.Clear(ClearBufferMask.ColorBufferBit | ClearBufferMask.DepthBufferBit); + + GL.LightModel(LightModelParameter.LightModelAmbient,new float[] {1f,1f,1f,1f}); + + GL.Enable(EnableCap.Texture2D); + GL.BindTexture(TextureTarget.Texture2D, texture); + /* + GL.Begin(BeginMode.LineStrip); + + GL.Color3(Color.White); + GL.Vertex3(0, 0, 0); + + GL.Vertex3(area.Bottom, 0, area.Left); + + GL.Vertex3(lookX, lookY, lookZ); + + //GL.Vertex3(cameraX, cameraY, cameraZ); + + GL.End(); + */ + System.Diagnostics.Stopwatch sw = new System.Diagnostics.Stopwatch(); + + sw.Start(); + + getImage(); + + sw.Stop(); + + Console.WriteLine("img " +sw.ElapsedMilliseconds); + + sw.Start(); + + double increment = step * 1; + + double cleanup = area.Bottom % increment; + double cleanup2 = area.Left % increment; + + for (double z = (area.Bottom - cleanup); z < area.Top - step; z += increment) + { + //Makes OpenGL draw a triangle at every three consecutive vertices + GL.Begin(BeginMode.TriangleStrip); + for (double x = (area.Left - cleanup2); x < area.Right - step; x += increment) + { + int heightl = srtm.getAltitude(z, area.Right + area.Left - x, 20); + + // Console.WriteLine(x + " " + z); + + GL.Color3(Color.White); + + + // int heightl = 0; + + double scale2 = (Math.Abs(x - area.Left) / area.WidthLng);// / (float)_terrain.Width; + + double scale3 = (Math.Abs(z - area.Bottom) / area.HeightLat);// / (float)_terrain.Height; + + double imgx = 1 - scale2; + double imgy = 1 - scale3; + // GL.Color3(Color.Red); + + //GL.Color3(_terrain.GetPixel(imgx, imgy)); + GL.TexCoord2(imgx,imgy); + GL.Vertex3(x, heightl * heightscale, z); // _terrain.GetPixel(x, z).R + + try + { + heightl = srtm.getAltitude(z + increment, area.Right + area.Left - x, 20); + + //scale2 = (Math.Abs(x - area.Left) / area.WidthLng) * (float)_terrain.Width; + + scale3 = (Math.Abs(((z + increment) - area.Bottom)) / area.HeightLat);// / (float)_terrain.Height; + + imgx = 1- scale2; + imgy = 1 - scale3; + // GL.Color3(Color.Green); + //GL.Color3(_terrain.GetPixel(imgx, imgy)); + GL.TexCoord2(imgx,imgy); + GL.Vertex3(x, heightl * heightscale, z + increment); + + // Console.WriteLine(x + " " + (z + step)); + } + catch { break; } + + } + GL.End(); + } + + GL.Enable(EnableCap.Blend); + GL.DepthMask(false); + GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.One); + GL.DepthMask(true); + GL.Disable(EnableCap.Blend); + + GL.Flush(); + + + sw.Stop(); + + Console.WriteLine("GL "+sw.ElapsedMilliseconds); + + this.SwapBuffers(); + + //this.Invalidate(); + } + + private void InitializeComponent() + { + this.SuspendLayout(); + // + // OpenGLtest + // + this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); + this.Name = "OpenGLtest"; + this.Load += new System.EventHandler(this.test_Load); + this.Resize += new System.EventHandler(this.test_Resize); + this.ResumeLayout(false); + + } + + private void test_Load(object sender, EventArgs e) + { + GL.Enable(EnableCap.DepthTest); + // GL.Enable(EnableCap.Light0); + GL.Enable(EnableCap.Lighting); + GL.Enable(EnableCap.ColorMaterial); + GL.Enable(EnableCap.Normalize); + + //GL.Enable(EnableCap.LineSmooth); + //GL.Enable(EnableCap.PointSmooth); + //GL.Enable(EnableCap.PolygonSmooth); + GL.ShadeModel(ShadingModel.Smooth); + GL.Enable(EnableCap.CullFace); + GL.Enable(EnableCap.Texture2D); + + } + + private void test_Resize(object sender, EventArgs e) + { + MakeCurrent(); + + GL.Viewport(0, 0, this.Width, this.Height); + + this.Invalidate(); + } + } +} diff --git a/Tools/ArdupilotMegaPlanner/OpenGLtest.resx b/Tools/ArdupilotMegaPlanner/OpenGLtest.resx new file mode 100644 index 0000000000..7080a7d118 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/OpenGLtest.resx @@ -0,0 +1,120 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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/Program.cs b/Tools/ArdupilotMegaPlanner/Program.cs index 0a255a9d08..38f6b127ef 100644 --- a/Tools/ArdupilotMegaPlanner/Program.cs +++ b/Tools/ArdupilotMegaPlanner/Program.cs @@ -28,6 +28,8 @@ namespace ArdupilotMega Application.ThreadException += Application_ThreadException; + AppDomain.CurrentDomain.UnhandledException += new UnhandledExceptionEventHandler(CurrentDomain_UnhandledException); + Application.Idle += Application_Idle; //MagCalib.ProcessLog(); @@ -38,30 +40,81 @@ namespace ArdupilotMega //Console.WriteLine(srtm.getAltitude(-35.115676879882812, 117.94178754638671,20)); /* - Arduino.ArduinoSTK comport = new Arduino.ArduinoSTK(); + Arduino.ArduinoSTKv2 comport = new Arduino.ArduinoSTKv2(); - comport.PortName = "com4"; + comport.PortName = "com8"; - comport.BaudRate = 57600; + comport.BaudRate = 115200; comport.Open(); - comport.connectAP(); - - comport.sync(); - - comport.sync(); - - Console.WriteLine( comport.getChipType(0)); - - Console.WriteLine(comport.getChipType(1)); - - Console.WriteLine(comport.getChipType(2)); + Arduino.Chip.Populate(); + if (comport.connectAP()) + { + Arduino.Chip chip = comport.getChipType(); + Console.WriteLine(chip); + } Console.ReadLine(); return; */ + /* + Comms.SerialPort sp = new Comms.SerialPort(); + + sp.PortName = "com8"; + sp.BaudRate = 115200; + + CurrentState cs = new CurrentState(); + + MAVLink mav = new MAVLink(); + + mav.BaseStream = sp; + + mav.Open(); + + HIL.XPlane xp = new HIL.XPlane(); + + xp.SetupSockets(49005, 49000, "127.0.0.1"); + + HIL.Hil.sitl_fdm data = new HIL.Hil.sitl_fdm(); + + while (true) + { + while (mav.BaseStream.BytesToRead > 0) + mav.readPacket(); + + // update all stats + cs.UpdateCurrentSettings(null); + + xp.GetFromSim(ref data); + xp.GetFromAP(); // no function + + xp.SendToAP(data); + xp.SendToSim(); + + MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t(); + + rc.chan3_raw = 1500; + + mav.sendPacket(rc); + + } */ + /* + MAVLink mav = new MAVLink(); + + mav.BaseStream = new Comms.CommsFile() { PortName = @"C:\Users\hog\Documents\Visual Studio 2010\Projects\ArdupilotMega\ArdupilotMega\bin\Debug\logs\2012-09-09 15-07-25.tlog" }; + + mav.Open(true); + + while (mav.BaseStream.BytesToRead > 0) + { + + byte[] packet = mav.readPacket(); + + mav.DebugPacket(packet, true); + } + */ try { @@ -71,6 +124,11 @@ namespace ArdupilotMega } catch (Exception ex) { + if (ex.GetType() == typeof(FileNotFoundException)) + { + Console.WriteLine("If your error is about Microsoft.DirectX.DirectInput, please install the latest directx redist from here http://www.microsoft.com/en-us/download/details.aspx?id=35 \n\n"); + } + log.Fatal("Fatal app exception", ex); Console.WriteLine(ex.ToString()); @@ -78,6 +136,11 @@ namespace ArdupilotMega } } + static void CurrentDomain_UnhandledException(object sender, UnhandledExceptionEventArgs e) + { + handleException((Exception)e.ExceptionObject); + } + static DateTime lastidle = DateTime.Now; static void Application_Idle(object sender, EventArgs e) @@ -93,10 +156,8 @@ namespace ArdupilotMega System.Threading.Thread.Sleep(1); } - static void Application_ThreadException(object sender, System.Threading.ThreadExceptionEventArgs e) + static void handleException(Exception ex) { - Exception ex = e.Exception; - log.Debug(ex.ToString()); if (ex.Message == "Requested registry access is not allowed.") @@ -113,18 +174,18 @@ namespace ArdupilotMega CustomMessageBox.Show("Serial connection has been lost"); return; } - if (e.Exception.GetType() == typeof(MissingMethodException)) + if (ex.GetType() == typeof(MissingMethodException)) { - CustomMessageBox.Show("Please Update - Some older library dlls are causing problems\n" + e.Exception.Message); + CustomMessageBox.Show("Please Update - Some older library dlls are causing problems\n" + ex.Message); return; } - if (e.Exception.GetType() == typeof(ObjectDisposedException) || e.Exception.GetType() == typeof(InvalidOperationException)) // something is trying to update while the form, is closing. + if (ex.GetType() == typeof(ObjectDisposedException) || ex.GetType() == typeof(InvalidOperationException)) // something is trying to update while the form, is closing. { return; // ignore } - if (e.Exception.GetType() == typeof(FileNotFoundException) || e.Exception.GetType() == typeof(BadImageFormatException)) // i get alot of error from people who click the exe from inside a zip file. + if (ex.GetType() == typeof(FileNotFoundException) || ex.GetType() == typeof(BadImageFormatException)) // i get alot of error from people who click the exe from inside a zip file. { - CustomMessageBox.Show("You are missing some DLL's. Please extract the zip file somewhere. OR Use the update feature from the menu " + e.Exception.ToString()); + CustomMessageBox.Show("You are missing some DLL's. Please extract the zip file somewhere. OR Use the update feature from the menu " + ex.ToString()); // return; } DialogResult dr = CustomMessageBox.Show("An error has occurred\n" + ex.ToString() + "\n\nReport this Error???", "Send Error", MessageBoxButtons.YesNo); @@ -173,5 +234,12 @@ namespace ArdupilotMega } } } + + static void Application_ThreadException(object sender, System.Threading.ThreadExceptionEventArgs e) + { + Exception ex = e.Exception; + + handleException(ex); + } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index 76ba6a5c14..baf34ed7c2 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs @@ -34,5 +34,5 @@ using System.Resources; // by using the '*' as shown below: // [assembly: AssemblyVersion("1.0.*")] [assembly: AssemblyVersion("1.1.*")] -[assembly: AssemblyFileVersion("1.2.11")] +[assembly: AssemblyFileVersion("1.2.12")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs b/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs index bffcd2b52e..53bc1a135b 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs @@ -95,6 +95,20 @@ namespace ArdupilotMega.Properties { } } + public static System.Drawing.Bitmap APM_rover_firmware { + get { + object obj = ResourceManager.GetObject("APM_rover_firmware", resourceCulture); + return ((System.Drawing.Bitmap)(obj)); + } + } + + public static System.Drawing.Icon apm2 { + get { + object obj = ResourceManager.GetObject("apm2", resourceCulture); + return ((System.Drawing.Icon)(obj)); + } + } + public static System.Drawing.Bitmap attocurrent { get { object obj = ResourceManager.GetObject("attocurrent", resourceCulture); diff --git a/Tools/ArdupilotMegaPlanner/Properties/Resources.resx b/Tools/ArdupilotMegaPlanner/Properties/Resources.resx index b3a2ff40a4..b7c705f4dc 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/Resources.resx +++ b/Tools/ArdupilotMegaPlanner/Properties/Resources.resx @@ -1246,8 +1246,14 @@ ..\Resources\frames_x.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - ..\Resources\cameraGimalYaw.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + ..\Resources\APM_rover-firmware.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + + ..\apm2.ico;System.Drawing.Icon, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs index 6da2478642..85dcfa24e7 100644 --- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs @@ -66,7 +66,6 @@ this.S8 = new System.Windows.Forms.ComboBox(); this.RS8 = new System.Windows.Forms.ComboBox(); this.RS9 = new System.Windows.Forms.ComboBox(); - this.linkLabel1 = new System.Windows.Forms.LinkLabel(); this.RS0 = new System.Windows.Forms.TextBox(); this.RTI = new System.Windows.Forms.TextBox(); this.ATI = new System.Windows.Forms.TextBox(); @@ -103,6 +102,7 @@ this.groupBox2 = new System.Windows.Forms.GroupBox(); this.label9 = new System.Windows.Forms.Label(); this.label10 = new System.Windows.Forms.Label(); + this.linkLabel1 = new System.Windows.Forms.LinkLabel(); this.SPLIT_local.Panel1.SuspendLayout(); this.SPLIT_local.Panel2.SuspendLayout(); this.SPLIT_local.SuspendLayout(); @@ -117,11 +117,9 @@ // resources.ApplyResources(this.Progressbar, "Progressbar"); this.Progressbar.Name = "Progressbar"; - this.toolTip1.SetToolTip(this.Progressbar, resources.GetString("Progressbar.ToolTip")); // // S1 // - resources.ApplyResources(this.S1, "S1"); this.S1.FormattingEnabled = true; this.S1.Items.AddRange(new object[] { resources.GetString("S1.Items"), @@ -133,6 +131,7 @@ resources.GetString("S1.Items6"), resources.GetString("S1.Items7"), resources.GetString("S1.Items8")}); + resources.ApplyResources(this.S1, "S1"); this.S1.Name = "S1"; this.toolTip1.SetToolTip(this.S1, resources.GetString("S1.ToolTip")); // @@ -140,30 +139,25 @@ // resources.ApplyResources(this.label1, "label1"); this.label1.Name = "label1"; - this.toolTip1.SetToolTip(this.label1, resources.GetString("label1.ToolTip")); // // S0 // resources.ApplyResources(this.S0, "S0"); this.S0.Name = "S0"; this.S0.ReadOnly = true; - this.toolTip1.SetToolTip(this.S0, resources.GetString("S0.ToolTip")); // // label2 // resources.ApplyResources(this.label2, "label2"); this.label2.Name = "label2"; - this.toolTip1.SetToolTip(this.label2, resources.GetString("label2.ToolTip")); // // label3 // resources.ApplyResources(this.label3, "label3"); this.label3.Name = "label3"; - this.toolTip1.SetToolTip(this.label3, resources.GetString("label3.ToolTip")); // // S2 // - resources.ApplyResources(this.S2, "S2"); this.S2.FormattingEnabled = true; this.S2.Items.AddRange(new object[] { resources.GetString("S2.Items"), @@ -179,6 +173,7 @@ resources.GetString("S2.Items10"), resources.GetString("S2.Items11"), resources.GetString("S2.Items12")}); + resources.ApplyResources(this.S2, "S2"); this.S2.Name = "S2"; this.toolTip1.SetToolTip(this.S2, resources.GetString("S2.ToolTip")); // @@ -186,11 +181,9 @@ // resources.ApplyResources(this.label4, "label4"); this.label4.Name = "label4"; - this.toolTip1.SetToolTip(this.label4, resources.GetString("label4.ToolTip")); // // S3 // - resources.ApplyResources(this.S3, "S3"); this.S3.FormattingEnabled = true; this.S3.Items.AddRange(new object[] { resources.GetString("S3.Items"), @@ -223,6 +216,7 @@ resources.GetString("S3.Items27"), resources.GetString("S3.Items28"), resources.GetString("S3.Items29")}); + resources.ApplyResources(this.S3, "S3"); this.S3.Name = "S3"; this.toolTip1.SetToolTip(this.S3, resources.GetString("S3.ToolTip")); // @@ -230,11 +224,9 @@ // resources.ApplyResources(this.label5, "label5"); this.label5.Name = "label5"; - this.toolTip1.SetToolTip(this.label5, resources.GetString("label5.ToolTip")); // // S4 // - resources.ApplyResources(this.S4, "S4"); this.S4.FormattingEnabled = true; this.S4.Items.AddRange(new object[] { resources.GetString("S4.Items"), @@ -245,6 +237,7 @@ resources.GetString("S4.Items5"), resources.GetString("S4.Items6"), resources.GetString("S4.Items7")}); + resources.ApplyResources(this.S4, "S4"); this.S4.Name = "S4"; this.toolTip1.SetToolTip(this.S4, resources.GetString("S4.ToolTip")); // @@ -252,7 +245,6 @@ // resources.ApplyResources(this.label6, "label6"); this.label6.Name = "label6"; - this.toolTip1.SetToolTip(this.label6, resources.GetString("label6.ToolTip")); // // S5 // @@ -264,7 +256,6 @@ // resources.ApplyResources(this.label7, "label7"); this.label7.Name = "label7"; - this.toolTip1.SetToolTip(this.label7, resources.GetString("label7.ToolTip")); // // S6 // @@ -276,7 +267,6 @@ // resources.ApplyResources(this.label8, "label8"); this.label8.Name = "label8"; - this.toolTip1.SetToolTip(this.label8, resources.GetString("label8.ToolTip")); // // S7 // @@ -304,7 +294,6 @@ // // RS4 // - resources.ApplyResources(this.RS4, "RS4"); this.RS4.FormattingEnabled = true; this.RS4.Items.AddRange(new object[] { resources.GetString("RS4.Items"), @@ -315,12 +304,12 @@ resources.GetString("RS4.Items5"), resources.GetString("RS4.Items6"), resources.GetString("RS4.Items7")}); + resources.ApplyResources(this.RS4, "RS4"); this.RS4.Name = "RS4"; this.toolTip1.SetToolTip(this.RS4, resources.GetString("RS4.ToolTip")); // // RS3 // - resources.ApplyResources(this.RS3, "RS3"); this.RS3.FormattingEnabled = true; this.RS3.Items.AddRange(new object[] { resources.GetString("RS3.Items"), @@ -353,12 +342,12 @@ resources.GetString("RS3.Items27"), resources.GetString("RS3.Items28"), resources.GetString("RS3.Items29")}); + resources.ApplyResources(this.RS3, "RS3"); this.RS3.Name = "RS3"; this.toolTip1.SetToolTip(this.RS3, resources.GetString("RS3.ToolTip")); // // RS2 // - resources.ApplyResources(this.RS2, "RS2"); this.RS2.FormattingEnabled = true; this.RS2.Items.AddRange(new object[] { resources.GetString("RS2.Items"), @@ -374,12 +363,12 @@ resources.GetString("RS2.Items10"), resources.GetString("RS2.Items11"), resources.GetString("RS2.Items12")}); + resources.ApplyResources(this.RS2, "RS2"); this.RS2.Name = "RS2"; this.toolTip1.SetToolTip(this.RS2, resources.GetString("RS2.ToolTip")); // // RS1 // - resources.ApplyResources(this.RS1, "RS1"); this.RS1.FormattingEnabled = true; this.RS1.Items.AddRange(new object[] { resources.GetString("RS1.Items"), @@ -391,6 +380,7 @@ resources.GetString("RS1.Items6"), resources.GetString("RS1.Items7"), resources.GetString("RS1.Items8")}); + resources.ApplyResources(this.RS1, "RS1"); this.RS1.Name = "RS1"; this.toolTip1.SetToolTip(this.RS1, resources.GetString("RS1.ToolTip")); // @@ -403,7 +393,6 @@ // // S10 // - resources.ApplyResources(this.S10, "S10"); this.S10.FormattingEnabled = true; this.S10.Items.AddRange(new object[] { resources.GetString("S10.Items"), @@ -425,12 +414,12 @@ resources.GetString("S10.Items16"), resources.GetString("S10.Items17"), resources.GetString("S10.Items18")}); + resources.ApplyResources(this.S10, "S10"); this.S10.Name = "S10"; this.toolTip1.SetToolTip(this.S10, resources.GetString("S10.ToolTip")); // // S11 // - resources.ApplyResources(this.S11, "S11"); this.S11.FormattingEnabled = true; this.S11.Items.AddRange(new object[] { resources.GetString("S11.Items"), @@ -443,32 +432,32 @@ resources.GetString("S11.Items7"), resources.GetString("S11.Items8"), resources.GetString("S11.Items9")}); + resources.ApplyResources(this.S11, "S11"); this.S11.Name = "S11"; this.toolTip1.SetToolTip(this.S11, resources.GetString("S11.ToolTip")); // // S12 // - resources.ApplyResources(this.S12, "S12"); this.S12.FormattingEnabled = true; this.S12.Items.AddRange(new object[] { resources.GetString("S12.Items"), resources.GetString("S12.Items1")}); + resources.ApplyResources(this.S12, "S12"); this.S12.Name = "S12"; this.toolTip1.SetToolTip(this.S12, resources.GetString("S12.ToolTip")); // // RS12 // - resources.ApplyResources(this.RS12, "RS12"); this.RS12.FormattingEnabled = true; this.RS12.Items.AddRange(new object[] { resources.GetString("RS12.Items"), resources.GetString("RS12.Items1")}); + resources.ApplyResources(this.RS12, "RS12"); this.RS12.Name = "RS12"; this.toolTip1.SetToolTip(this.RS12, resources.GetString("RS12.ToolTip")); // // RS11 // - resources.ApplyResources(this.RS11, "RS11"); this.RS11.FormattingEnabled = true; this.RS11.Items.AddRange(new object[] { resources.GetString("RS11.Items"), @@ -481,12 +470,12 @@ resources.GetString("RS11.Items7"), resources.GetString("RS11.Items8"), resources.GetString("RS11.Items9")}); + resources.ApplyResources(this.RS11, "RS11"); this.RS11.Name = "RS11"; this.toolTip1.SetToolTip(this.RS11, resources.GetString("RS11.ToolTip")); // // RS10 // - resources.ApplyResources(this.RS10, "RS10"); this.RS10.FormattingEnabled = true; this.RS10.Items.AddRange(new object[] { resources.GetString("RS10.Items"), @@ -508,12 +497,12 @@ resources.GetString("RS10.Items16"), resources.GetString("RS10.Items17"), resources.GetString("RS10.Items18")}); + resources.ApplyResources(this.RS10, "RS10"); this.RS10.Name = "RS10"; this.toolTip1.SetToolTip(this.RS10, resources.GetString("RS10.ToolTip")); // // S9 // - resources.ApplyResources(this.S9, "S9"); this.S9.FormattingEnabled = true; this.S9.Items.AddRange(new object[] { resources.GetString("S9.Items"), @@ -525,12 +514,12 @@ resources.GetString("S9.Items6"), resources.GetString("S9.Items7"), resources.GetString("S9.Items8")}); + resources.ApplyResources(this.S9, "S9"); this.S9.Name = "S9"; this.toolTip1.SetToolTip(this.S9, resources.GetString("S9.ToolTip")); // // S8 // - resources.ApplyResources(this.S8, "S8"); this.S8.FormattingEnabled = true; this.S8.Items.AddRange(new object[] { resources.GetString("S8.Items"), @@ -545,12 +534,12 @@ resources.GetString("S8.Items9"), resources.GetString("S8.Items10"), resources.GetString("S8.Items11")}); + resources.ApplyResources(this.S8, "S8"); this.S8.Name = "S8"; this.toolTip1.SetToolTip(this.S8, resources.GetString("S8.ToolTip")); // // RS8 // - resources.ApplyResources(this.RS8, "RS8"); this.RS8.FormattingEnabled = true; this.RS8.Items.AddRange(new object[] { resources.GetString("RS8.Items"), @@ -562,12 +551,12 @@ resources.GetString("RS8.Items6"), resources.GetString("RS8.Items7"), resources.GetString("RS8.Items8")}); + resources.ApplyResources(this.RS8, "RS8"); this.RS8.Name = "RS8"; this.toolTip1.SetToolTip(this.RS8, resources.GetString("RS8.ToolTip")); // // RS9 // - resources.ApplyResources(this.RS9, "RS9"); this.RS9.FormattingEnabled = true; this.RS9.Items.AddRange(new object[] { resources.GetString("RS9.Items"), @@ -579,55 +568,42 @@ resources.GetString("RS9.Items6"), resources.GetString("RS9.Items7"), resources.GetString("RS9.Items8")}); + resources.ApplyResources(this.RS9, "RS9"); this.RS9.Name = "RS9"; this.toolTip1.SetToolTip(this.RS9, resources.GetString("RS9.ToolTip")); // - // linkLabel1 - // - resources.ApplyResources(this.linkLabel1, "linkLabel1"); - this.linkLabel1.Name = "linkLabel1"; - this.linkLabel1.TabStop = true; - this.toolTip1.SetToolTip(this.linkLabel1, resources.GetString("linkLabel1.ToolTip")); - this.linkLabel1.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.linkLabel1_LinkClicked); - // // RS0 // resources.ApplyResources(this.RS0, "RS0"); this.RS0.Name = "RS0"; this.RS0.ReadOnly = true; - this.toolTip1.SetToolTip(this.RS0, resources.GetString("RS0.ToolTip")); // // RTI // resources.ApplyResources(this.RTI, "RTI"); this.RTI.Name = "RTI"; this.RTI.ReadOnly = true; - this.toolTip1.SetToolTip(this.RTI, resources.GetString("RTI.ToolTip")); // // ATI // resources.ApplyResources(this.ATI, "ATI"); this.ATI.Name = "ATI"; this.ATI.ReadOnly = true; - this.toolTip1.SetToolTip(this.ATI, resources.GetString("ATI.ToolTip")); // // label11 // resources.ApplyResources(this.label11, "label11"); this.label11.Name = "label11"; - this.toolTip1.SetToolTip(this.label11, resources.GetString("label11.ToolTip")); // // label12 // resources.ApplyResources(this.label12, "label12"); this.label12.Name = "label12"; - this.toolTip1.SetToolTip(this.label12, resources.GetString("label12.ToolTip")); // // BUT_savesettings // resources.ApplyResources(this.BUT_savesettings, "BUT_savesettings"); this.BUT_savesettings.Name = "BUT_savesettings"; - this.toolTip1.SetToolTip(this.BUT_savesettings, resources.GetString("BUT_savesettings.ToolTip")); this.BUT_savesettings.UseVisualStyleBackColor = true; this.BUT_savesettings.Click += new System.EventHandler(this.BUT_savesettings_Click); // @@ -635,22 +611,19 @@ // resources.ApplyResources(this.BUT_getcurrent, "BUT_getcurrent"); this.BUT_getcurrent.Name = "BUT_getcurrent"; - this.toolTip1.SetToolTip(this.BUT_getcurrent, resources.GetString("BUT_getcurrent.ToolTip")); this.BUT_getcurrent.UseVisualStyleBackColor = true; this.BUT_getcurrent.Click += new System.EventHandler(this.BUT_getcurrent_Click); // // lbl_status // - resources.ApplyResources(this.lbl_status, "lbl_status"); this.lbl_status.BackColor = System.Drawing.Color.Transparent; + resources.ApplyResources(this.lbl_status, "lbl_status"); this.lbl_status.Name = "lbl_status"; - this.toolTip1.SetToolTip(this.lbl_status, resources.GetString("lbl_status.ToolTip")); // // BUT_upload // resources.ApplyResources(this.BUT_upload, "BUT_upload"); this.BUT_upload.Name = "BUT_upload"; - this.toolTip1.SetToolTip(this.BUT_upload, resources.GetString("BUT_upload.ToolTip")); this.BUT_upload.UseVisualStyleBackColor = true; this.BUT_upload.Click += new System.EventHandler(this.BUT_upload_Click); // @@ -658,109 +631,91 @@ // resources.ApplyResources(this.label13, "label13"); this.label13.Name = "label13"; - this.toolTip1.SetToolTip(this.label13, resources.GetString("label13.ToolTip")); // // label14 // resources.ApplyResources(this.label14, "label14"); this.label14.Name = "label14"; - this.toolTip1.SetToolTip(this.label14, resources.GetString("label14.ToolTip")); // // label15 // resources.ApplyResources(this.label15, "label15"); this.label15.Name = "label15"; - this.toolTip1.SetToolTip(this.label15, resources.GetString("label15.ToolTip")); // // label16 // resources.ApplyResources(this.label16, "label16"); this.label16.Name = "label16"; - this.toolTip1.SetToolTip(this.label16, resources.GetString("label16.ToolTip")); // // label17 // resources.ApplyResources(this.label17, "label17"); this.label17.Name = "label17"; - this.toolTip1.SetToolTip(this.label17, resources.GetString("label17.ToolTip")); // // label20 // resources.ApplyResources(this.label20, "label20"); this.label20.Name = "label20"; - this.toolTip1.SetToolTip(this.label20, resources.GetString("label20.ToolTip")); // // label21 // resources.ApplyResources(this.label21, "label21"); this.label21.Name = "label21"; - this.toolTip1.SetToolTip(this.label21, resources.GetString("label21.ToolTip")); // // label22 // resources.ApplyResources(this.label22, "label22"); this.label22.Name = "label22"; - this.toolTip1.SetToolTip(this.label22, resources.GetString("label22.ToolTip")); // // label23 // resources.ApplyResources(this.label23, "label23"); this.label23.Name = "label23"; - this.toolTip1.SetToolTip(this.label23, resources.GetString("label23.ToolTip")); // // label24 // resources.ApplyResources(this.label24, "label24"); this.label24.Name = "label24"; - this.toolTip1.SetToolTip(this.label24, resources.GetString("label24.ToolTip")); // // label25 // resources.ApplyResources(this.label25, "label25"); this.label25.Name = "label25"; - this.toolTip1.SetToolTip(this.label25, resources.GetString("label25.ToolTip")); // // label26 // resources.ApplyResources(this.label26, "label26"); this.label26.Name = "label26"; - this.toolTip1.SetToolTip(this.label26, resources.GetString("label26.ToolTip")); // // label27 // resources.ApplyResources(this.label27, "label27"); this.label27.Name = "label27"; - this.toolTip1.SetToolTip(this.label27, resources.GetString("label27.ToolTip")); // // label28 // resources.ApplyResources(this.label28, "label28"); this.label28.Name = "label28"; - this.toolTip1.SetToolTip(this.label28, resources.GetString("label28.ToolTip")); // // label29 // resources.ApplyResources(this.label29, "label29"); this.label29.Name = "label29"; - this.toolTip1.SetToolTip(this.label29, resources.GetString("label29.ToolTip")); // // label30 // resources.ApplyResources(this.label30, "label30"); this.label30.Name = "label30"; - this.toolTip1.SetToolTip(this.label30, resources.GetString("label30.ToolTip")); // // label31 // resources.ApplyResources(this.label31, "label31"); this.label31.Name = "label31"; - this.toolTip1.SetToolTip(this.label31, resources.GetString("label31.ToolTip")); // // label32 // resources.ApplyResources(this.label32, "label32"); this.label32.Name = "label32"; - this.toolTip1.SetToolTip(this.label32, resources.GetString("label32.ToolTip")); // // SPLIT_local // @@ -769,7 +724,6 @@ // // SPLIT_local.Panel1 // - resources.ApplyResources(this.SPLIT_local.Panel1, "SPLIT_local.Panel1"); this.SPLIT_local.Panel1.Controls.Add(this.label2); this.SPLIT_local.Panel1.Controls.Add(this.S1); this.SPLIT_local.Panel1.Controls.Add(this.label1); @@ -786,11 +740,9 @@ this.SPLIT_local.Panel1.Controls.Add(this.S6); this.SPLIT_local.Panel1.Controls.Add(this.S7); this.SPLIT_local.Panel1.Controls.Add(this.label7); - this.toolTip1.SetToolTip(this.SPLIT_local.Panel1, resources.GetString("SPLIT_local.Panel1.ToolTip")); // // SPLIT_local.Panel2 // - resources.ApplyResources(this.SPLIT_local.Panel2, "SPLIT_local.Panel2"); this.SPLIT_local.Panel2.Controls.Add(this.label13); this.SPLIT_local.Panel2.Controls.Add(this.S9); this.SPLIT_local.Panel2.Controls.Add(this.S10); @@ -801,8 +753,6 @@ this.SPLIT_local.Panel2.Controls.Add(this.S8); this.SPLIT_local.Panel2.Controls.Add(this.label15); this.SPLIT_local.Panel2.Controls.Add(this.label14); - this.toolTip1.SetToolTip(this.SPLIT_local.Panel2, resources.GetString("SPLIT_local.Panel2.ToolTip")); - this.toolTip1.SetToolTip(this.SPLIT_local, resources.GetString("SPLIT_local.ToolTip")); // // SPLIT_remote // @@ -811,7 +761,6 @@ // // SPLIT_remote.Panel1 // - resources.ApplyResources(this.SPLIT_remote.Panel1, "SPLIT_remote.Panel1"); this.SPLIT_remote.Panel1.Controls.Add(this.RS0); this.SPLIT_remote.Panel1.Controls.Add(this.RS1); this.SPLIT_remote.Panel1.Controls.Add(this.RS2); @@ -828,11 +777,9 @@ this.SPLIT_remote.Panel1.Controls.Add(this.label32); this.SPLIT_remote.Panel1.Controls.Add(this.label30); this.SPLIT_remote.Panel1.Controls.Add(this.label31); - this.toolTip1.SetToolTip(this.SPLIT_remote.Panel1, resources.GetString("SPLIT_remote.Panel1.ToolTip")); // // SPLIT_remote.Panel2 // - resources.ApplyResources(this.SPLIT_remote.Panel2, "SPLIT_remote.Panel2"); this.SPLIT_remote.Panel2.Controls.Add(this.label24); this.SPLIT_remote.Panel2.Controls.Add(this.RS9); this.SPLIT_remote.Panel2.Controls.Add(this.RS10); @@ -843,14 +790,11 @@ this.SPLIT_remote.Panel2.Controls.Add(this.label22); this.SPLIT_remote.Panel2.Controls.Add(this.label21); this.SPLIT_remote.Panel2.Controls.Add(this.label20); - this.toolTip1.SetToolTip(this.SPLIT_remote.Panel2, resources.GetString("SPLIT_remote.Panel2.ToolTip")); - this.toolTip1.SetToolTip(this.SPLIT_remote, resources.GetString("SPLIT_remote.ToolTip")); // // CHK_advanced // resources.ApplyResources(this.CHK_advanced, "CHK_advanced"); this.CHK_advanced.Name = "CHK_advanced"; - this.toolTip1.SetToolTip(this.CHK_advanced, resources.GetString("CHK_advanced.ToolTip")); this.CHK_advanced.UseVisualStyleBackColor = true; this.CHK_advanced.CheckedChanged += new System.EventHandler(this.CHK_advanced_CheckedChanged); // @@ -858,7 +802,6 @@ // resources.ApplyResources(this.BUT_Syncoptions, "BUT_Syncoptions"); this.BUT_Syncoptions.Name = "BUT_Syncoptions"; - this.toolTip1.SetToolTip(this.BUT_Syncoptions, resources.GetString("BUT_Syncoptions.ToolTip")); this.BUT_Syncoptions.UseVisualStyleBackColor = true; this.BUT_Syncoptions.Click += new System.EventHandler(this.BUT_Syncoptions_Click); // @@ -867,42 +810,45 @@ resources.ApplyResources(this.ATI3, "ATI3"); this.ATI3.Name = "ATI3"; this.ATI3.ReadOnly = true; - this.toolTip1.SetToolTip(this.ATI3, resources.GetString("ATI3.ToolTip")); // // groupBox1 // - resources.ApplyResources(this.groupBox1, "groupBox1"); this.groupBox1.Controls.Add(this.SPLIT_local); this.groupBox1.Controls.Add(this.ATI3); this.groupBox1.Controls.Add(this.label11); this.groupBox1.Controls.Add(this.ATI); this.groupBox1.Controls.Add(this.RSSI); this.groupBox1.Controls.Add(this.label12); + resources.ApplyResources(this.groupBox1, "groupBox1"); this.groupBox1.Name = "groupBox1"; this.groupBox1.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox1, resources.GetString("groupBox1.ToolTip")); // // groupBox2 // - resources.ApplyResources(this.groupBox2, "groupBox2"); this.groupBox2.Controls.Add(this.label9); this.groupBox2.Controls.Add(this.SPLIT_remote); this.groupBox2.Controls.Add(this.RTI); + resources.ApplyResources(this.groupBox2, "groupBox2"); this.groupBox2.Name = "groupBox2"; this.groupBox2.TabStop = false; - this.toolTip1.SetToolTip(this.groupBox2, resources.GetString("groupBox2.ToolTip")); // // label9 // resources.ApplyResources(this.label9, "label9"); this.label9.Name = "label9"; - this.toolTip1.SetToolTip(this.label9, resources.GetString("label9.ToolTip")); // // label10 // resources.ApplyResources(this.label10, "label10"); this.label10.Name = "label10"; - this.toolTip1.SetToolTip(this.label10, resources.GetString("label10.ToolTip")); + // + // linkLabel1 + // + resources.ApplyResources(this.linkLabel1, "linkLabel1"); + this.linkLabel1.Name = "linkLabel1"; + this.linkLabel1.TabStop = true; + this.toolTip1.SetToolTip(this.linkLabel1, resources.GetString("linkLabel1.ToolTip")); + this.linkLabel1.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.linkLabel1_LinkClicked); // // _3DRradio // @@ -921,7 +867,6 @@ this.Controls.Add(this.BUT_upload); this.MinimumSize = new System.Drawing.Size(781, 433); this.Name = "_3DRradio"; - this.toolTip1.SetToolTip(this, resources.GetString("$this.ToolTip")); this.SPLIT_local.Panel1.ResumeLayout(false); this.SPLIT_local.Panel1.PerformLayout(); this.SPLIT_local.Panel2.ResumeLayout(false); diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx index bc566032bc..df00f160bf 100644 --- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx +++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx @@ -117,177 +117,43 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 90 - - - 25 - - - 81, 164 + + 12, 389 - - 8 + + 755, 36 - - 80 + + 2 - - 0 + + Progressbar - - 13 + + System.Windows.Forms.ProgressBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 7 + + $this - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 91 - - - 8 - - - 44, 13 - - - label20 - - - label26 - - - 7 - - - 16 - - - 16 - - - 26 - - - maximum frequency in kHz - - - RTI - - - 435000 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - the percentage of time to allow transmit - - - 82, 38 - - - 6 + + 9 + + 17, 17 + 115 - - Version + + 111 - - - NoControl + + 57 - - label27 - - - 192 - - - ECC - - - SPLIT_local.Panel2 - - - 46 - - - 928000 - - - 433050 - - - 434040 - - - 30 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 915000 - - - 921000 - - - 250 - - - 6, 172 - - - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. - - - - 435000 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 20 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - Tx Power - - - 8 - - - 2 - - - 689, 11 - - - 4 - - - linkLabel1 - - - 2 - - - SPLIT_local.Panel1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 38 19 @@ -301,1481 +167,138 @@ 2 - - SPLIT_remote.Panel1 - - - 111 - - - 57 - - - 38 - - - SPLIT_local.Panel2 - 1 - - 7 - - - 50 - - - System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 8 - - - 102, 20 - - - 17 - - - 3 - - - 3 - - - 6 - - - SPLIT_remote.Panel1 - - - S12 - - - 102, 20 - - - 0 - - - 80 - - - 60 - - - 3 - - - 42 - - - Op Resend - - - SPLIT_local.Panel1 - - - 81, 3 - - - SPLIT_remote.Panel1 - - - label23 - - - toolTip1 - - - 90 - - - Format - - - - - - TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to lower levels for short range testing. - - - - 30 - - - 1 - - - label28 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - SPLIT_remote.Panel1 - - - 6, 118 - - - - - - maximum frequency in kHz - - - 0, 13 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - label22 - - - 6, 64 - - - 2 - - - 37 - - - BUT_getcurrent - - - 12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6, 199 - - - - - - label29 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 9 - - - 19 - - - SPLIT_remote.Panel2 - - - S7 - - - System.Windows.Forms.ProgressBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 0 - - - 80, 20 - - - 97, 28 - - - 2 - - - 28 - - - Baud - - - 434040 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - _3DRradio - - - 8 - - - SPLIT_remote.Panel1 - - - 70 - - - 11 - - - 81, 83 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 357, 221 + + 81, 29 80, 21 - - - - - NoControl - - - 21 - - - 96, 82 - - - Net ID - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 902000 - - - 12 - - - 22 - - - the percentage of time to allow transmit - - - SPLIT_remote.Panel1 - - - 15 - - - True - - - 15 - - - 68 - - - 9 - - - 70 - - - NoControl - - - 28 - - - 80, 21 - - - S8 - - - Min Freq - - - 19 - - - 5 - - - SPLIT_remote.Panel1 - - - 97, 55 - - - 172 - - - SPLIT_remote.Panel1 - - - 51 - - - RS12 - - - 5 - - - NoControl - - - Upload Firmware (Local) - - - 28 - - - 1 - - - True - - - 11 - - - - - - - - + 4 - - 65 - - - RS11 - - - 434790 - - - NoControl - - - 12 - - - Save Settings - - - SPLIT_local.Panel1 - - - SPLIT_remote.Panel1 - - - NoControl - - - 78 - - - 374, 221 - - - Mavlink - - - label10 - - - 2 - - - 22 - - - SPLIT_remote.Panel1 - - - 419, 3 - - - 5 - - - 33 - - - 7 - - - 8 - - - - - - SPLIT_local.Panel1 - - - 3 - - - 4 - - - 9, 11 - - - 10 - - - 10 - - - 67 - - - True - - - label11 - - - - - - 36 - - - True - - - 10 - - - 6 - - - 6, 64 - - - SPLIT_local.Panel2 - - - True - - - 6, 10 - - - 20 - - - LBT Rssi - - - 9 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 15 - - - 9 - - - 4 - - - label16 - - - The 3DR Radios have 2 status LEDs, one red and one green. -green LED blinking - searching for another radio -green LED solid - link is established with another radio -red LED flashing - transmitting data -red LED solid - in firmware update mode - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - groupBox1 - - - 10 - - - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. - - - - 6, 145 - - - 6, 13 - - - SPLIT_local.Panel2 - - - 5 - - - 63 - - - - - - 80, 21 - - - 34 - - - True - - - 12 - - - 22 - - - 21 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 928000 - - - NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area. - - - System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - BUT_upload - - - 50 - - - ATI - - - 18 - - - S0 - - - 0 - - - - - - 7 - - - SPLIT_remote.Panel2 - - - S4 - - - Mavlink - - - True - - - $this - - - 30 - - - True - - - ATI3 - - - 7 - - - - - - 25 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 18, 50 - - - 5 - - - 57 - - - SPLIT_remote.Panel1 - - - $this - - - NoControl - - - 1 - - - True - - - 42, 13 - - - 6 - - - label12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 4 - - - 0 - - - 80, 21 - - - number of frequency hopping channels - - - label2 - - - SPLIT_local - - - - - - 13 - - - label6 - - - 1 - - - 13 - - - 23 - - - SPLIT_local.Panel1 - - - 5, 85 - - - SPLIT_remote.Panel2 - - - System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 13 - - - 433050 - - - 53, 13 - - - 24 - - - 24 - - - 52, 13 - - - 80, 21 - - - 0 - - - 83, 56 - - - RS10 - - - 40 - - - 11 - - - 44, 13 - - - 5 - - - - - - 435000 - - - 0 - - - SPLIT_local.Panel2 - - - 100 - - - 83, 164 - - - Air Speed - - - NoControl - - - Tx Power - - - label30 - - - 54 - - - SPLIT_local.Panel1 - - - SPLIT_local.Panel2 - - - 7 - - - Air Speed - - - 8 - - - System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - - - - 32 - - - 29 - - - Max Freq - - - 17 - - - 38 - - - SPLIT_local.Panel1 - - - - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 53 - - - True - - - SPLIT_remote.Panel2 - - - groupBox2 - - - 6, 145 - - - - - - 52, 13 - - - ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less. - - - - SPLIT_local.Panel1 - - - 1 - - - - - - 1 - - - 80, 21 - - - 4, 31 - - - groupBox1 - - - 14 - - - 24 - - - 21 - - - 1 - - - SPLIT_remote.Panel2 - - - - - - 96, 3 - - - 915000 - - - SPLIT_local.Panel1 - - - True - - - 12 - - - 56 - - - 30 - - - 12, 48 - - - True - - - NoControl - - - 81, 110 - - - 28, 13 - - - Listen Before Talk threshold - - - 16 - - - 12 - - - groupBox1 - - - 40 - - - SPLIT_local.Panel1 - - - 59 - - - ECC - - - 5, 31 - - - 5 - - - 61, 13 - - - 921000 - - - 32, 13 - - - Local - - - SPLIT_local - - - groupBox1 - - - 16 - - - - - - 83, 110 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 13 - - - 14 - - - 20 - - - True - - - True - - - 6, 118 - Serial baud rate in rounded kbps. So 57 means 57600. - - 20 + + S1 - - 0 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + SPLIT_local.Panel1 + + + 1 + + True - - label24 - - - Remote - - - 102, 20 - - - 210, 12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 10 - - - S11 - - - CHK_advanced - - - 114, 17 - - - 921000 - - - 73, 13 - - - - - - System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 30 - - - 47 - - - 81, 191 - - - 4, 85 - - - SPLIT_remote.Panel1 - - - 71 - - - - - - 781, 433 - - - 434040 - - - 80, 21 - - - RSSI + + 6, 37 32, 13 - - False + + 5 - - 2 + + Baud - - NoControl + + label1 - - number of frequency hopping channels + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 27 - - - SPLIT_remote.Panel2 - - - SPLIT_remote.Panel1 - - - 48, 13 - - - 928000 - - - 6 - - - 80, 20 - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null + + SPLIT_local.Panel1 2 - - 15 - - - 6, 199 - - - 38, 13 - - - 80, 21 - - - NoControl - - - 11 - - - 111 - - - 19 - - - 0 - - - 902000 - - - $this - - - SPLIT_remote.Panel1 - - - 14 - - - 6, 37 - - - 80, 20 - - - 58, 13 - - - - - - 9 - - - 5 - - - 58, 13 - - - 3 - - - True - - - S3 - - - SPLIT_remote.Panel1 - - - $this - - - 10 - - - 14 - - - # of Channels - - - 25 - - - 51, 13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 20 - - - 32, 13 - - - 6 - - - 0 - - - $this - - - 434790 - - - 44 - - - 15 - - - Serial baud rate in rounded kbps. So 57 means 57600. - - - - 10 + + 81, 3 80, 20 - - 4 + + 7 - - Max Freq + + S0 - - 48 + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - NoControl + + SPLIT_local.Panel1 - - 2 - - - label31 - - - 82 - - + 3 - - 14 + + True - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 6, 10 - - 50 + + 39, 13 - - 16 + + 8 - - 81 + + Format - - 40 + + label2 - - 25 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 4, 81 + + SPLIT_local.Panel1 - - + + 0 - - 14 + + True - - AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long. + + 6, 64 - - 16 + + 53, 13 - - 1 + + 10 - - 18 + + Air Speed - - 9 - - - - - - SPLIT_remote - - - SPLIT_remote.Panel2 - - - 4 - - - NoControl - - - SPLIT_local.Panel2 - - - $this - - - 50, 13 - - - - - - + + label3 System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox2 - - - - - - 80, 21 - - - 434790 - - - 80, 21 - - - 907500 - - - 5 - - - True - - - 97, 3 - - - 907500 - - - 170 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - SPLIT_local.Panel2 - - - 83, 3 - - - 928000 - - - 10 - - - 11 - - + SPLIT_local.Panel1 - - 902000 - - - 9 - - - System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 8 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 6 - - - SPLIT_remote.Panel2 - - - 4 - - - 0 - - - 9 - - - 28, 13 - - - 6, 172 - - - 83, 29 - - + 5 - - 32 - - - 48 - - - 32 - - - 20 + + 250 192 @@ -1783,394 +306,800 @@ red LED solid - in firmware update mode 128 - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 96 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 64 + + + 48 + + + 32 + + + 24 19 - - 11 + + 16 - - label32 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - True - - - 7 - - - 0 - - - - - - System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 77 - - - - - - Status Leds - - - 102, 29 - - + 8 - - label4 + + 4 - - 60 - - - label8 - - - $this - - - 1 - - - label17 - - - Advanced Options - - - 433050 - - - 14 - - - 19 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 66 - - - 12, 389 - - - 55 - - - 4, 6 - - - - - - 10 - - - SPLIT_local.Panel1 - - - Op Resend - - - 18 - - - 4, 112 - - - 42, 13 - - - 7 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 3 - - - - - - 8 - - - True - - - 24 - - - - - - 39, 13 - - - 43 - - - 17 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 20 - - - RS0 - - - S10 - - - SPLIT_local.Panel1 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 14 - - - 80, 21 - - - 13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - 80, 21 - - - 1 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 48, 13 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 17 - - - 69, 39 - - - 10 - - - 29 - - - Baud - - - S9 + + 2 81, 56 - - False + + 80, 21 - - Min Freq + + 9 - + + AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long. + + + S2 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel1 + + + 4 + + + True + + + 6, 91 + + + 38, 13 + + + 12 + + + Net ID + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel1 + + 7 - - 96, 109 + + 1 - - NoControl - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 19 - - - 29 - - - Load Settings - - - System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - SPLIT_remote - - - True - - - - - - NoControl - - - True - - + 2 - - SPLIT_remote.Panel2 + + 3 - - 12, 15 + + 4 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 2 - - - S6 - - - 64 + + 5 6 + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + 16 + + + 17 + 18 + + 19 + + + 20 + + + 21 + + + 22 + + + 23 + + + 24 + + + 25 + + + 26 + 27 - - 14, 15 + + 28 - - # of Channels + + 29 - - groupBox1 + + 30 - + + 81, 83 + + + 80, 21 + + + 11 + + + NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area. + + + S3 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel1 + + + 6 + + True - - + + 6, 118 - - 40 + + 52, 13 - - label14 + + 14 - - RS4 + + Tx Power - - 83, 191 + + label5 - - 60 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + SPLIT_local.Panel1 + + + 9 + + + 1 + + + 2 + + + 5 + + + 8 + + + 11 + + + 14 + + 17 + + 20 + + + 81, 110 + + + 80, 21 + + + 13 + + + TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to lower levels for short range testing. + + + + S4 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel1 + + + 8 + True + + 6, 145 + + + 28, 13 + + + 16 + + + ECC + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel1 + + + 11 + + + 81, 137 + + + 80, 20 + + + 15 + + + ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less. + + + + S5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel1 + + + 10 + + + True + + + 6, 172 + + + 44, 13 + + + 18 + + + Mavlink + + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel1 + + + 15 + + + 81, 164 + + + 80, 20 + + + 17 + MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet. + + S6 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel1 + + + 13 + + + True + + + 6, 199 + + + 61, 13 + + + 20 + + + Op Resend + + + label8 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel1 + + + 12 + + + 81, 191 + + + 80, 20 + + + 19 + + + OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + + + + S7 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel1 + + + 14 + + + 17, 17 + + + 83, 191 + + + 80, 20 + + + 29 + + + OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + + + + RS7 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 11 + + + 83, 164 + + + 80, 20 + + + 28 + MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet. - - BUT_Syncoptions + + RS6 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + SPLIT_remote.Panel1 - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null + + 9 - + + 83, 137 + + + 80, 20 + + + 27 + + + ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less. + + + + RS5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 7 + + + 1 + + 2 - - Format + + 5 - - Net ID + + 8 - - 4, 81 + + 11 - - label15 + + 14 - - S5 + + 17 + + + 20 + + + 83, 110 + + + 80, 21 + + + 26 + + + TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to lower levels for short range testing. + + + + RS4 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 5 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 21 + + + 22 + + + 23 + + + 24 + + + 25 + + + 26 + + + 27 + + + 28 + + + 29 + + + 30 + + + 83, 83 + + + 80, 21 + + + 25 + + + NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area. RS3 - - 344, 3 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + SPLIT_remote.Panel1 + + + 3 + + + 250 + + + 192 + + + 128 + + + 96 + + + 64 + + + 48 + + + 32 + + + 24 + + + 19 + + + 16 + + + 8 + + + 4 + + + 2 + + + 83, 56 + + 80, 21 - - + + 24 - - 69, 39 + + AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long. + + + RS2 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 2 + + + 115 + + + 111 + + + 57 + + + 38 + + + 19 + + + 9 + + + 4 + + + 2 + + + 1 + + + 83, 29 + + + 80, 21 + + + 22 + + + Serial baud rate in rounded kbps. So 57 means 57600. + + + + RS1 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 1 + + + 82, 38 + + + True + + + 250, 39 + + + 34 see the spec for a RSSI to dBm graph. The numbers at the end are: @@ -2182,159 +1111,401 @@ ecc: number of 12 bit words successfully corrected by the golay code which result in a valid packet CRC - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + RSSI - - 63, 13 + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 18 + + groupBox1 - - + + 4 - - 11 - - - 14 - - - 64 - - - 20 - - - 2 - - + 5 - + + 6 + + + 7 + + 8 - - SPLIT_remote.Panel2 + + 9 - - RS2 + + 10 - - NoControl + + 11 - - 20 + + 12 - - 30 + + 13 - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - 16 - - - True + + 14 15 - - 97, 82 + + 16 - - True + + 17 - - 61, 13 + + 18 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 19 - - 49 + + 20 - - label1 + + 30 - - 12 + + 40 - - 115 + + 50 - - groupBox1 + + 96, 55 - - True + + 80, 21 - - True + + 42 - - label5 + + number of frequency hopping channels - - 58 + + S10 - - RS1 - - - 2 - - - Listen Before Talk threshold - - - SPLIT_local.Panel1 - - - - - + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 27 - - - 9 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long. - SPLIT_local.Panel2 - - minimum frequency in kHz + + 2 - - ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less. - + + 10 - + + 20 + + + 30 + + + 40 + + + 50 + + + 60 + + + 70 + + + 80 + + + 90 + + + 100 + + + 96, 82 + + + 80, 21 + + + 43 + + + the percentage of time to allow transmit + + + S11 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel2 + + + 3 + + + 0 + + + 25 + + + 96, 109 + + + 80, 21 + + + 44 + + + Listen Before Talk threshold + + + S12 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel2 + + + 5 + + + 0 + + + 25 + + + 97, 109 + + + 80, 21 + + + 56 + + + Listen Before Talk threshold + + + RS12 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel2 + + + 4 + + + 10 + + + 20 + + + 30 + + + 40 + + + 50 + + + 60 + + + 70 + + + 80 + + + 90 + + + 100 + + + 97, 82 + + + 80, 21 + + + 55 + + + the percentage of time to allow transmit + + + RS11 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel2 + + + 3 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 30 + + + 40 + + + 50 + + + 97, 55 + + + 80, 21 + + + 54 + + + number of frequency hopping channels + + + RS10 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel2 + + + 2 + + 902000 - + + 907500 + + + 915000 + + + 921000 + + + 928000 + + 433050 - + 434040 - + 434790 - - 17 + + 435000 + + + 96, 28 + + + 80, 21 + + + 41 + + + maximum frequency in kHz + + + S9 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel2 + + + 1 + + + 902000 907500 @@ -2345,8 +1516,17 @@ which result in a valid packet CRC 921000 - - S1 + + 928000 + + + 433050 + + + 434040 + + + 434790 435000 @@ -2354,566 +1534,1248 @@ which result in a valid packet CRC - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 37 - - - 69 - - - 6, 37 - - - 83 - - - Copy Required Items to Remote - - - 382, 306 - - - - - - 5, 112 - - - groupBox2 - - - True - - - 269, 3 - - - RS7 - - - 6, 91 - - - Progressbar - - - 11 - - - 62 - - + - - 367, 306 + + 96, 3 - - 8 + + 80, 21 - - RS6 - - - 138, 12 - - - 8 - - - 70 - - - NoControl - - - NoControl - - - Duty Cycle + + 46 minimum frequency in kHz - - 250, 39 - - - NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area. - - - NoControl - - - BUT_savesettings - - - 80, 20 - - - 0 - - - 128 - - - SPLIT_remote.Panel1 - - - RS5 - - - label3 - - - True - - - 51, 13 - - - label7 - - - SPLIT_local.Panel2 - - - True - - - 81, 29 - - - 4 - - - Duty Cycle - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 1 - - - - - - - - - SPLIT_remote.Panel2 - - - 39, 13 - - - 80 - - - 3 - - - 38, 13 - - - 72 - - - True - - - 13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 19 - - - True - - - 907500 - - - 26 - - - 4 - - - 4, 58 - - - 5, 58 - - - 400, 48 - - - TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to lower levels for short range testing. - - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4639.25747, Culture=neutral, PublicKeyToken=null - - - label9 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 0 - - - 83, 83 - - - 5 - - - 96, 28 - - - 8 - - - OPPRESEND 启用/禁用“条件性重发”。当启动时,当输入缓冲含有少于256字节时电台将两次发送同一个数据包。第二遍将标记为重发,接收电台在正确收到第一个包时会忽略重发的包。这对链路质量,特别是上行命令有很大的影响。 - - - 9 - - - 102, 12 - - - - - - 50 - - - 11 - - - - - - 80, 21 - - - 17 - - - - - - SPLIT_local.Panel2 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 19 - - - 96 - - - SPLIT_local.Panel1 - - - 4 - - - 80, 21 - - - RS9 - - - 346, 355 - - - 5 - - - 97, 109 - - - - - - 53, 13 - - - 23 - - - - - - 20 - - - 48 - - - - - - label13 - - - 1 - - - 80, 21 - - - 26 - - - 3 - - - 6, 10 - - - 24 - - - SPLIT_local - - - 96 - - - label25 - - - 1 - - - 1 - - - 23 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 73, 13 - - - 121, 39 - - - 6 - - - 2 - - - 100 - - - RS8 - - - groupBox2 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - True - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 80, 20 - - - 80, 21 - - - 250 - - - True - - - 96, 55 - - - 50, 13 - - - 80, 20 - - - - - - - - - 15 - - - 25 - - - + + S8 System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 755, 36 + + SPLIT_local.Panel2 - - 2 + + 7 - - S2 + + 902000 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 9 - - - 50 - - - 61 - - - 80, 21 - - - LBT Rssi - - - $this - - - 41 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - SPLIT_remote - - - 5, 6 - - - 653, 366 - - - 4 - - - RSSI - - - $this - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 907500 915000 - - NoControl + + 921000 - - SPLIT_local.Panel1 + + 928000 - + + 433050 + + + 434040 + + + 434790 + + + 435000 + + + 97, 3 + + + 80, 21 + + + 58 + + + minimum frequency in kHz + + + RS8 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel2 + + + 5 + + + 902000 + + + 907500 + + + 915000 + + + 921000 + + + 928000 + + + 433050 + + + 434040 + + + 434790 + + + 435000 + + + 97, 28 + + + 80, 21 + + + 53 + + + maximum frequency in kHz + + + RS9 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel2 + + + 1 + + + 83, 3 + + + 80, 20 + + + 23 + + + RS0 + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 83, 137 - - - lbl_status - - - Version - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - 79 - - - NoControl - - - 12, 361 - SPLIT_remote.Panel1 + + 0 + + + 138, 12 + + + 102, 20 + + + 33 + + + RTI + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 2 + + + 102, 12 + + + 102, 20 + + + 32 + + + ATI + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 3 + + + True + + + 14, 15 + + + 42, 13 + + + 36 + + + Version + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 2 + + + True + + + 18, 50 + + + 32, 13 + + + 37 + + + RSSI + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 5 + + + False + + + 344, 3 + + + 69, 39 + + + 21 + + + Save Settings + + + BUT_savesettings + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4585.14832, Culture=neutral, PublicKeyToken=null + + + $this + + + 6 + + + 269, 3 + + + 69, 39 + + + 6 + + + Load Settings + + + BUT_getcurrent + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4585.14832, Culture=neutral, PublicKeyToken=null + + + $this + + + 7 + + + 12, 361 + 310, 22 - - SPLIT_local.Panel1 + + 3 + + + lbl_status + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + 419, 3 + + + 121, 39 + + + 0 + + + Upload Firmware (Local) + + + BUT_upload + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4585.14832, Culture=neutral, PublicKeyToken=null + + + $this + + + 10 + + + True + + + + NoControl + + + 4, 6 + + + 48, 13 + + + 47 + + + Min Freq + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel2 + + + 0 + + + True + + + NoControl + + + 4, 31 + + + 51, 13 + + + 48 + + + Max Freq + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel2 + + + 9 + + + True + + + NoControl + + + 4, 58 + + + 73, 13 + + + 49 + + + # of Channels + + + label15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel2 + + + 8 + + + True + + + NoControl + + + 4, 85 + + + 58, 13 + + + 50 + + + Duty Cycle + + + label16 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local.Panel2 + + + 6 + + + True + + + NoControl + + + 4, 112 + + + 50, 13 + + + 51 + + + LBT Rssi + + + label17 System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + SPLIT_local.Panel2 + + + 4 + + + True + + + NoControl + + + 5, 112 + + + 50, 13 + + + 63 + + + LBT Rssi + + + label20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel2 + + + 9 + + + True + + + NoControl + + + 5, 85 + + + 58, 13 + + + 62 + + + Duty Cycle + label21 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel2 + + + 8 + + + True + + + NoControl + + + 5, 58 + + + 73, 13 + + + 61 + + + # of Channels + + + label22 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel2 + + + 7 + + + True + + + NoControl + + + 5, 31 + + + 51, 13 + + + 60 + + + Max Freq + + + label23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel2 + + + 6 True + + NoControl + + + 5, 6 + + + 48, 13 + + + 59 + + + Min Freq + + + label24 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel2 + + + 0 + + + True + + + NoControl + + + 6, 199 + + + 61, 13 + + + 72 + + + Op Resend + + + label25 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 4 + + + True + + + NoControl + + + 6, 172 + + + 44, 13 + + + 71 + + + Mavlink + + + label26 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + 6 - - 81, 137 + + True + + + NoControl + + + 6, 145 + + + 28, 13 + + + 70 + + + ECC + + + label27 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 8 + + + True + + + NoControl + + + 6, 118 + + + 52, 13 + + + 69 + + + Tx Power + + + label28 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 10 + + + True + + + NoControl + + + 6, 91 + + + 38, 13 + + + 68 + + + Net ID + + + label29 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 12 + + + True + + + NoControl + + + 6, 64 + + + 53, 13 + + + 67 + + + Air Speed + + + label30 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 14 + + + True + + + NoControl + + + 6, 10 + + + 39, 13 + + + 66 + + + Format + + + label31 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 15 + + + True + + + NoControl + + + 6, 37 + + + 32, 13 + + + 65 + + + Baud + + + label32 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote.Panel1 + + + 13 + + + True + + + 4, 81 + + + SPLIT_local.Panel1 + + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local + + + 0 + + + SPLIT_local.Panel2 + + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_local + + + 1 + + + 374, 221 + + + 172 + + + 1 + + + 0 + + + SPLIT_local + + + System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 0 + + + True + + + 4, 81 + + + SPLIT_remote.Panel1 + + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote + + + 0 + + + SPLIT_remote.Panel2 + + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SPLIT_remote + + + 1 + + + 357, 221 + + + 170 + + + 1 + + + 0 + + + SPLIT_remote + + + System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 1 - - 17, 17 - + + True + + + 653, 366 + + + 114, 17 + + + 77 + + + Advanced Options + + + CHK_advanced + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + False + + + NoControl + + + 346, 355 + + + 102, 29 + + + 78 + + + Copy Required Items to Remote + + + BUT_Syncoptions + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4585.14832, Culture=neutral, PublicKeyToken=null + + + $this + + + 4 + + + 210, 12 + + + 102, 20 + + + 79 + + + ATI3 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 1 + + + 12, 48 + + + 382, 306 + + + 80 + + + Local + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 0 + + + 400, 48 + + + 367, 306 + + + 81 + + + Remote + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + True + + + NoControl + + + 12, 15 + + + 42, 13 + + + 37 + + + Version + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 0 + + + True + + + NoControl + + + 9, 11 + + + 0, 13 + + + 82 + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + True + + + 689, 11 + + + 63, 13 + + + 83 + + + Status Leds + + + The 3DR Radios have 2 status LEDs, one red and one green. +green LED blinking - searching for another radio +green LED solid - link is established with another radio +red LED flashing - transmitting data +red LED solid - in firmware update mode + + + linkLabel1 + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + True + + 6, 13 + + + 781, 433 + + + toolTip1 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + _3DRradio + + + System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Utilities/CaptureMJPEG.cs b/Tools/ArdupilotMegaPlanner/Utilities/CaptureMJPEG.cs index 477867c592..a8b85d7f9d 100644 --- a/Tools/ArdupilotMegaPlanner/Utilities/CaptureMJPEG.cs +++ b/Tools/ArdupilotMegaPlanner/Utilities/CaptureMJPEG.cs @@ -69,113 +69,121 @@ namespace ArdupilotMega.Utilities Bitmap frame = new Bitmap(640, 480); - // Create a request using a URL that can receive a post. - WebRequest request = HttpWebRequest.Create(URL); - // Set the Method property of the request to POST. - request.Method = "GET"; - - ((HttpWebRequest)request).AutomaticDecompression = DecompressionMethods.GZip | DecompressionMethods.Deflate; - - request.Headers.Add("Accept-Encoding", "gzip,deflate"); - - // Get the response. - WebResponse response = request.GetResponse(); - // Display the status. - log.Debug(((HttpWebResponse)response).StatusDescription); - // Get the stream containing content returned by the server. - Stream dataStream = response.GetResponseStream(); - - BinaryReader br = new BinaryReader(dataStream); - - // get boundary header - - string mpheader = response.Headers["Content-Type"]; - if (mpheader.IndexOf("boundary=") == -1) { - ReadLine(br); // this is a blank line - string line = "proxyline"; - while (line.Length > 2) - { - line = ReadLine(br); - if (line.StartsWith("--")) { - mpheader = line; - break; - } - } - } - else + try { - int startboundary = mpheader.IndexOf("boundary=") + 9; - int endboundary = mpheader.Length; - mpheader = mpheader.Substring(startboundary, endboundary - startboundary); - } + // Create a request using a URL that can receive a post. + WebRequest request = HttpWebRequest.Create(URL); + // Set the Method property of the request to POST. + request.Method = "GET"; - dataStream.ReadTimeout = 30000; // 30 seconds - br.BaseStream.ReadTimeout = 30000; + ((HttpWebRequest)request).AutomaticDecompression = DecompressionMethods.GZip | DecompressionMethods.Deflate; - while (running) - { - try + request.Headers.Add("Accept-Encoding", "gzip,deflate"); + + // Get the response. + WebResponse response = request.GetResponse(); + // Display the status. + log.Debug(((HttpWebResponse)response).StatusDescription); + // Get the stream containing content returned by the server. + Stream dataStream = response.GetResponseStream(); + + BinaryReader br = new BinaryReader(dataStream); + + // get boundary header + + string mpheader = response.Headers["Content-Type"]; + if (mpheader.IndexOf("boundary=") == -1) { - // get the multipart start header - int length = int.Parse(getHeader(br)["Content-Length"]); - - // read boundary header - if (length > 0) + ReadLine(br); // this is a blank line + string line = "proxyline"; + do { - byte[] buf1 = new byte[length]; - - dataStream.ReadTimeout = 3000; - - int offset = 0; - int len = 0; - - while ((len = br.Read(buf1, offset, length)) > 0) + line = ReadLine(br); + if (line.StartsWith("--")) { - offset += len; - length -= len; - + mpheader = line; + break; } - /* - BinaryWriter sw = new BinaryWriter(File.OpenWrite("test.jpg")); - - sw.Write(buf1,0,buf1.Length); - - sw.Close(); - */ - try - { - - frame = new Bitmap(new MemoryStream(buf1)); - - } - catch { } - - fps++; - - if (lastimage.Second != DateTime.Now.Second) - { - Console.WriteLine("MJPEG " + fps); - fps = 0; - lastimage = DateTime.Now; - } - - if (OnNewImage != null) - OnNewImage(frame, new EventArgs()); - } - - // blank line at end of data - ReadLine(br); + } while (line.Length > 2); } - catch (Exception ex) { log.Info(ex); break; } + else + { + int startboundary = mpheader.IndexOf("boundary=") + 9; + int endboundary = mpheader.Length; + + mpheader = mpheader.Substring(startboundary, endboundary - startboundary); + } + + dataStream.ReadTimeout = 30000; // 30 seconds + br.BaseStream.ReadTimeout = 30000; + + while (running) + { + try + { + // get the multipart start header + int length = int.Parse(getHeader(br)["Content-Length"]); + + // read boundary header + if (length > 0) + { + byte[] buf1 = new byte[length]; + + dataStream.ReadTimeout = 3000; + + int offset = 0; + int len = 0; + + while ((len = br.Read(buf1, offset, length)) > 0) + { + offset += len; + length -= len; + + } + /* + BinaryWriter sw = new BinaryWriter(File.OpenWrite("test.jpg")); + + sw.Write(buf1,0,buf1.Length); + + sw.Close(); + */ + try + { + + frame = new Bitmap(new MemoryStream(buf1)); + + } + catch { } + + fps++; + + if (lastimage.Second != DateTime.Now.Second) + { + Console.WriteLine("MJPEG " + fps); + fps = 0; + lastimage = DateTime.Now; + } + + if (OnNewImage != null) + OnNewImage(frame, new EventArgs()); + } + + // blank line at end of data + ReadLine(br); + } + catch (Exception ex) { log.Info(ex); break; } + } + + // clear last image + if (OnNewImage != null) + OnNewImage(null, new EventArgs()); + + dataStream.Close(); + response.Close(); + } - - // clear last image - if (OnNewImage != null) - OnNewImage(null, new EventArgs()); - - dataStream.Close(); - response.Close(); + catch (Exception ex) { log.Error(ex); } running = false; }