From 8f084ae8eee50240dbdd126225b880d23d40ab33 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Tue, 27 Nov 2012 22:06:59 +0800 Subject: [PATCH] Mission Planner 1.2.23 ammend serial dispose on usb devices detach add item currentstate item description and units ammend battery screen for 3dr power module add trackbar zoom to flight data add unit desccription ammend PREFLIGHT_REBOOT_SHUTDOWN timeout --- .../Arduino/ArduinoSTK.cs | 8 +- .../Arduino/ArduinoSTKv2.cs | 10 +- .../ArdupilotMegaPlanner/ArdupilotMega.csproj | 27 +- Tools/ArdupilotMegaPlanner/ArdupilotMega.sln | 14 - Tools/ArdupilotMegaPlanner/ChangeLog.txt | 17 +- .../Comms/CommsSerialPort.cs | 14 + .../Controls/QuickView.cs | 16 +- Tools/ArdupilotMegaPlanner/CurrentState.cs | 215 +- Tools/ArdupilotMegaPlanner/FollowMe.cs | 2 +- .../ConfigBatteryMonitoring.Designer.cs | 11 +- .../ConfigBatteryMonitoring.resx | 69 +- .../GCSViews/ConfigurationView/Setup.cs | 2 +- .../ArdupilotMegaPlanner/GCSViews/Firmware.cs | 12 +- .../GCSViews/FlightData.Designer.cs | 105 +- .../GCSViews/FlightData.cs | 67 +- .../GCSViews/FlightData.resx | 3238 ++++++++++------- .../GCSViews/Simulation.cs | 2 +- Tools/ArdupilotMegaPlanner/MainV2.cs | 24 +- Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs | 3 + Tools/ArdupilotMegaPlanner/MavlinkLog.cs | 31 +- Tools/ArdupilotMegaPlanner/Msi/installer.wxs | 48 +- Tools/ArdupilotMegaPlanner/Program.cs | 8 +- .../Properties/AssemblyInfo.cs | 2 +- .../Properties/Resources.Designer.cs | 9 +- .../Properties/Resources.resx | 237 +- Tools/ArdupilotMegaPlanner/Radio/Uploader.cs | 2 +- Tools/ArdupilotMegaPlanner/SerialOutput.cs | 2 +- Tools/ArdupilotMegaPlanner/SerialOutput2.cs | 2 +- Tools/ArdupilotMegaPlanner/Splash.Designer.cs | 2 +- 29 files changed, 2510 insertions(+), 1689 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs index 163be54070..00e59889cd 100644 --- a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs +++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs @@ -360,8 +360,12 @@ namespace ArdupilotMega.Arduino } catch { } - if (base.IsOpen) - base.Close(); + try + { + if (base.IsOpen) + base.Close(); + } + catch { } this.DtrEnable = false; this.RtsEnable = false; diff --git a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs index 0916360f7e..85b48cf9b2 100644 --- a/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs +++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs @@ -2,7 +2,7 @@ using System.Collections.Generic; using System.Reflection; using System.Text; -using System.IO.Ports; +using ArdupilotMega.Comms; using System.Threading; using log4net; @@ -410,8 +410,12 @@ namespace ArdupilotMega.Arduino } catch { } - if (base.IsOpen) - base.Close(); + try + { + if (base.IsOpen) + base.Close(); + } + catch { } base.DtrEnable = false; base.RtsEnable = false; diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index 3709e105fb..2d343243d8 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -85,10 +85,10 @@ ArdupilotMega_TemporaryKey.pfx - true + false - true + false false @@ -157,7 +157,7 @@ False - False + True @@ -381,9 +381,15 @@ ValuesControl.cs - - - + + Always + + + Always + + + Always + Code @@ -1431,11 +1437,15 @@ Always - + + Always + - + + Always + Always Designer @@ -1462,6 +1472,7 @@ + diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.sln b/Tools/ArdupilotMegaPlanner/ArdupilotMega.sln index b74dfc2d2b..256d4bb24b 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.sln +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.sln @@ -9,8 +9,6 @@ Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "wix", "wix\wix.csproj", "{7 EndProject Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "3DRRadio", "3DRRadio\3DRRadio.csproj", "{B8943726-04B0-4477-BFDA-E156A0CD98A4}" EndProject -Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "px4uploader", "..\px4uploader\px4uploader.csproj", "{664FC484-2A94-4B0D-808F-A71F88E06B11}" -EndProject Global GlobalSection(SolutionConfigurationPlatforms) = preSolution Debug|Any CPU = Debug|Any CPU @@ -71,18 +69,6 @@ Global {B8943726-04B0-4477-BFDA-E156A0CD98A4}.Release|Win32.ActiveCfg = Release|x86 {B8943726-04B0-4477-BFDA-E156A0CD98A4}.Release|x86.ActiveCfg = Release|x86 {B8943726-04B0-4477-BFDA-E156A0CD98A4}.Release|x86.Build.0 = Release|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Debug|Any CPU.ActiveCfg = Debug|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Debug|Mixed Platforms.ActiveCfg = Debug|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Debug|Mixed Platforms.Build.0 = Debug|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Debug|Win32.ActiveCfg = Debug|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Debug|x86.ActiveCfg = Debug|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Debug|x86.Build.0 = Debug|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Release|Any CPU.ActiveCfg = Release|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Release|Mixed Platforms.ActiveCfg = Release|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Release|Mixed Platforms.Build.0 = Release|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Release|Win32.ActiveCfg = Release|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Release|x86.ActiveCfg = Release|x86 - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Release|x86.Build.0 = Release|x86 EndGlobalSection GlobalSection(SolutionProperties) = preSolution HideSolutionNode = FALSE diff --git a/Tools/ArdupilotMegaPlanner/ChangeLog.txt b/Tools/ArdupilotMegaPlanner/ChangeLog.txt index d4c12acc85..baeac2d157 100644 --- a/Tools/ArdupilotMegaPlanner/ChangeLog.txt +++ b/Tools/ArdupilotMegaPlanner/ChangeLog.txt @@ -1,4 +1,19 @@ -* Mission Planner 1.2.20 +* Mission Planner 1.2.22 +fix speed modification scale +fix typo on antenna Tracker +setup for ThemeManager.cs +new auto hide menu + +* Mission Planner 1.2.21 +Antenna Tracker mod from William Bryan +Scaling mods +battery screen mods +failsafe screen pwm checking +remove reverse radio options when we are using a quad +config menu reorganise +add Ateryx stuff + +* Mission Planner 1.2.20 fix airspeed error scale and min ground speed modify mount options add german lang diff --git a/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs index 1ca16abfb9..737d4d2cf3 100644 --- a/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs +++ b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs @@ -6,6 +6,7 @@ using System.IO; using System.Linq; using System.Management; using ArdupilotMega.Utilities; +using System.Reflection; namespace ArdupilotMega.Comms { @@ -17,6 +18,19 @@ namespace ArdupilotMega.Comms { try { + try + { + Type mytype = typeof(System.IO.Ports.SerialPort); + FieldInfo field = mytype.GetField("internalSerialStream", BindingFlags.Instance | BindingFlags.NonPublic); + Stream stream = (Stream)field.GetValue(this); + + if (stream != null) + { + stream.Dispose(); + } + } + catch { } + base.Dispose(disposing); } catch { } diff --git a/Tools/ArdupilotMegaPlanner/Controls/QuickView.cs b/Tools/ArdupilotMegaPlanner/Controls/QuickView.cs index 12c9095a46..36c65c4636 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/QuickView.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/QuickView.cs @@ -12,7 +12,20 @@ namespace ArdupilotMega.Controls public partial class QuickView : UserControl { [System.ComponentModel.Browsable(true)] - public string desc { get { return labelWithPseudoOpacity1.Text; } set { if (labelWithPseudoOpacity1.Text == value) return; labelWithPseudoOpacity1.Text = value; } } + public string desc + { + get + { + return labelWithPseudoOpacity1.Text; + } + set + { + if (labelWithPseudoOpacity1.Text == value) + return; + + labelWithPseudoOpacity1.Text = value; + } + } [System.ComponentModel.Browsable(true)] public double number { get { return double.Parse(labelWithPseudoOpacity2.Text); } set { @@ -23,6 +36,7 @@ namespace ArdupilotMega.Controls GetFontSize(); } } + [System.ComponentModel.Browsable(true)] public Color numberColor { get { return labelWithPseudoOpacity2.ForeColor; } set { if (labelWithPseudoOpacity2.ForeColor == value) return; labelWithPseudoOpacity2.ForeColor = value; } } diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs index 125f419e24..2465dfb733 100644 --- a/Tools/ArdupilotMegaPlanner/CurrentState.cs +++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs @@ -5,6 +5,7 @@ using System.Text; using System.ComponentModel; using ArdupilotMega.Utilities; using log4net; +using ArdupilotMega.Attributes; namespace ArdupilotMega { @@ -13,32 +14,46 @@ namespace ArdupilotMega private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType); // multipliers public float multiplierdist = 1; + internal string DistanceUnit = ""; public float multiplierspeed = 1; + internal string SpeedUnit = ""; // orientation - rads + [DisplayText("Roll (deg)")] public float roll { get; set; } + [DisplayText("Pitch (deg)")] public float pitch { get; set; } + [DisplayText("Yaw (deg)")] public float yaw { get { return _yaw; } set { if (value < 0) { _yaw = value + 360; } else { _yaw = value; } } } private float _yaw = 0; + [DisplayText("GroundCourse (deg)")] public float groundcourse { get { return _groundcourse; } set { if (value < 0) { _groundcourse = value + 360; } else { _groundcourse = value; } } } private float _groundcourse = 0; /// /// time over target in seconds /// + [DisplayText("Time over Target (sec)")] public int tot { get { if (groundspeed <= 0) return 0; return (int)(wp_dist / groundspeed); } } + [DisplayText("Dist Traveled (dist)")] public float distTraveled { get; set; } + [DisplayText("Time in Air (sec)")] public float timeInAir { get; set; } // speeds + [DisplayText("AirSpeed (speed)")] public float airspeed { get { return _airspeed * multiplierspeed; } set { _airspeed = value; } } + [DisplayText("GroundSpeed (speed)")] public float groundspeed { get { return _groundspeed * multiplierspeed; } set { _groundspeed = value; } } float _airspeed; float _groundspeed; float _verticalspeed; - public float verticalspeed { get { if (float.IsNaN(_verticalspeed)) _verticalspeed = 0; return _verticalspeed; } set { _verticalspeed = _verticalspeed * 0.4f + value * 0.6f; } } + [DisplayText("Vertical Speed (speed)")] + public float verticalspeed { get { if (float.IsNaN(_verticalspeed)) _verticalspeed = 0; return _verticalspeed * multiplierspeed; } set { _verticalspeed = _verticalspeed * 0.4f + value * 0.6f; } } + [DisplayText("Wind Direction (Deg)")] public float wind_dir { get; set; } + [DisplayText("Wind Velocity (speed)")] public float wind_vel { get; set; } /// /// used in wind calc @@ -52,39 +67,59 @@ namespace ArdupilotMega //(alt_now - alt_then)/(time_now-time_then) // position + [DisplayText("Latitude (dd)")] public float lat { get; set; } + [DisplayText("Longitude (dd)")] public float lng { get; set; } + [DisplayText("Altitude (dist)")] public float alt { get { return (_alt - altoffsethome) * multiplierdist; } set { _alt = value; } } DateTime lastalt = DateTime.Now; float oldalt = 0; + [DisplayText("Alt Home Offset (dist)")] public float altoffsethome { get; set; } private float _alt = 0; + [DisplayText("Gps Status")] public float gpsstatus { get; set; } + [DisplayText("Gps HDOP")] public float gpshdop { get; set; } + [DisplayText("Sat Count")] public float satcount { get; set; } public float altd1000 { get { return (alt / 1000) % 10; } } public float altd100 { get { return (alt / 100) % 10; } } // accel + [DisplayText("Accel X")] public float ax { get; set; } + [DisplayText("Accel Y")] public float ay { get; set; } + [DisplayText("Accel Z")] public float az { get; set; } // gyro + [DisplayText("Gyro X")] public float gx { get; set; } + [DisplayText("Gyro Y")] public float gy { get; set; } + [DisplayText("Gyro Z")] public float gz { get; set; } // mag + [DisplayText("Mag X")] public float mx { get; set; } + [DisplayText("Mag Y")] public float my { get; set; } + [DisplayText("Mag Z")] public float mz { get; set; } + [DisplayText("Mag Field")] public float magfield { get { return (float)Math.Sqrt(Math.Pow(mx, 2) + Math.Pow(my, 2) + Math.Pow(mz, 2)); } } + [DisplayText("Accel Strength")] public float accelsq { get { return (float)Math.Sqrt(Math.Pow(ax, 2) + Math.Pow(ay, 2) + Math.Pow(az, 2)) / 1000.0f /*980.665f*/; } } // calced turn rate + [DisplayText("Turn Rate (speed)")] public float turnrate { get { if (groundspeed <= 1) return 0; return (roll * 9.8f) / groundspeed; } } // turn radius + [DisplayText("Turn Radius (dist)")] public float radius { get { if (groundspeed <= 1) return 0; return ((groundspeed * groundspeed)/(float)(9.8f*Math.Tan(roll * deg2rad))); } } public float rxrssi { get; set; } @@ -136,43 +171,128 @@ namespace ArdupilotMega float _ch3percent = -1; //nav state + [DisplayText("Roll Target (deg)")] public float nav_roll { get; set; } + [DisplayText("Pitch Target (deg)")] public float nav_pitch { get; set; } + [DisplayText("Bearing Target (deg)")] public float nav_bearing { get; set; } + [DisplayText("Bearing Target (deg)")] public float target_bearing { get; set; } + [DisplayText("Dist to WP (dist)")] public float wp_dist { get { return (_wpdist * multiplierdist); } set { _wpdist = value; } } + [DisplayText("Altitude Error (dist)")] public float alt_error { get { return _alt_error * multiplierdist; } set { if (_alt_error == value) return; _alt_error = value; _targetalt = _targetalt * 0.5f + (float)Math.Round(alt + alt_error, 0) * 0.5f; } } + [DisplayText("Bearing Error (deg)")] public float ber_error { get { return (target_bearing - yaw); } set { } } + [DisplayText("Airspeed Error (speed)")] public float aspd_error { get { return _aspd_error * multiplierspeed; } set { if (_aspd_error == value) return; _aspd_error = value; _targetairspeed = _targetairspeed * 0.5f + (float)Math.Round(airspeed + aspd_error, 0) * 0.5f; } } + [DisplayText("Xtrack Error (m)")] public float xtrack_error { get; set; } + [DisplayText("WP No")] public float wpno { get; set; } + [DisplayText("Mode")] public string mode { get; set; } - public float climbrate { get; set; } + [DisplayText("ClimbRate (speed)")] + public float climbrate { get { return _climbrate * multiplierspeed; } set {_climbrate = value;} } float _wpdist; float _aspd_error; float _alt_error; float _targetalt; float _targetairspeed; + float _climbrate; public float targetaltd100 { get { return (_targetalt / 100) % 10; } } public float targetalt { get { return _targetalt; } } //airspeed_error = (airspeed_error - airspeed); + [DisplayText("Airspeed Target (speed)")] public float targetairspeed { get { return _targetairspeed; } } //message - public List messages { get; set; } - public string message { get { if (messages.Count == 0) return ""; return messages[messages.Count - 1]; } set { } } + internal List messages { get; set; } + internal string message { get { if (messages.Count == 0) return ""; return messages[messages.Count - 1]; } set { } } //battery + [DisplayText("Bat Voltage (V)")] public float battery_voltage { get { return _battery_voltage; } set { _battery_voltage = value / 1000; } } private float _battery_voltage; + [DisplayText("Bat Remaining (%)")] public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 100; if (_battery_remaining < 0 || _battery_remaining > 1) _battery_remaining = 0; } } private float _battery_remaining; + [DisplayText("Bat Current (Amps)")] public float current { get { return _current; } set { _current = value / 100; } } private float _current; + public float HomeAlt { get { return (float)HomeLocation.Alt; } set { } } + internal PointLatLngAlt HomeLocation = new PointLatLngAlt(); + + PointLatLngAlt _trackerloc = new PointLatLngAlt(); + internal PointLatLngAlt TrackerLocation { get { if (_trackerloc.Lng != 0) return _trackerloc; return HomeLocation; } set { _trackerloc = value; } } + + public float DistToMAV + { + get + { + // shrinking factor for longitude going to poles direction + double rads = Math.Abs(TrackerLocation.Lat) * 0.0174532925; + double scaleLongDown = Math.Cos(rads); + double scaleLongUp = 1.0f / Math.Cos(rads); + + //DST to Home + double dstlat = Math.Abs(TrackerLocation.Lat - lat) * 111319.5; + double dstlon = Math.Abs(TrackerLocation.Lng - lng) * 111319.5 * scaleLongDown; + return (float)Math.Sqrt((dstlat * dstlat) + (dstlon * dstlon)) * multiplierdist; + } + } + + [DisplayText("Elevation to Mav (deg)")] + public float ELToMAV + { + get + { + float dist = DistToMAV / multiplierdist; + + if (dist < 5) + return 0; + + float altdiff = (float)(alt - TrackerLocation.Alt); + + float angle = (float)Math.Atan(altdiff / dist) * rad2deg; + + return angle; + } + } + + [DisplayText("Bearing to Mav (deg)")] + public float AZToMAV + { + get + { + // shrinking factor for longitude going to poles direction + double rads = Math.Abs(TrackerLocation.Lat) * 0.0174532925; + double scaleLongDown = Math.Cos(rads); + double scaleLongUp = 1.0f / Math.Cos(rads); + + //DIR to Home + double dstlon = (TrackerLocation.Lng - lng); //OffSet_X + double dstlat = (TrackerLocation.Lat - lat) * scaleLongUp; //OffSet Y + double bearing = 90 + (Math.Atan2(dstlat, -dstlon) * 57.295775); //absolut home direction + if (bearing < 0) bearing += 360;//normalization + //bearing = bearing - 180;//absolut return direction + //if (bearing < 0) bearing += 360;//normalization + + float dist = DistToMAV / multiplierdist; + + if (dist < 5) + return 0; + + return (float)bearing; + } + } + + // pressure public float press_abs { get; set; } public int press_temp { get; set; } @@ -212,70 +332,6 @@ namespace ArdupilotMega public ushort rcoverridech8 { get; set; } - public float HomeAlt { get { return (float)HomeLocation.Alt; } set { } } - internal PointLatLngAlt HomeLocation = new PointLatLngAlt(); - - PointLatLngAlt _trackerloc = new PointLatLngAlt(); - internal PointLatLngAlt TrackerLocation { get { if (_trackerloc.Lng != 0) return _trackerloc; return HomeLocation; } set { _trackerloc = value; } } - - public float DistToMAV - { - get - { - // shrinking factor for longitude going to poles direction - double rads = Math.Abs(TrackerLocation.Lat) * 0.0174532925; - double scaleLongDown = Math.Cos(rads); - double scaleLongUp = 1.0f / Math.Cos(rads); - - //DST to Home - double dstlat = Math.Abs(TrackerLocation.Lat - lat) * 111319.5; - double dstlon = Math.Abs(TrackerLocation.Lng - lng) * 111319.5 * scaleLongDown; - return (float)Math.Sqrt((dstlat * dstlat) + (dstlon * dstlon)) * multiplierdist; - } - } - - public float ELToMAV - { - get - { - float dist = DistToMAV / multiplierdist; - - if (dist < 5) - return 0; - - float altdiff = (float)(alt - TrackerLocation.Alt); - - float angle = (float)Math.Atan(altdiff / dist) * rad2deg; - - return angle; - } - } - - public float AZToMAV - { - get - { - // shrinking factor for longitude going to poles direction - double rads = Math.Abs(TrackerLocation.Lat) * 0.0174532925; - double scaleLongDown = Math.Cos(rads); - double scaleLongUp = 1.0f / Math.Cos(rads); - - //DIR to Home - double dstlon = (TrackerLocation.Lng - lng); //OffSet_X - double dstlat = (TrackerLocation.Lat - lat) * scaleLongUp; //OffSet Y - double bearing = 90 + (Math.Atan2(dstlat, -dstlon) * 57.295775); //absolut home direction - if (bearing < 0) bearing += 360;//normalization - //bearing = bearing - 180;//absolut return direction - //if (bearing < 0) bearing += 360;//normalization - - float dist = DistToMAV / multiplierdist; - - if (dist < 5) - return 0; - - return (float)bearing; - } - } // current firmware public MainV2.Firmwares firmware = MainV2.Firmwares.ArduPlane; public float freemem { get; set; } @@ -368,6 +424,27 @@ namespace ArdupilotMega private DateTime lastsecondcounter = DateTime.Now; private PointLatLngAlt lastpos = new PointLatLngAlt(); + public string GetNameandUnit(string name) + { + string desc = name; + try + { + desc = ((Attributes.DisplayTextAttribute)typeof(CurrentState).GetProperty(name).GetCustomAttributes(false)[0]).Text; + } + catch { } + + if (desc.Contains("(dist)")) + { + desc = desc.Replace("(dist)", "(" + MainV2.cs.DistanceUnit + ")"); + } + else if (desc.Contains("(speed)")) + { + desc = desc.Replace("(speed)", "(" + MainV2.cs.SpeedUnit + ")"); + } + + return desc; + } + public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs) { UpdateCurrentSettings(bs, false, MainV2.comPort); @@ -485,7 +562,7 @@ namespace ArdupilotMega gotwind = true; wind_dir = (wind.direction + 360) % 360; - wind_vel = wind.speed; + wind_vel = wind.speed * multiplierspeed; //MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] = null; } diff --git a/Tools/ArdupilotMegaPlanner/FollowMe.cs b/Tools/ArdupilotMegaPlanner/FollowMe.cs index b68d62989b..804e3a9be4 100644 --- a/Tools/ArdupilotMegaPlanner/FollowMe.cs +++ b/Tools/ArdupilotMegaPlanner/FollowMe.cs @@ -6,7 +6,7 @@ using System.Drawing; using System.Linq; using System.Text; using System.Windows.Forms; -using System.IO.Ports; +using ArdupilotMega.Comms; using System.Globalization; namespace ArdupilotMega diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs index 6945d4cff7..ad1e19880e 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs @@ -53,6 +53,7 @@ this.timer1 = new System.Windows.Forms.Timer(this.components); this.CMB_apmversion = new System.Windows.Forms.ComboBox(); this.label1 = new System.Windows.Forms.Label(); + this.label2 = new System.Windows.Forms.Label(); this.groupBox4.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).BeginInit(); this.SuspendLayout(); @@ -135,6 +136,7 @@ // // CMB_batmonsensortype // + this.CMB_batmonsensortype.DropDownWidth = 150; this.CMB_batmonsensortype.FormattingEnabled = true; this.CMB_batmonsensortype.Items.AddRange(new object[] { resources.GetString("CMB_batmonsensortype.Items"), @@ -182,7 +184,7 @@ // pictureBox5 // this.pictureBox5.BackColor = System.Drawing.Color.White; - this.pictureBox5.BackgroundImage = global::ArdupilotMega.Properties.Resources.attocurrent; + this.pictureBox5.BackgroundImage = global::ArdupilotMega.Properties.Resources.BR_APMPWRDEAN_2; resources.ApplyResources(this.pictureBox5, "pictureBox5"); this.pictureBox5.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle; this.pictureBox5.Name = "pictureBox5"; @@ -209,10 +211,16 @@ resources.ApplyResources(this.label1, "label1"); this.label1.Name = "label1"; // + // label2 + // + resources.ApplyResources(this.label2, "label2"); + this.label2.Name = "label2"; + // // ConfigBatteryMonitoring // resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.label2); this.Controls.Add(this.label1); this.Controls.Add(this.CMB_apmversion); this.Controls.Add(this.groupBox4); @@ -257,5 +265,6 @@ private System.Windows.Forms.Timer timer1; private System.Windows.Forms.ComboBox CMB_apmversion; private System.Windows.Forms.Label label1; + private System.Windows.Forms.Label label2; } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx index 3017f98535..191585aebe 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx @@ -427,7 +427,7 @@ $this - 2 + 3 NoControl @@ -454,7 +454,7 @@ $this - 3 + 4 0: Other @@ -469,7 +469,7 @@ 3: AttoPilot 180A - 4: 3DR IV Sensor + 4: 3DR Power Module 160, 68 @@ -490,7 +490,7 @@ $this - 4 + 5 Microsoft Sans Serif, 8.25pt @@ -526,7 +526,7 @@ Then subtract 0.3v from that value and enter it in field #1 at left. $this - 5 + 6 True @@ -535,16 +535,16 @@ Then subtract 0.3v from that value and enter it in field #1 at left. NoControl - 288, 45 + 287, 44 - 48, 13 + 84, 13 43 - Capacity + Battery Capacity label29 @@ -556,7 +556,7 @@ Then subtract 0.3v from that value and enter it in field #1 at left. $this - 6 + 7 NoControl @@ -583,17 +583,20 @@ Then subtract 0.3v from that value and enter it in field #1 at left. $this - 7 + 8 - 349, 42 + 377, 41 - 83, 20 + 50, 20 45 + + 2200 + TXT_battcapacity @@ -604,7 +607,7 @@ Then subtract 0.3v from that value and enter it in field #1 at left. $this - 8 + 9 0: Disabled @@ -634,7 +637,7 @@ Then subtract 0.3v from that value and enter it in field #1 at left. $this - 9 + 10 Zoom @@ -643,10 +646,10 @@ Then subtract 0.3v from that value and enter it in field #1 at left. NoControl - 14, 16 + 3, 41 - 75, 75 + 97, 75 42 @@ -661,7 +664,7 @@ Then subtract 0.3v from that value and enter it in field #1 at left. $this - 10 + 11 17, 17 @@ -694,7 +697,7 @@ Then subtract 0.3v from that value and enter it in field #1 at left. $this - 1 + 2 NoControl @@ -721,6 +724,36 @@ Then subtract 0.3v from that value and enter it in field #1 at left. $this + 1 + + + True + + + NoControl + + + 433, 44 + + + 28, 13 + + + 53 + + + mAh + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + 0 diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs index 5b802558fd..aa260d7f0c 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs @@ -112,7 +112,7 @@ If you are just setting up 3DR radios, you may continue without connecting."); AddBackstageViewPage(configpanel, "ArduCopter Pids", standardpage); AddBackstageViewPage(new ConfigArducopter(), "ArduCopter Config", standardpage); - // AddBackstageViewPage(new ConfigAP_Limits(), "GeoFence"); + AddBackstageViewPage(new ConfigAP_Limits(), "GeoFence"); } /****************************** ArduPlane **************************/ else if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs index 599e7bee7b..c78b9f7cbd 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs @@ -2,11 +2,11 @@ using System.Collections.Generic; using System.Reflection; using System.Windows.Forms; -using System.IO.Ports; using System.IO; using System.Xml; using System.Net; using log4net; +using ArdupilotMega.Comms; using ArdupilotMega.Arduino; using ArdupilotMega.Utilities; using System.Text.RegularExpressions; @@ -491,8 +491,8 @@ namespace ArdupilotMega.GCSViews }; } port.DataBits = 8; - port.StopBits = StopBits.One; - port.Parity = Parity.None; + port.StopBits = System.IO.Ports.StopBits.One; + port.Parity = System.IO.Ports.Parity.None; port.DtrEnable = true; try @@ -606,7 +606,11 @@ namespace ArdupilotMega.GCSViews { lbl_status.Text = "Failed upload"; CustomMessageBox.Show("Check port settings or Port in use? " + ex); - port.Close(); + try + { + port.Close(); + } + catch { } } flashing = false; MainV2.giveComport = false; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs index b234392b1e..2052ef5dfb 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs @@ -8,8 +8,8 @@ { this.components = new System.ComponentModel.Container(); 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(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle7 = new System.Windows.Forms.DataGridViewCellStyle(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle8 = 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(); @@ -70,11 +70,12 @@ this.tableMap = new System.Windows.Forms.TableLayoutPanel(); this.splitContainer1 = new System.Windows.Forms.SplitContainer(); this.zg1 = new ZedGraph.ZedGraphControl(); + this.gMapControl1 = new ArdupilotMega.Controls.myGMAP(); + this.TRK_zoom = new ArdupilotMega.Controls.MyTrackBar(); this.lbl_winddir = new ArdupilotMega.Controls.MyLabel(); this.lbl_windvel = new ArdupilotMega.Controls.MyLabel(); this.lbl_hdop = new ArdupilotMega.Controls.MyLabel(); this.lbl_sats = new ArdupilotMega.Controls.MyLabel(); - this.gMapControl1 = new ArdupilotMega.Controls.myGMAP(); this.panel1 = new System.Windows.Forms.Panel(); this.TXT_lat = new ArdupilotMega.Controls.MyLabel(); this.Zoomlevel = new System.Windows.Forms.NumericUpDown(); @@ -87,8 +88,6 @@ 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.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(); @@ -109,9 +108,9 @@ this.splitContainer1.Panel1.SuspendLayout(); this.splitContainer1.Panel2.SuspendLayout(); this.splitContainer1.SuspendLayout(); + ((System.ComponentModel.ISupportInitialize)(this.TRK_zoom)).BeginInit(); this.panel1.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).BeginInit(); - this.contextMenuStripDockContainer.SuspendLayout(); this.SuspendLayout(); // // contextMenuStripMap @@ -1117,11 +1116,12 @@ // splitContainer1.Panel2 // this.splitContainer1.Panel2.ContextMenuStrip = this.contextMenuStripMap; + this.splitContainer1.Panel2.Controls.Add(this.gMapControl1); + this.splitContainer1.Panel2.Controls.Add(this.TRK_zoom); this.splitContainer1.Panel2.Controls.Add(this.lbl_winddir); this.splitContainer1.Panel2.Controls.Add(this.lbl_windvel); this.splitContainer1.Panel2.Controls.Add(this.lbl_hdop); this.splitContainer1.Panel2.Controls.Add(this.lbl_sats); - this.splitContainer1.Panel2.Controls.Add(this.gMapControl1); // // zg1 // @@ -1136,6 +1136,44 @@ this.zg1.ScrollMinY2 = 0D; this.zg1.DoubleClick += new System.EventHandler(this.zg1_DoubleClick); // + // gMapControl1 + // + this.gMapControl1.Bearing = 0F; + this.gMapControl1.CanDragMap = true; + this.gMapControl1.ContextMenuStrip = this.contextMenuStripMap; + resources.ApplyResources(this.gMapControl1, "gMapControl1"); + this.gMapControl1.GrayScaleMode = false; + this.gMapControl1.LevelsKeepInMemmory = 5; + this.gMapControl1.MarkersEnabled = true; + this.gMapControl1.MaxZoom = 2; + this.gMapControl1.MinZoom = 2; + this.gMapControl1.MouseWheelZoomType = GMap.NET.MouseWheelZoomType.MousePositionAndCenter; + this.gMapControl1.Name = "gMapControl1"; + this.gMapControl1.NegativeMode = false; + this.gMapControl1.PolygonsEnabled = true; + this.gMapControl1.RetryLoadTile = 0; + this.gMapControl1.RoutesEnabled = true; + this.gMapControl1.ShowTileGridLines = false; + this.gMapControl1.streamjpg = ((System.IO.MemoryStream)(resources.GetObject("gMapControl1.streamjpg"))); + this.gMapControl1.Zoom = 0D; + this.gMapControl1.Click += new System.EventHandler(this.gMapControl1_Click); + this.gMapControl1.MouseDown += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseDown); + this.gMapControl1.MouseLeave += new System.EventHandler(this.gMapControl1_MouseLeave); + this.gMapControl1.MouseMove += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseMove); + // + // TRK_zoom + // + resources.ApplyResources(this.TRK_zoom, "TRK_zoom"); + this.TRK_zoom.LargeChange = 100; + this.TRK_zoom.Maximum = 18D; + this.TRK_zoom.Minimum = 1D; + this.TRK_zoom.Name = "TRK_zoom"; + this.TRK_zoom.SmallChange = 50; + this.TRK_zoom.TickFrequency = 100; + this.TRK_zoom.TickStyle = System.Windows.Forms.TickStyle.Both; + this.TRK_zoom.Value = 10D; + this.TRK_zoom.Scroll += new System.EventHandler(this.TRK_zoom_Scroll); + // // lbl_winddir // this.lbl_winddir.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_dir", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Dir: 0")); @@ -1168,32 +1206,6 @@ this.lbl_sats.resize = true; this.toolTip1.SetToolTip(this.lbl_sats, resources.GetString("lbl_sats.ToolTip")); // - // gMapControl1 - // - this.gMapControl1.BackColor = System.Drawing.Color.Transparent; - this.gMapControl1.Bearing = 0F; - this.gMapControl1.CanDragMap = true; - this.gMapControl1.ContextMenuStrip = this.contextMenuStripMap; - resources.ApplyResources(this.gMapControl1, "gMapControl1"); - this.gMapControl1.GrayScaleMode = false; - this.gMapControl1.LevelsKeepInMemmory = 5; - this.gMapControl1.MarkersEnabled = true; - this.gMapControl1.MaxZoom = 2; - this.gMapControl1.MinZoom = 2; - this.gMapControl1.MouseWheelZoomType = GMap.NET.MouseWheelZoomType.MousePositionAndCenter; - this.gMapControl1.Name = "gMapControl1"; - this.gMapControl1.NegativeMode = false; - this.gMapControl1.PolygonsEnabled = true; - this.gMapControl1.RetryLoadTile = 0; - this.gMapControl1.RoutesEnabled = true; - this.gMapControl1.ShowTileGridLines = false; - this.gMapControl1.streamjpg = ((System.IO.MemoryStream)(resources.GetObject("gMapControl1.streamjpg"))); - this.gMapControl1.Zoom = 0D; - this.gMapControl1.Click += new System.EventHandler(this.gMapControl1_Click); - this.gMapControl1.MouseDown += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseDown); - this.gMapControl1.MouseLeave += new System.EventHandler(this.gMapControl1_MouseLeave); - this.gMapControl1.MouseMove += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseMove); - // // panel1 // this.panel1.Controls.Add(this.TXT_lat); @@ -1281,8 +1293,8 @@ // // dataGridViewImageColumn1 // - dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; - this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle1; + dataGridViewCellStyle7.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; + this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle7; resources.ApplyResources(this.dataGridViewImageColumn1, "dataGridViewImageColumn1"); this.dataGridViewImageColumn1.Image = global::ArdupilotMega.Properties.Resources.up; this.dataGridViewImageColumn1.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; @@ -1290,8 +1302,8 @@ // // dataGridViewImageColumn2 // - dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; - this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle2; + dataGridViewCellStyle8.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; + this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle8; resources.ApplyResources(this.dataGridViewImageColumn2, "dataGridViewImageColumn2"); this.dataGridViewImageColumn2.Image = global::ArdupilotMega.Properties.Resources.down; this.dataGridViewImageColumn2.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; @@ -1306,19 +1318,6 @@ 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))))); // - // 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"); @@ -1350,11 +1349,12 @@ this.tableMap.ResumeLayout(false); this.splitContainer1.Panel1.ResumeLayout(false); this.splitContainer1.Panel2.ResumeLayout(false); + this.splitContainer1.Panel2.PerformLayout(); this.splitContainer1.ResumeLayout(false); + ((System.ComponentModel.ISupportInitialize)(this.TRK_zoom)).EndInit(); this.panel1.ResumeLayout(false); this.panel1.PerformLayout(); ((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).EndInit(); - this.contextMenuStripDockContainer.ResumeLayout(false); this.ResumeLayout(false); } @@ -1433,12 +1433,11 @@ 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; private Controls.MyButton BUT_ARM; private Controls.ModifyandSet modifyandSetAlt; private Controls.ModifyandSet modifyandSetSpeed; private System.Windows.Forms.ToolStripMenuItem triggerCameraToolStripMenuItem; + private Controls.MyTrackBar TRK_zoom; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs index 326ac672ff..da8f7f40ce 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs @@ -140,24 +140,6 @@ namespace ArdupilotMega.GCSViews chk_box_CheckedChanged((object)(new CheckBox() { Name = "nav_pitch", Checked = true }), new EventArgs()); } - for (int f = 1; f < 10; f++) - { - // load settings - if (MainV2.config["quickView" + f] != null) - { - Control[] ctls = this.Controls.Find("quickView" + f, true); - if (ctls.Length > 0) - { - // set description - ((QuickView)ctls[0]).desc = MainV2.config["quickView" + f].ToString(); - - // set databinding for value - ((QuickView)ctls[0]).DataBindings.Clear(); - ((QuickView)ctls[0]).DataBindings.Add(new System.Windows.Forms.Binding("number", this.bindingSource1, MainV2.config["quickView" + f].ToString(), true)); - } - } - } - foreach (string item in MainV2.config.Keys) { if (item.StartsWith("hud1_useritem_")) @@ -345,6 +327,24 @@ namespace ArdupilotMega.GCSViews hud1.Dock = DockStyle.Fill; } + for (int f = 1; f < 10; f++) + { + // load settings + if (MainV2.config["quickView" + f] != null) + { + Control[] ctls = this.Controls.Find("quickView" + f, true); + if (ctls.Length > 0) + { + // set description + ((QuickView)ctls[0]).desc = MainV2.cs.GetNameandUnit(MainV2.config["quickView" + f].ToString()); + + // set databinding for value + ((QuickView)ctls[0]).DataBindings.Clear(); + ((QuickView)ctls[0]).DataBindings.Add(new System.Windows.Forms.Binding("number", this.bindingSource1, MainV2.config["quickView" + f].ToString(), true)); + } + } + } + if (MainV2.comPort.param.ContainsKey("BATT_MONITOR") && (float)MainV2.comPort.param["BATT_MONITOR"] != 0) { hud1.batteryon = true; @@ -396,6 +396,7 @@ namespace ArdupilotMega.GCSViews void gMapControl1_OnMapZoomChanged() { + TRK_zoom.Value = gMapControl1.Zoom; Zoomlevel.Value = Convert.ToDecimal(gMapControl1.Zoom); } @@ -410,6 +411,10 @@ namespace ArdupilotMega.GCSViews t11.Start(); //MainH.threads.Add(t11); + TRK_zoom.Minimum = gMapControl1.MinZoom; + TRK_zoom.Maximum = gMapControl1.MaxZoom + 1; + TRK_zoom.Value = gMapControl1.Zoom; + Zoomlevel.Minimum = gMapControl1.MinZoom; Zoomlevel.Maximum = gMapControl1.MaxZoom + 1; Zoomlevel.Value = Convert.ToDecimal(gMapControl1.Zoom); @@ -2308,7 +2313,7 @@ print 'Roll complete' CheckBox chk_box = new CheckBox(); - if (((QuickView)sender).desc == field.Name) + if (((QuickView)sender).Tag == field.Name) chk_box.Checked = true; chk_box.Text = field.Name; @@ -2345,7 +2350,12 @@ print 'Roll complete' MainV2.config[((QuickView)((CheckBox)sender).Tag).Name] = ((CheckBox)sender).Name; // set description - ((QuickView)((CheckBox)sender).Tag).desc = ((CheckBox)sender).Name; + string desc = ((CheckBox)sender).Name; + ((QuickView)((CheckBox)sender).Tag).Tag = desc; + + desc = MainV2.cs.GetNameandUnit(desc); + + ((QuickView)((CheckBox)sender).Tag).desc = desc; // set databinding for value ((QuickView)((CheckBox)sender).Tag).DataBindings.Clear(); @@ -2562,5 +2572,22 @@ print 'Roll complete' } catch { CustomMessageBox.Show("Error sending command"); } } + + private void TRK_zoom_Scroll(object sender, EventArgs e) + { + try + { + if (gMapControl1.MaxZoom + 1 == (double)TRK_zoom.Value) + { + gMapControl1.Zoom = (double)TRK_zoom.Value - .1; + } + else + { + gMapControl1.Zoom = (double)TRK_zoom.Value; + } + } + catch { } + } + } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx index 480b630e27..16ac76de0c 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx @@ -121,6 +121,15 @@ 290, 17 + + 189, 114 + + + contextMenuStripMap + + + System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + 188, 22 @@ -151,15 +160,6 @@ Flight Planner - - 189, 114 - - - contextMenuStripMap - - - System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - Fill @@ -185,38 +185,8 @@ 542, 17 - - 172, 22 - - - Record Hud to AVI - - - 172, 22 - - - Stop Record - - - 172, 22 - - - Set MJPEG source - - - 172, 22 - - - Set Aspect Ratio - - - 172, 22 - - - User Items - - 173, 136 + 173, 114 contextMenuStripHud @@ -244,7 +214,7 @@ hud1 - ArdupilotMega.Controls.HUD, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.HUD, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null SubMainLeft.Panel1 @@ -264,174 +234,6 @@ 0 - - True - - - Top - - - 3, 278 - - - 327, 55 - - - 10 - - - quickView6 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 0 - - - Top - - - 3, 223 - - - 327, 55 - - - 9 - - - quickView5 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 1 - - - Top - - - 3, 168 - - - 327, 55 - - - 8 - - - quickView4 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 2 - - - Top - - - 3, 113 - - - 327, 55 - - - 3 - - - quickView3 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 3 - - - Top - - - 3, 58 - - - 327, 55 - - - 1 - - - quickView2 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 4 - - - Top - - - 3, 3 - - - 327, 55 - - - 1 - - - 445, 17 - - - Double Click me to change - - - quickView1 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 5 - - - 4, 22 - - - 3, 3, 3, 3 - - - 350, 117 - - - 4 - - - Quick - tabQuick @@ -444,516 +246,6 @@ 0 - - 275, 35 - - - 114, 32 - - - 81 - - - modifyandSetSpeed - - - ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 0 - - - 216, 90 - - - 114, 29 - - - 80 - - - modifyandSetAlt - - - ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 1 - - - Microsoft Sans Serif, 8.25pt - - - NoControl - - - 111, 90 - - - 45, 23 - - - 79 - - - Arm/ Disarm - - - Arm the Mav - - - BUT_ARM - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 2 - - - NoControl - - - 4, 91 - - - 46, 23 - - - 78 - - - Script - - - BUT_script - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 3 - - - NoControl - - - 56, 91 - - - 49, 23 - - - 77 - - - Joystick - - - Setup and enable your joystick - - - BUT_joystick - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 4 - - - NoControl - - - 147, 35 - - - 47, 23 - - - 76 - - - &Manual - - - Change Mode to Manual/Stabalize - - - BUT_quickmanual - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 5 - - - NoControl - - - 147, 64 - - - 47, 23 - - - 75 - - - &RTL - - - Change Mode to RTL - - - BUT_quickrtl - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 6 - - - NoControl - - - 147, 6 - - - 47, 23 - - - 74 - - - &Auto - - - Change mode to Auto - - - BUT_quickauto - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 7 - - - 0 (Home) - - - 4, 35 - - - 76, 21 - - - 72 - - - CMB_setwp - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabActions - - - 8 - - - NoControl - - - 86, 35 - - - 55, 23 - - - 73 - - - Set WP - - - Changes the current target waypoint - - - BUT_setwp - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 9 - - - 4, 64 - - - 76, 21 - - - 70 - - - CMB_modes - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabActions - - - 10 - - - NoControl - - - 86, 64 - - - 55, 23 - - - 71 - - - Set Mode - - - Changes to the Mode on the left - - - BUT_setmode - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 11 - - - NoControl - - - 162, 90 - - - 47, 23 - - - 52 - - - Clear Track - - - Clear the recorded path on the map - - - BUT_clear_track - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 12 - - - 4, 6 - - - 76, 21 - - - 59 - - - CMB_action - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabActions - - - 13 - - - NoControl - - - 200, 6 - - - 69, 23 - - - 69 - - - Set Home Alt - - - Set the current display alt as 0, ie home alt is shown as 0 - - - BUT_Homealt - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 14 - - - NoControl - - - 200, 64 - - - 69, 23 - - - 68 - - - Raw Sensor View - - - View raw Gyro and Accel values, and Raw Radio ins/outs - - - BUT_RAWSensor - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 15 - - - NoControl - - - 200, 35 - - - 69, 23 - - - 63 - - - Restart Mission - - - Restarts the mission from the beginning - - - BUTrestartmission - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 16 - - - NoControl - - - 86, 6 - - - 55, 23 - - - 60 - - - Do Action - - - Preform the action ot the left - - - BUTactiondo - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabActions - - - 17 - - - 4, 22 - - - 350, 117 - - - 2 - - - Actions - tabActions @@ -966,144 +258,6 @@ 1 - - Zoom - - - Microsoft Sans Serif, 9pt - - - 3, 6 - - - 0, 0, 0, 0 - - - 100, 100 - - - 82 - - - Gvspeed - - - AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabGauges - - - 0 - - - Zoom - - - Microsoft Sans Serif, 9pt - - - 303, 6 - - - 0, 0, 0, 0 - - - 100, 100 - - - 80 - - - Gheading - - - ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabGauges - - - 1 - - - Zoom - - - Microsoft Sans Serif, 9pt - - - 203, 6 - - - 0, 0, 0, 0 - - - 100, 100 - - - 81 - - - Galt - - - AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabGauges - - - 2 - - - Zoom - - - Microsoft Sans Serif, 9pt - - - 103, 6 - - - 0, 0, 0, 0 - - - 100, 100 - - - 79 - - - Double click me to change Max - - - Gspeed - - - AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabGauges - - - 3 - - - 4, 22 - - - 3, 3, 3, 3 - - - 350, 117 - - - 0 - - - Gauges - tabGauges @@ -1116,24 +270,6 @@ 2 - - True - - - 4, 22 - - - 3, 3, 3, 3 - - - 350, 117 - - - 1 - - - Status - tabStatus @@ -1146,207 +282,6 @@ 3 - - Top, Right - - - 253, 54 - - - 51, 20 - - - 79 - - - x 1.0 - - - lbl_playbackspeed - - - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabTLogs - - - 0 - - - Top, Right - - - 253, 32 - - - 51, 20 - - - 78 - - - 0.00 % - - - lbl_logpercent - - - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabTLogs - - - 1 - - - Top, Left, Right - - - 178, 40 - - - 73, 45 - - - 77 - - - Playback Speed - - - NUM_playbackspeed - - - ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabTLogs - - - 2 - - - NoControl - - - 29, 32 - - - 127, 23 - - - 76 - - - Tlog > Kml or Graph - - - BUT_log2kml - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabTLogs - - - 3 - - - Top, Left, Right - - - NoControl - - - 178, 3 - - - 110, 45 - - - 75 - - - tracklog - - - System.Windows.Forms.TrackBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabTLogs - - - 4 - - - NoControl - - - 89, 3 - - - 80, 23 - - - 73 - - - Play/Pause - - - BUT_playlog - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabTLogs - - - 5 - - - NoControl - - - 3, 3 - - - 80, 23 - - - 71 - - - Load Log - - - BUT_loadtelem - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - tabTLogs - - - 6 - - - 4, 22 - - - 350, 117 - - - 3 - - - Telemetry Logs - tabTLogs @@ -1440,6 +375,1638 @@ 1 + + splitContainer1 + + + System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tableMap + + + 0 + + + panel1 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tableMap + + + 1 + + + Fill + + + 0, 0 + + + 2 + + + 642, 459 + + + 75 + + + tableMap + + + System.Windows.Forms.TableLayoutPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + MainH.Panel2 + + + 0 + + + <?xml version="1.0" encoding="utf-16"?><TableLayoutSettings><Controls><Control Name="splitContainer1" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /><Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /></Controls><Columns Styles="Percent,100" /><Rows Styles="Percent,100,Absolute,30,Absolute,20" /></TableLayoutSettings> + + + MainH.Panel2 + + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + MainH + + + 1 + + + 1008, 461 + + + 360 + + + 68 + + + MainH + + + System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + 172, 22 + + + Record Hud to AVI + + + 172, 22 + + + Stop Record + + + 172, 22 + + + Set MJPEG source + + + 172, 22 + + + Set Aspect Ratio + + + 172, 22 + + + User Items + + + True + + + quickView6 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 0 + + + quickView5 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 1 + + + quickView4 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 2 + + + quickView3 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 3 + + + quickView2 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 4 + + + quickView1 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 5 + + + 4, 22 + + + 3, 3, 3, 3 + + + 350, 117 + + + 4 + + + Quick + + + tabQuick + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 0 + + + Top + + + 3, 278 + + + 327, 55 + + + 10 + + + quickView6 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 0 + + + Top + + + 3, 223 + + + 327, 55 + + + 9 + + + quickView5 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 1 + + + Top + + + 3, 168 + + + 327, 55 + + + 8 + + + quickView4 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 2 + + + Top + + + 3, 113 + + + 327, 55 + + + 3 + + + quickView3 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 3 + + + Top + + + 3, 58 + + + 327, 55 + + + 1 + + + quickView2 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 4 + + + 445, 17 + + + Top + + + 3, 3 + + + 327, 55 + + + 1 + + + Double Click me to change + + + quickView1 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 5 + + + modifyandSetSpeed + + + ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 0 + + + modifyandSetAlt + + + ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 1 + + + BUT_ARM + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 2 + + + BUT_script + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 3 + + + BUT_joystick + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 4 + + + BUT_quickmanual + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 5 + + + BUT_quickrtl + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 6 + + + BUT_quickauto + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 7 + + + CMB_setwp + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabActions + + + 8 + + + BUT_setwp + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 9 + + + CMB_modes + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabActions + + + 10 + + + BUT_setmode + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 11 + + + BUT_clear_track + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 12 + + + CMB_action + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabActions + + + 13 + + + BUT_Homealt + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 14 + + + BUT_RAWSensor + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 15 + + + BUTrestartmission + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 16 + + + BUTactiondo + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 17 + + + 4, 22 + + + 350, 117 + + + 2 + + + Actions + + + tabActions + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 1 + + + 275, 35 + + + 114, 32 + + + 81 + + + modifyandSetSpeed + + + ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 0 + + + 216, 90 + + + 114, 29 + + + 80 + + + modifyandSetAlt + + + ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 1 + + + Microsoft Sans Serif, 8.25pt + + + NoControl + + + 111, 90 + + + 45, 23 + + + 79 + + + Arm/ Disarm + + + Arm the Mav + + + BUT_ARM + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 2 + + + NoControl + + + 4, 91 + + + 46, 23 + + + 78 + + + Script + + + BUT_script + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 3 + + + NoControl + + + 56, 91 + + + 49, 23 + + + 77 + + + Joystick + + + Setup and enable your joystick + + + BUT_joystick + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 4 + + + NoControl + + + 147, 35 + + + 47, 23 + + + 76 + + + &Manual + + + Change Mode to Manual/Stabalize + + + BUT_quickmanual + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 5 + + + NoControl + + + 147, 64 + + + 47, 23 + + + 75 + + + &RTL + + + Change Mode to RTL + + + BUT_quickrtl + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 6 + + + NoControl + + + 147, 6 + + + 47, 23 + + + 74 + + + &Auto + + + Change mode to Auto + + + BUT_quickauto + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 7 + + + 0 (Home) + + + 4, 35 + + + 76, 21 + + + 72 + + + CMB_setwp + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabActions + + + 8 + + + NoControl + + + 86, 35 + + + 55, 23 + + + 73 + + + Set WP + + + Changes the current target waypoint + + + BUT_setwp + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 9 + + + 4, 64 + + + 76, 21 + + + 70 + + + CMB_modes + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabActions + + + 10 + + + NoControl + + + 86, 64 + + + 55, 23 + + + 71 + + + Set Mode + + + Changes to the Mode on the left + + + BUT_setmode + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 11 + + + NoControl + + + 162, 90 + + + 47, 23 + + + 52 + + + Clear Track + + + Clear the recorded path on the map + + + BUT_clear_track + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 12 + + + 4, 6 + + + 76, 21 + + + 59 + + + CMB_action + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabActions + + + 13 + + + NoControl + + + 200, 6 + + + 69, 23 + + + 69 + + + Set Home Alt + + + Set the current display alt as 0, ie home alt is shown as 0 + + + BUT_Homealt + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 14 + + + NoControl + + + 200, 64 + + + 69, 23 + + + 68 + + + Raw Sensor View + + + View raw Gyro and Accel values, and Raw Radio ins/outs + + + BUT_RAWSensor + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 15 + + + NoControl + + + 200, 35 + + + 69, 23 + + + 63 + + + Restart Mission + + + Restarts the mission from the beginning + + + BUTrestartmission + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 16 + + + NoControl + + + 86, 6 + + + 55, 23 + + + 60 + + + Do Action + + + Preform the action ot the left + + + BUTactiondo + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 17 + + + Gvspeed + + + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 0 + + + Gheading + + + ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 1 + + + Galt + + + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 2 + + + Gspeed + + + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 3 + + + 4, 22 + + + 3, 3, 3, 3 + + + 350, 117 + + + 0 + + + Gauges + + + tabGauges + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 2 + + + Zoom + + + Microsoft Sans Serif, 9pt + + + 3, 6 + + + 0, 0, 0, 0 + + + 100, 100 + + + 82 + + + Gvspeed + + + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 0 + + + Zoom + + + Microsoft Sans Serif, 9pt + + + 303, 6 + + + 0, 0, 0, 0 + + + 100, 100 + + + 80 + + + Gheading + + + ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 1 + + + Zoom + + + Microsoft Sans Serif, 9pt + + + 203, 6 + + + 0, 0, 0, 0 + + + 100, 100 + + + 81 + + + Galt + + + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 2 + + + Zoom + + + Microsoft Sans Serif, 9pt + + + 103, 6 + + + 0, 0, 0, 0 + + + 100, 100 + + + 79 + + + Double click me to change Max + + + Gspeed + + + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 3 + + + True + + + 4, 22 + + + 3, 3, 3, 3 + + + 350, 117 + + + 1 + + + Status + + + tabStatus + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 3 + + + lbl_playbackspeed + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 0 + + + lbl_logpercent + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 1 + + + NUM_playbackspeed + + + ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 2 + + + BUT_log2kml + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 3 + + + tracklog + + + System.Windows.Forms.TrackBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabTLogs + + + 4 + + + BUT_playlog + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 5 + + + BUT_loadtelem + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 6 + + + 4, 22 + + + 350, 117 + + + 3 + + + Telemetry Logs + + + tabTLogs + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 4 + + + Top, Right + + + 253, 54 + + + 51, 20 + + + 79 + + + x 1.0 + + + lbl_playbackspeed + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 0 + + + Top, Right + + + 253, 32 + + + 51, 20 + + + 78 + + + 0.00 % + + + lbl_logpercent + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 1 + + + Top, Left, Right + + + 178, 40 + + + 73, 45 + + + 77 + + + Playback Speed + + + NUM_playbackspeed + + + ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 2 + + + NoControl + + + 29, 32 + + + 127, 23 + + + 76 + + + Tlog > Kml or Graph + + + BUT_log2kml + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 3 + + + Top, Left, Right + + + NoControl + + + 178, 3 + + + 110, 45 + + + 75 + + + tracklog + + + System.Windows.Forms.TrackBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabTLogs + + + 4 + + + NoControl + + + 89, 3 + + + 80, 23 + + + 73 + + + Play/Pause + + + BUT_playlog + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 5 + + + NoControl + + + 3, 3 + + + 80, 23 + + + 71 + + + Load Log + + + BUT_loadtelem + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 6 + Fill @@ -1491,132 +2058,6 @@ 0 - - NoControl - - - 4, 3 - - - 46, 12 - - - 68 - - - Dir: 0 - - - Estimated Wind Direction - - - lbl_winddir - - - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - splitContainer1.Panel2 - - - 0 - - - NoControl - - - 4, 23 - - - 48, 12 - - - 69 - - - Vel: 0 - - - Estimated Wind Velocity - - - lbl_windvel - - - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - splitContainer1.Panel2 - - - 1 - - - Bottom, Left - - - NoControl - - - -1, 390 - - - 43, 12 - - - 70 - - - hdop: 0 - - - gps hdop - - - lbl_hdop - - - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - splitContainer1.Panel2 - - - 2 - - - Bottom, Left - - - NoControl - - - -1, 408 - - - 40, 12 - - - 71 - - - Sats: 0 - - - Satallite Count - - - lbl_sats - - - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null - - - splitContainer1.Panel2 - - - 3 - Fill @@ -1627,7 +2068,7 @@ 0, 0, 0, 0 - 634, 420 + 589, 420 @@ -1781,14 +2222,167 @@ gMapControl1 - ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 + 0 + + + Right + + + 589, 0 + + + Vertical + + + 45, 420 + + + 72 + + + TRK_zoom + + + ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + splitContainer1.Panel2 + + + 1 + + + NoControl + + + 4, 3 + + + 46, 12 + + + 68 + + + Dir: 0 + + + Estimated Wind Direction + + + lbl_winddir + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + splitContainer1.Panel2 + + + 2 + + + NoControl + + + 4, 23 + + + 48, 12 + + + 69 + + + Vel: 0 + + + Estimated Wind Velocity + + + lbl_windvel + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + splitContainer1.Panel2 + + + 3 + + + Bottom, Left + + + NoControl + + + -1, 390 + + + 43, 12 + + + 70 + + + hdop: 0 + + + gps hdop + + + lbl_hdop + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + splitContainer1.Panel2 + + 4 + + Bottom, Left + + + NoControl + + + -1, 408 + + + 40, 12 + + + 71 + + + Sats: 0 + + + Satallite Count + + + lbl_sats + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + splitContainer1.Panel2 + + + 5 + splitContainer1.Panel2 @@ -1822,6 +2416,117 @@ 0 + + TXT_lat + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + panel1 + + + 0 + + + Zoomlevel + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 1 + + + label1 + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + panel1 + + + 2 + + + TXT_long + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + panel1 + + + 3 + + + TXT_alt + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null + + + panel1 + + + 4 + + + CHK_autopan + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 5 + + + CB_tuning + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 6 + + + Fill + + + 1, 428 + + + 0, 0, 0, 0 + + + 640, 30 + + + 0 + + + panel1 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tableMap + + + 1 + Bottom, Left @@ -1844,7 +2549,7 @@ TXT_lat - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null panel1 @@ -1901,7 +2606,7 @@ label1 - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null panel1 @@ -1931,7 +2636,7 @@ TXT_long - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null panel1 @@ -1961,7 +2666,7 @@ TXT_alt - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4712.38843, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4714.36626, Culture=neutral, PublicKeyToken=null panel1 @@ -2041,96 +2746,6 @@ 6 - - Fill - - - 1, 428 - - - 0, 0, 0, 0 - - - 640, 30 - - - 0 - - - panel1 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tableMap - - - 1 - - - Fill - - - 0, 0 - - - 2 - - - 642, 459 - - - 75 - - - tableMap - - - System.Windows.Forms.TableLayoutPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - MainH.Panel2 - - - 0 - - - <?xml version="1.0" encoding="utf-16"?><TableLayoutSettings><Controls><Control Name="splitContainer1" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /><Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /></Controls><Columns Styles="Percent,100" /><Rows Styles="Percent,100,Absolute,30,Absolute,20" /></TableLayoutSettings> - - - MainH.Panel2 - - - System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - MainH - - - 1 - - - 1008, 461 - - - 360 - - - 68 - - - MainH - - - System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 3 - Up @@ -2146,24 +2761,9 @@ 17, 17 - - 714, 17 + + 445, 17 - - 102, 22 - - - Reset - - - 103, 26 - - - contextMenuStripDockContainer - - - System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - True @@ -2266,16 +2866,10 @@ 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.4712.38843, Culture=neutral, PublicKeyToken=null + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4714.36626, 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 822e746803..0bbe2662ce 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs @@ -1038,7 +1038,7 @@ namespace ArdupilotMega.GCSViews // comPort.sendPacket(oldgps); - comPort.sendPacket(new MAVLink.mavlink_vfr_hud_t() { airspeed = (float)sitldata.airspeed } ); + //comPort.sendPacket(new MAVLink.mavlink_vfr_hud_t() { airspeed = (float)sitldata.airspeed } ); MAVLink.mavlink_raw_pressure_t pres = new MAVLink.mavlink_raw_pressure_t(); double calc = (101325 * Math.Pow(1 - 2.25577 * Math.Pow(10, -5) * sitldata.altitude, 5.25588)); // updated from valid gps diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index b93f5d8fc3..9642c99476 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -249,6 +249,8 @@ namespace ArdupilotMega } } + ChangeUnits(); + try { FlightData = new GCSViews.FlightData(); @@ -275,8 +277,6 @@ namespace ArdupilotMega if (MainV2.config["CHK_GDIPlus"] != null) GCSViews.FlightData.myhud.UseOpenGL = !bool.Parse(MainV2.config["CHK_GDIPlus"].ToString()); - ChangeUnits(); - try { if (config["MainLocX"] != null && config["MainLocY"] != null) @@ -2258,12 +2258,19 @@ namespace ArdupilotMega { case Common.distances.Meters: MainV2.cs.multiplierdist = 1; + MainV2.cs.DistanceUnit = "Meters"; break; case Common.distances.Feet: MainV2.cs.multiplierdist = 3.2808399f; + MainV2.cs.DistanceUnit = "Feet"; break; } } + else + { + MainV2.cs.multiplierdist = 1; + MainV2.cs.DistanceUnit = "Meters"; + } // speed if (MainV2.config["speedunits"] != null) @@ -2272,21 +2279,31 @@ namespace ArdupilotMega { case Common.speeds.ms: MainV2.cs.multiplierspeed = 1; + MainV2.cs.SpeedUnit = "m/s"; break; case Common.speeds.fps: MainV2.cs.multiplierdist = 3.2808399f; + MainV2.cs.SpeedUnit = "fps"; break; case Common.speeds.kph: MainV2.cs.multiplierspeed = 3.6f; + MainV2.cs.SpeedUnit = "kph"; break; case Common.speeds.mph: MainV2.cs.multiplierspeed = 2.23693629f; + MainV2.cs.SpeedUnit = "mph"; break; case Common.speeds.knots: MainV2.cs.multiplierspeed = 1.94384449f; + MainV2.cs.SpeedUnit = "knots"; break; } } + else + { + MainV2.cs.multiplierspeed = 1; + MainV2.cs.SpeedUnit = "m/s"; + } } catch { } @@ -2337,10 +2354,9 @@ namespace ArdupilotMega { this.SuspendLayout(); panel1.Location = new Point(0,0); - panel1.Visible = true; panel1.Width = menu.Width; panel1.BringToFront(); - + panel1.Visible = true; this.ResumeLayout(); } } diff --git a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs index 87d2f7c21a..6b53529092 100644 --- a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs +++ b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs @@ -1073,6 +1073,9 @@ namespace ArdupilotMega { retrys = 1; timeout = 25000; + } else if (actionid == MAV_CMD.PREFLIGHT_REBOOT_SHUTDOWN) { + generatePacket(MAVLINK_MSG_ID_COMMAND_LONG, req); + return true; } while (true) diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs index beee2dc000..854d08ce99 100644 --- a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs +++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs @@ -1289,19 +1289,20 @@ namespace ArdupilotMega foreach (string logfile in openFileDialog1.FileNames) { - - MAVLink mine = new MAVLink(); try { - mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read)); - } - catch (Exception ex) { log.Debug(ex.ToString()); CustomMessageBox.Show("Log Can not be opened. Are you still connected?"); return; } + MAVLink mine = new MAVLink(); + try + { + mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read)); + } + catch (Exception ex) { log.Debug(ex.ToString()); CustomMessageBox.Show("Log Can not be opened. Are you still connected?"); return; } - mine.logreadmode = true; + mine.logreadmode = true; - mine.packets.Initialize(); // clear + mine.packets.Initialize(); // clear - StreamWriter sw = new StreamWriter(Path.GetDirectoryName(logfile) + Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(logfile) + ".param"); + StreamWriter sw = new StreamWriter(Path.GetDirectoryName(logfile) + Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(logfile) + ".param"); // bar moves to 100 % in this step progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f / 1.0f); @@ -1316,15 +1317,17 @@ namespace ArdupilotMega sw.WriteLine(item + "\t" + mine.param[item]); } - sw.Close(); + sw.Close(); - progressBar1.Value = 100; + progressBar1.Value = 100; - mine.logreadmode = false; - mine.logplaybackfile.Close(); - mine.logplaybackfile = null; + mine.logreadmode = false; + mine.logplaybackfile.Close(); + mine.logplaybackfile = null; - CustomMessageBox.Show("File Saved with log file"); + CustomMessageBox.Show("File Saved with log file"); + } + catch { CustomMessageBox.Show("Error Extracting params"); } } } } diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs index e11118e119..530a0154d7 100644 --- a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs +++ b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs @@ -2,14 +2,14 @@ - + - - + + @@ -31,7 +31,7 @@ - + @@ -107,11 +107,11 @@ - + - + @@ -122,20 +122,20 @@ - + - + - + @@ -149,7 +149,7 @@ - + @@ -161,13 +161,13 @@ - + - + @@ -178,7 +178,7 @@ - + @@ -189,36 +189,36 @@ - + - + - + - + - + - + @@ -227,31 +227,31 @@ - + - + - + - + - + diff --git a/Tools/ArdupilotMegaPlanner/Program.cs b/Tools/ArdupilotMegaPlanner/Program.cs index 4de708a3f5..3f73dc8c18 100644 --- a/Tools/ArdupilotMegaPlanner/Program.cs +++ b/Tools/ArdupilotMegaPlanner/Program.cs @@ -22,6 +22,8 @@ namespace ArdupilotMega static void Main() { + 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"); + Application.EnableVisualStyles(); XmlConfigurator.Configure(); log.Info("******************* Logging Configured *******************"); @@ -131,14 +133,10 @@ 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()); + Console.WriteLine("\nPress any key to exit!"); Console.ReadLine(); } } diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index 424f079ee9..a8fba1786a 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.22")] +[assembly: AssemblyFileVersion("1.2.23")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs b/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs index 53bc1a135b..327e1f8cf3 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/Resources.Designer.cs @@ -1,7 +1,7 @@ //------------------------------------------------------------------------------ // // This code was generated by a tool. -// Runtime Version:4.0.30319.269 +// Runtime Version:4.0.30319.296 // // Changes to this file may cause incorrect behavior and will be lost if // the code is regenerated. @@ -123,6 +123,13 @@ namespace ArdupilotMega.Properties { } } + public static System.Drawing.Bitmap BR_APMPWRDEAN_2 { + get { + object obj = ResourceManager.GetObject("BR-APMPWRDEAN-2", resourceCulture); + return ((System.Drawing.Bitmap)(obj)); + } + } + public static System.Drawing.Bitmap cameraGimalPitch1 { get { object obj = ResourceManager.GetObject("cameraGimalPitch1", resourceCulture); diff --git a/Tools/ArdupilotMegaPlanner/Properties/Resources.resx b/Tools/ArdupilotMegaPlanner/Properties/Resources.resx index b7c705f4dc..256420e1bd 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/Resources.resx +++ b/Tools/ArdupilotMegaPlanner/Properties/Resources.resx @@ -118,71 +118,137 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - ..\Resources\down.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\up.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\bg.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\configuration.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\data.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\firmware.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\planner.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\simulation.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\connect.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\disconnect.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\help.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\terminal.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_airframes_001.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - ..\Resources\APM_airframes_002.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - ..\Resources\APM_airframes-07.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - ..\Resources\APM_airframes-08.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + ..\Resources\new frames-06.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - ..\Resources\frames-03.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + ..\Resources\09028-01.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\iconWarning48.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a ..\Resources\frames-04.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - ..\Resources\frames-05.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + ..\Resources\MAVParam.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252 - - ..\Resources\frames-06.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + ..\Resources\terminal.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\car.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\new frames-12.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\firmware.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\new frames-11.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\BR-0004-03-2.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\help.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\new frames-13.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\y6.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 + + + ..\Resources\data.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\AC-0004-11-2.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\new frames-10.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\iconWarning32.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\quad2.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\BR-HMC5883-01-2.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\APM_airframes_002.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\cameraGimalPitch1.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\simulation.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 + + + ..\Resources\frames_plus.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\up.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\connect.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\planetracker.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\new frames-05.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\octox.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a ..\Resources\frames-07.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - ..\Resources\planetracker.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + ..\Resources\disconnect.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\planner.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\configuration.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\frames-03.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\frames-05.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\down.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\BR-0016-01-3T.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\frames-06.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + + ..\Resources\cameraGimalRoll1.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a @@ -1180,80 +1246,17 @@ an+FN5rNTSpY1divRTiUek6K2tXTNqq8zWHT/53G/1AVtv8fjhuF2iv2lz4AAAAASUVORK5CYII= - - ..\Resources\BR-0004-03-2.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + ..\Resources\APM_airframes-08.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - ..\Resources\09028-01.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\BR-HMC5883-01-2.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\AC-0004-11-2.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\quad2.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\BR-0016-01-3T.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\new frames-10.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\new frames-13.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\new frames-11.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\new frames-12.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\new frames-05.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\new frames-06.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\iconWarning32.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\iconWarning48.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\y6.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\MAVParam.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252 - - - ..\Resources\octox.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\car.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\cameraGimalPitch1.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\cameraGimalRoll1.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a - - - ..\Resources\frames_plus.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a + + ..\Resources\bg.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a ..\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 + + ..\Resources\BR-APMPWRDEAN-2.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Radio/Uploader.cs b/Tools/ArdupilotMegaPlanner/Radio/Uploader.cs index 68218a053b..554c2485fd 100644 --- a/Tools/ArdupilotMegaPlanner/Radio/Uploader.cs +++ b/Tools/ArdupilotMegaPlanner/Radio/Uploader.cs @@ -1,5 +1,5 @@ using System; -using System.IO.Ports; +using ArdupilotMega.Comms; using System.Collections.Generic; namespace uploader diff --git a/Tools/ArdupilotMegaPlanner/SerialOutput.cs b/Tools/ArdupilotMegaPlanner/SerialOutput.cs index 95f9254c32..206f4fda79 100644 --- a/Tools/ArdupilotMegaPlanner/SerialOutput.cs +++ b/Tools/ArdupilotMegaPlanner/SerialOutput.cs @@ -6,7 +6,7 @@ using System.Drawing; using System.Linq; using System.Text; using System.Windows.Forms; -using System.IO.Ports; +using ArdupilotMega.Comms; namespace ArdupilotMega { diff --git a/Tools/ArdupilotMegaPlanner/SerialOutput2.cs b/Tools/ArdupilotMegaPlanner/SerialOutput2.cs index 47f31b44fa..708cb514bb 100644 --- a/Tools/ArdupilotMegaPlanner/SerialOutput2.cs +++ b/Tools/ArdupilotMegaPlanner/SerialOutput2.cs @@ -6,7 +6,7 @@ using System.Drawing; using System.Linq; using System.Text; using System.Windows.Forms; -using System.IO.Ports; +using ArdupilotMega.Comms; namespace ArdupilotMega { diff --git a/Tools/ArdupilotMegaPlanner/Splash.Designer.cs b/Tools/ArdupilotMegaPlanner/Splash.Designer.cs index 6b411628d6..b885ee81d2 100644 --- a/Tools/ArdupilotMegaPlanner/Splash.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Splash.Designer.cs @@ -74,7 +74,7 @@ this.MinimumSize = new System.Drawing.Size(600, 375); this.Name = "Splash"; this.StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen; - this.Text = "APM Planner"; + this.Text = "Mission Planner"; this.TopMost = true; this.ResumeLayout(false); this.PerformLayout();