diff --git a/Tools/ArdupilotMegaPlanner/3DRRadio/ChangeLog.txt b/Tools/ArdupilotMegaPlanner/3DRRadio/ChangeLog.txt
index 5520a2a8ea..78e539edb7 100644
--- a/Tools/ArdupilotMegaPlanner/3DRRadio/ChangeLog.txt
+++ b/Tools/ArdupilotMegaPlanner/3DRRadio/ChangeLog.txt
@@ -1,4 +1,5 @@
-0.9 - added rfd900a
+1.0 - added rf freeq for 868
+0.9 - added rfd900a
0.8 - fix settings saving.
0.7 - fix typos - log rssi screen to log as well
0.6 - add terminal logging to file, fix remote radio config
diff --git a/Tools/ArdupilotMegaPlanner/3DRRadio/Config.resx b/Tools/ArdupilotMegaPlanner/3DRRadio/Config.resx
index 253ddcc778..abc588ecd0 100644
--- a/Tools/ArdupilotMegaPlanner/3DRRadio/Config.resx
+++ b/Tools/ArdupilotMegaPlanner/3DRRadio/Config.resx
@@ -1588,7 +1588,7 @@
- 3DRRadio Config 0.9
+ 3DRRadio Config 1.0
settingsToolStripMenuItem
diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
index 3f7ec918df..566ca8a197 100644
--- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
+++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
@@ -198,7 +198,7 @@ namespace ArdupilotMega.Antenna
try
{
// 10 hz - position updates default to 3 hz on the stream rate
- tracker.PanAndTilt(MainV2.cs.AZToMAV, MainV2.cs.ELToMAV);
+ tracker.PanAndTilt(MainV2.comPort.MAV.cs.AZToMAV, MainV2.comPort.MAV.cs.ELToMAV);
System.Threading.Thread.Sleep(100);
}
catch { }
@@ -262,7 +262,7 @@ namespace ArdupilotMega.Antenna
void tm1_Tick(object item)
{
- float snr = MainV2.cs.localsnrdb;
+ float snr = MainV2.comPort.MAV.cs.localsnrdb;
float best = snr;
float tilt = 0;
@@ -316,13 +316,13 @@ namespace ArdupilotMega.Antenna
System.Threading.Thread.Sleep(2000);
- Console.WriteLine("Angle " + n + " snr " + MainV2.cs.localsnrdb);
+ Console.WriteLine("Angle " + n + " snr " + MainV2.comPort.MAV.cs.localsnrdb);
- if (MainV2.cs.localsnrdb > lastsnr)
+ if (MainV2.comPort.MAV.cs.localsnrdb > lastsnr)
{
best = n;
- lastsnr = MainV2.cs.localsnrdb;
+ lastsnr = MainV2.comPort.MAV.cs.localsnrdb;
}
}
diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
index 2d343243d8..0fa7c14e76 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
@@ -292,6 +292,12 @@
ConnectionStats.cs
+
+ Component
+
+
+ FlashMessage.cs
+
UserControl
@@ -412,6 +418,12 @@
ConfigAteryxSensors.cs
+
+ UserControl
+
+
+ ConfigSignalization.cs
+
@@ -730,6 +742,9 @@
ConnectionStats.cs
+
+ FlashMessage.cs
+
HSI.cs
@@ -844,6 +859,9 @@
ConfigRawParams.cs
+
+ ConfigSignalization.cs
+
ConfigTradHeli.cs
@@ -1203,6 +1221,7 @@
Help.cs
+ Designer
Simulation.cs
@@ -1343,6 +1362,7 @@
Help.cs
+ Designer
Simulation.cs
@@ -1425,8 +1445,6 @@
Always
-
-
Always
diff --git a/Tools/ArdupilotMegaPlanner/ChangeLog.txt b/Tools/ArdupilotMegaPlanner/ChangeLog.txt
index baeac2d157..2d671710e9 100644
--- a/Tools/ArdupilotMegaPlanner/ChangeLog.txt
+++ b/Tools/ArdupilotMegaPlanner/ChangeLog.txt
@@ -1,4 +1,34 @@
-* Mission Planner 1.2.22
+* Mission Planner 1.2.26
+move mavlink structure/currentstate around for future mods
+update old firmware git hashs
+mod some error descriptions
+AP_mount camera trigger mod
+modify raw param display with units/range/desc
+add radio support for 868mhz
+update ch7 options
+updated dataflashlog format
+small df log parser mod for bad gps loc
+renable menu to always dock. right click for autohide
+
+* Mission Planner 1.2.25
+fix scaling problem on arducopter config tab. when linking is enabled
+
+* Mission Planner 1.2.24
+failsafe: hide element not needed
+ap_limits back - beta
+add new accel setup - beta
+fix planner config screen exception
+fix quickview desc/units if never been configured
+
+* 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
+
+* Mission Planner 1.2.22
fix speed modification scale
fix typo on antenna Tracker
setup for ThemeManager.cs
diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs
index 2751b8911c..49f7a41af1 100644
--- a/Tools/ArdupilotMegaPlanner/Common.cs
+++ b/Tools/ArdupilotMegaPlanner/Common.cs
@@ -201,29 +201,29 @@ namespace ArdupilotMega
double width = (MainMap.Manager.GetDistance(MainMap.FromLocalToLatLng(0, 0), MainMap.FromLocalToLatLng(MainMap.Width, 0)) * 1000.0);
double m2pixelwidth = MainMap.Width / width;
- float alpha = ((desired_lead_dist * (float)m2pixelwidth) / MainV2.cs.radius) * rad2deg;
+ float alpha = ((desired_lead_dist * (float)m2pixelwidth) / MainV2.comPort.MAV.cs.radius) * rad2deg;
- if (MainV2.cs.radius < -1)
+ if (MainV2.comPort.MAV.cs.radius < -1)
{
// fixme
- float p1 = (float)Math.Cos((cog) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius;
+ float p1 = (float)Math.Cos((cog) * deg2rad) * MainV2.comPort.MAV.cs.radius + MainV2.comPort.MAV.cs.radius;
- float p2 = (float)Math.Sin((cog) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius;
+ float p2 = (float)Math.Sin((cog) * deg2rad) * MainV2.comPort.MAV.cs.radius + MainV2.comPort.MAV.cs.radius;
- g.DrawArc(new Pen(Color.HotPink, 2), p1, p2, Math.Abs(MainV2.cs.radius) * 2, Math.Abs(MainV2.cs.radius) * 2, cog, alpha);
+ g.DrawArc(new Pen(Color.HotPink, 2), p1, p2, Math.Abs(MainV2.comPort.MAV.cs.radius) * 2, Math.Abs(MainV2.comPort.MAV.cs.radius) * 2, cog, alpha);
}
- else if (MainV2.cs.radius > 1)
+ else if (MainV2.comPort.MAV.cs.radius > 1)
{
// correct
- float p1 = (float)Math.Cos((cog - 180) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius;
+ float p1 = (float)Math.Cos((cog - 180) * deg2rad) * MainV2.comPort.MAV.cs.radius + MainV2.comPort.MAV.cs.radius;
- float p2 = (float)Math.Sin((cog - 180) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius;
+ float p2 = (float)Math.Sin((cog - 180) * deg2rad) * MainV2.comPort.MAV.cs.radius + MainV2.comPort.MAV.cs.radius;
- g.DrawArc(new Pen(Color.HotPink, 2), -p1, -p2, MainV2.cs.radius * 2, MainV2.cs.radius * 2, cog - 180, alpha);
+ g.DrawArc(new Pen(Color.HotPink, 2), -p1, -p2, MainV2.comPort.MAV.cs.radius * 2, MainV2.comPort.MAV.cs.radius * 2, cog - 180, alpha);
}
}
@@ -543,20 +543,18 @@ namespace ArdupilotMega
{
[DisplayText("Do Nothing")]
CH7_DO_NOTHING = 0,
- [DisplayText("Set Hover")]
- CH7_SET_HOVER = 1,
[DisplayText("Flip")]
CH7_FLIP = 2,
[DisplayText("Simple Mode")]
CH7_SIMPLE_MODE = 3,
[DisplayText("Return to Launch")]
CH7_RTL = 4,
- [DisplayText("Automatic Trim")]
+ [DisplayText("Save Trim")]
CH7_AUTO_TRIM = 5,
- [DisplayText("ADC Filter")]
- CH7_ADC_FILTER = 6,
[DisplayText("Save Waypoint")]
- CH7_SAVE_WP = 7
+ CH7_SAVE_WP = 7,
+ [DisplayText("Camera Trigger")]
+ CH7_CAMERA_TRIGGER = 9
}
public enum ac2ch6modes
@@ -699,15 +697,15 @@ namespace ArdupilotMega
public static Type getModes()
{
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
return typeof(apmmodes);
}
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
return typeof(ac2modes);
}
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduRover)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover)
{
return typeof(aprovermodes);
}
@@ -717,17 +715,17 @@ namespace ArdupilotMega
public static List> getModesList()
{
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
var flightModes = EnumTranslator.Translate();
return flightModes.ToList();
}
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
var flightModes = EnumTranslator.Translate();
return flightModes.ToList();
}
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduRover)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover)
{
var flightModes = EnumTranslator.Translate();
return flightModes.ToList();
@@ -897,26 +895,26 @@ namespace ArdupilotMega
public static string speechConversion(string input)
{
- if (MainV2.cs.wpno == 0)
+ if (MainV2.comPort.MAV.cs.wpno == 0)
{
input = input.Replace("{wpn}", "Home");
}
else
{
- input = input.Replace("{wpn}", MainV2.cs.wpno.ToString());
+ input = input.Replace("{wpn}", MainV2.comPort.MAV.cs.wpno.ToString());
}
- input = input.Replace("{asp}", MainV2.cs.airspeed.ToString("0"));
+ input = input.Replace("{asp}", MainV2.comPort.MAV.cs.airspeed.ToString("0"));
- input = input.Replace("{alt}", MainV2.cs.alt.ToString("0"));
+ input = input.Replace("{alt}", MainV2.comPort.MAV.cs.alt.ToString("0"));
- input = input.Replace("{wpa}", MainV2.cs.targetalt.ToString("0"));
+ input = input.Replace("{wpa}", MainV2.comPort.MAV.cs.targetalt.ToString("0"));
- input = input.Replace("{gsp}", MainV2.cs.groundspeed.ToString("0"));
+ input = input.Replace("{gsp}", MainV2.comPort.MAV.cs.groundspeed.ToString("0"));
- input = input.Replace("{mode}", MainV2.cs.mode.ToString());
+ input = input.Replace("{mode}", MainV2.comPort.MAV.cs.mode.ToString());
- input = input.Replace("{batv}", MainV2.cs.battery_voltage.ToString("0.00"));
+ input = input.Replace("{batv}", MainV2.comPort.MAV.cs.battery_voltage.ToString("0.00"));
return input;
}
diff --git a/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs b/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs
index 6bfaa471ab..c50129d717 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs
@@ -35,7 +35,7 @@ namespace ArdupilotMega.Controls
public void PopulateData()
{
// process hashdefines and update display
- foreach (string value in MainV2.comPort.param.Keys)
+ foreach (string value in MainV2.comPort.MAV.param.Keys)
{
if (value == null || value == "") // older ap version have a null param
continue;
@@ -44,7 +44,7 @@ namespace ArdupilotMega.Controls
{
try
{
- float numbervalue = (float)MainV2.comPort.param[value];
+ float numbervalue = (float)MainV2.comPort.MAV.param[value];
MAVLink.modifyParamForDisplay(true, value, ref numbervalue);
diff --git a/Tools/ArdupilotMegaPlanner/Controls/FlashMessage.cs b/Tools/ArdupilotMegaPlanner/Controls/FlashMessage.cs
new file mode 100644
index 0000000000..f685e389f3
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Controls/FlashMessage.cs
@@ -0,0 +1,142 @@
+using System;
+using System.ComponentModel;
+using System.Drawing;
+using System.Text;
+using System.Windows.Forms;
+using System.Collections;
+
+namespace ArdupilotMega.Controls
+{
+ public partial class FlashMessage : Label
+ {
+ private const int fadeInterval = 20; //time in ms between "frames" of animation
+ private const int fadeDuration = 200; //overall animation duration in ms in one direction
+ private const int desiredHeight = 20; //desired height to animate to
+ private const int inOutDelay = 800 / fadeInterval; //number in ms between in and out
+ private const float fadeStepValue = desiredHeight * (float)fadeInterval / (float)fadeDuration;
+ private int inOutDelayCounter;
+ private int direction;
+ private int heightVisible;
+ private bool disposeOnComplete;
+ private Timer fadeTimer;
+ private bool inOut;
+ private Queue messages = new Queue();
+
+ public FlashMessage()
+ {
+ Visible = false;
+
+ Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Left)
+ | System.Windows.Forms.AnchorStyles.Right)));
+ Font = new System.Drawing.Font("Microsoft Sans Serif", 9.25F, System.Drawing.FontStyle.Bold, System.Drawing.GraphicsUnit.Point, ((byte)(238)));
+ Location = new Point(0, 0);
+ TextAlign = System.Drawing.ContentAlignment.MiddleCenter;
+
+ fadeTimer = new Timer();
+ fadeTimer.Interval = fadeInterval;
+ fadeTimer.Tick += new EventHandler(fadeTimer_Tick);
+ }
+
+ public void FadeInOut(string msg, bool success)
+ {
+ if (Visible)
+ {
+ messages.Enqueue(new { msg = msg, success = success });
+ }
+ else
+ {
+ if (this.Parent != null) Width = this.Parent.ClientSize.Width;
+ BringToFront();
+ direction = 1;
+ inOut = true;
+ inOutDelayCounter = inOutDelay;
+ heightVisible = Height = 0;
+ Text = msg;
+ BackColor = success ? Color.YellowGreen : Color.Coral;
+ }
+ Visible = true;
+ fadeTimer.Enabled = true;
+ }
+
+ //public void FadeIn(string msg, bool success)
+ //{
+ // if (this.Parent != null) Width = this.Parent.ClientSize.Width;
+ // BringToFront();
+ // direction = 1;
+ // inOut = false;
+ // heightVisible = Height = 0;
+ // if (Visible)
+ // {
+ // messages.Enqueue(msg);
+ // }
+ // else
+ // {
+ // Text = msg;
+ // }
+ // BackColor = success ? Color.YellowGreen : Color.Coral;
+ // Visible = true;
+ // fadeTimer.Enabled = true;
+ //}
+
+ private void FadeOut(bool disposeOnComplete = false)
+ {
+ if (this.Parent != null) Width = this.Parent.ClientSize.Width;
+ BringToFront();
+ direction = -1;
+ inOut = false;
+ heightVisible = Height = desiredHeight;
+ this.disposeOnComplete = disposeOnComplete;
+ fadeTimer.Enabled = true;
+ }
+
+ private void fadeTimer_Tick(object sender, EventArgs e)
+ {
+ bool done = false;
+ heightVisible += (int)Math.Round(direction * fadeStepValue);
+ if (heightVisible < 0) { done = true; heightVisible = 0; }
+ if (heightVisible > desiredHeight) { done = true; heightVisible = desiredHeight; }
+ Height = heightVisible;
+ if (done)
+ {
+ if (inOut)
+ {
+ if (--inOutDelayCounter == 0)
+ {
+ FadeOut(disposeOnComplete);
+ }
+ }
+ else
+ {
+ if (messages.Count > 0)
+ {
+ Object o = messages.Dequeue();
+ Text = (string)o.GetType().GetProperty("msg").GetValue(o, null);
+ bool success = (bool)o.GetType().GetProperty("success").GetValue(o, null);
+ BackColor = success ? Color.YellowGreen : Color.Coral;
+
+ direction = 1;
+ inOut = true;
+ inOutDelayCounter = inOutDelay;
+ heightVisible = Height = 0;
+
+ //Text = (messages.Dequeue()).msg;
+ }
+ else
+ {
+ fadeTimer.Enabled = false;
+ Visible = false;
+ if (direction == -1) //hide after fadeOut
+ {
+ if (disposeOnComplete) this.Dispose();
+ }
+ }
+ }
+ }
+ else
+ {
+ //this.Height = heightVisible;
+ //this.Invalidate();
+ }
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/Controls/FlashMessage.designer.cs b/Tools/ArdupilotMegaPlanner/Controls/FlashMessage.designer.cs
new file mode 100644
index 0000000000..e13f1af57f
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Controls/FlashMessage.designer.cs
@@ -0,0 +1,46 @@
+using System.Windows.Forms;
+using System.Drawing;
+namespace ArdupilotMega.Controls
+{
+ partial class FlashMessage
+ {
+ public AutoScaleMode AutoScaleMode = AutoScaleMode.Font;
+
+ ///
+ /// Required designer variable.
+ ///
+ private System.ComponentModel.IContainer components = null;
+
+ ///
+ /// Clean up any resources being used.
+ ///
+ /// true if managed resources should be disposed; otherwise, false.
+ protected override void Dispose(bool disposing)
+ {
+ if (disposing && (components != null))
+ {
+ components.Dispose();
+ }
+ base.Dispose(disposing);
+ }
+
+ #region Component Designer generated code
+
+ ///
+ /// Required method for Designer support - do not modify
+ /// the contents of this method with the code editor.
+ ///
+ private void InitializeComponent()
+ {
+ this.SuspendLayout();
+ //
+ // FlashMessage
+ //
+ this.BackColor = System.Drawing.Color.Coral;
+ this.Name = "FM_info";
+ this.ResumeLayout(false);
+ }
+
+ #endregion
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/Controls/FlashMessage.resx b/Tools/ArdupilotMegaPlanner/Controls/FlashMessage.resx
new file mode 100644
index 0000000000..73afb877bd
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Controls/FlashMessage.resx
@@ -0,0 +1,123 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ False
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Controls/HUD.cs b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs
index be21aa39d6..44e027d4e2 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/HUD.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs
@@ -169,7 +169,7 @@ namespace ArdupilotMega.Controls
//public float FontSize;
public string Header;
public System.Reflection.PropertyInfo Item;
- public float GetValue { get { return (float)Item.GetValue((object)MainV2.cs, null); } }
+ public float GetValue { get { return (float)Item.GetValue((object)MainV2.comPort.MAV.cs, null); } }
}
public Hashtable CustomItems = new Hashtable();
diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs
index 8c4a8dd464..57fa227972 100644
--- a/Tools/ArdupilotMegaPlanner/CurrentState.cs
+++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs
@@ -151,9 +151,9 @@ namespace ArdupilotMega
return _ch3percent;
try
{
- if (MainV2.comPort.param.ContainsKey("RC3_MIN"))
+ if (MainV2.comPort.MAV.param.ContainsKey("RC3_MIN"))
{
- return (int)((ch3out - float.Parse(MainV2.comPort.param["RC3_MIN"].ToString())) / (float.Parse(MainV2.comPort.param["RC3_MAX"].ToString()) - float.Parse(MainV2.comPort.param["RC3_MIN"].ToString())) * 100);
+ return (int)((ch3out - float.Parse(MainV2.comPort.MAV.param["RC3_MIN"].ToString())) / (float.Parse(MainV2.comPort.MAV.param["RC3_MAX"].ToString()) - float.Parse(MainV2.comPort.MAV.param["RC3_MIN"].ToString())) * 100);
}
else
{
@@ -437,11 +437,11 @@ namespace ArdupilotMega
if (desc.Contains("(dist)"))
{
- desc = desc.Replace("(dist)", "(" + MainV2.cs.DistanceUnit + ")");
+ desc = desc.Replace("(dist)", "(" + MainV2.comPort.MAV.cs.DistanceUnit + ")");
}
else if (desc.Contains("(speed)"))
{
- desc = desc.Replace("(speed)", "(" + MainV2.cs.SpeedUnit + ")");
+ desc = desc.Replace("(speed)", "(" + MainV2.comPort.MAV.cs.SpeedUnit + ")");
}
return desc;
@@ -490,10 +490,10 @@ namespace ArdupilotMega
dowindcalc();
}
- if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text
+ if (mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text
{
- string logdata = DateTime.Now + " " + Encoding.ASCII.GetString(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT], 6, mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT].Length - 6);
+ string logdata = DateTime.Now + " " + Encoding.ASCII.GetString(mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT], 6, mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT].Length - 6);
int ind = logdata.IndexOf('\0');
if (ind != -1)
@@ -509,10 +509,10 @@ namespace ArdupilotMega
}
catch { }
- mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] = null;
+ mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] = null;
}
- byte[] bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED];
+ byte[] bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED];
if (bytearray != null) // hil mavlink 0.9
{
@@ -530,7 +530,7 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] = null;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HIL_CONTROLS];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_HIL_CONTROLS];
if (bytearray != null) // hil mavlink 0.9 and 1.0
{
@@ -544,7 +544,7 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_HIL_CONTROLS] = null;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HWSTATUS];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_HWSTATUS];
if (bytearray != null)
{
@@ -556,7 +556,7 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_HWSTATUS] = null;
}
- bytearray = mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WIND];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_WIND];
if (bytearray != null)
{
var wind = bytearray.ByteArrayToStructure(6);
@@ -572,7 +572,7 @@ namespace ArdupilotMega
#if MAVLINK10
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HEARTBEAT];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_HEARTBEAT];
if (bytearray != null)
{
var hb = bytearray.ByteArrayToStructure(6);
@@ -669,7 +669,7 @@ namespace ArdupilotMega
}
- bytearray = mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS];
+ bytearray = mavinterface.MAV.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS];
if (bytearray != null)
{
var sysstatus = bytearray.ByteArrayToStructure(6);
@@ -684,7 +684,7 @@ namespace ArdupilotMega
}
#else
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SYS_STATUS];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_SYS_STATUS];
if (bytearray != null)
{
@@ -802,7 +802,7 @@ namespace ArdupilotMega
}
#endif
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_PRESSURE];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_SCALED_PRESSURE];
if (bytearray != null)
{
var pres = bytearray.ByteArrayToStructure(6);
@@ -810,7 +810,7 @@ namespace ArdupilotMega
press_temp = pres.temperature;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SENSOR_OFFSETS];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_SENSOR_OFFSETS];
if (bytearray != null)
{
var sensofs = bytearray.ByteArrayToStructure(6);
@@ -833,7 +833,7 @@ namespace ArdupilotMega
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE];
if (bytearray != null)
{
@@ -847,7 +847,7 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] = null;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW_INT];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW_INT];
if (bytearray != null)
{
var gps = bytearray.ByteArrayToStructure(6);
@@ -872,14 +872,14 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] = null;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS];
if (bytearray != null)
{
var gps = bytearray.ByteArrayToStructure(6);
satcount = gps.satellites_visible;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RADIO];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_RADIO];
if (bytearray != null)
{
var radio = bytearray.ByteArrayToStructure(6);
@@ -892,7 +892,7 @@ namespace ArdupilotMega
fixedp = radio.fixedp;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT];
if (bytearray != null)
{
var loc = bytearray.ByteArrayToStructure(6);
@@ -912,7 +912,7 @@ namespace ArdupilotMega
}
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MISSION_CURRENT];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_MISSION_CURRENT];
if (bytearray != null)
{
var wpcur = bytearray.ByteArrayToStructure(6);
@@ -929,7 +929,7 @@ namespace ArdupilotMega
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] = null;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT];
if (bytearray != null)
{
@@ -947,7 +947,7 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] = null;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW];
if (bytearray != null)
{
var rcin = bytearray.ByteArrayToStructure(6);
@@ -967,7 +967,7 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW] = null;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW];
if (bytearray != null)
{
var servoout = bytearray.ByteArrayToStructure(6);
@@ -985,7 +985,7 @@ namespace ArdupilotMega
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU];
if (bytearray != null)
{
var imu = bytearray.ByteArrayToStructure(6);
@@ -1005,7 +1005,7 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU];
if (bytearray != null)
{
var imu = bytearray.ByteArrayToStructure(6);
@@ -1022,7 +1022,7 @@ namespace ArdupilotMega
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD];
if (bytearray != null)
{
var vfr = bytearray.ByteArrayToStructure(6);
@@ -1051,7 +1051,7 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] = null;
}
- bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO];
+ bytearray = mavinterface.MAV.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO];
if (bytearray != null)
{
var mem = bytearray.ByteArrayToStructure(6);
diff --git a/Tools/ArdupilotMegaPlanner/ElevationProfile.cs b/Tools/ArdupilotMegaPlanner/ElevationProfile.cs
index ca7d702ff1..c41c1d877e 100644
--- a/Tools/ArdupilotMegaPlanner/ElevationProfile.cs
+++ b/Tools/ArdupilotMegaPlanner/ElevationProfile.cs
@@ -43,7 +43,7 @@ namespace ArdupilotMega
lastloc = loc;
}
- this.homealt = homealt / MainV2.cs.multiplierdist;
+ this.homealt = homealt / MainV2.comPort.MAV.cs.multiplierdist;
Form frm = Common.LoadingBox("Loading", "Downloading Google Earth Data");
@@ -82,7 +82,7 @@ namespace ArdupilotMega
a += planloc.GetDistance(lastloc);
}
- list1.Add(a, planloc.Alt / MainV2.cs.multiplierdist, 0, planloc.Tag); // homealt
+ list1.Add(a, planloc.Alt / MainV2.comPort.MAV.cs.multiplierdist, 0, planloc.Tag); // homealt
lastloc = planloc;
count++;
diff --git a/Tools/ArdupilotMegaPlanner/FollowMe.cs b/Tools/ArdupilotMegaPlanner/FollowMe.cs
index 804e3a9be4..eb0738fef1 100644
--- a/Tools/ArdupilotMegaPlanner/FollowMe.cs
+++ b/Tools/ArdupilotMegaPlanner/FollowMe.cs
@@ -57,18 +57,18 @@ namespace ArdupilotMega
string alt = "100";
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
- alt = (10 * MainV2.cs.multiplierdist).ToString("0");
+ alt = (10 * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
}
else
{
- alt = (100 * MainV2.cs.multiplierdist).ToString("0");
+ alt = (100 * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
}
if (DialogResult.Cancel == Common.InputBox("Enter Alt", "Enter Alt (relative to home alt)", ref alt))
return;
- intalt = (int)(100 * MainV2.cs.multiplierdist);
+ intalt = (int)(100 * MainV2.comPort.MAV.cs.multiplierdist);
if (!int.TryParse(alt, out intalt))
{
CustomMessageBox.Show("Bad Alt");
@@ -97,7 +97,7 @@ namespace ArdupilotMega
{
string line = comPort.ReadLine();
- //string line = string.Format("$GP{0},{1:HHmmss},{2},{3},{4},{5},{6},{7},{8},{9},{10},{11},{12},{13},", "GGA", DateTime.Now.ToUniversalTime(), Math.Abs(lat * 100), MainV2.cs.lat < 0 ? "S" : "N", Math.Abs(lng * 100), MainV2.cs.lng < 0 ? "W" : "E", MainV2.cs.gpsstatus, MainV2.cs.satcount, MainV2.cs.gpshdop, MainV2.cs.alt, "M", 0, "M", "");
+ //string line = string.Format("$GP{0},{1:HHmmss},{2},{3},{4},{5},{6},{7},{8},{9},{10},{11},{12},{13},", "GGA", DateTime.Now.ToUniversalTime(), Math.Abs(lat * 100), MainV2.comPort.MAV.cs.lat < 0 ? "S" : "N", Math.Abs(lng * 100), MainV2.comPort.MAV.cs.lng < 0 ? "W" : "E", MainV2.comPort.MAV.cs.gpsstatus, MainV2.comPort.MAV.cs.satcount, MainV2.comPort.MAV.cs.gpshdop, MainV2.comPort.MAV.cs.alt, "M", 0, "M", "");
if (line.StartsWith("$GPGGA")) //
{
string[] items = line.Trim().Split(',','*');
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.cs
index 27d7de5228..7277612941 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.cs
@@ -41,7 +41,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
private void LIM_ENABLED_CheckedChanged(object sender, EventArgs e)
{
- if (!MainV2.comPort.param.ContainsKey("LIM_ENABLED"))
+ if (!MainV2.comPort.MAV.param.ContainsKey("LIM_ENABLED"))
{
CustomMessageBox.Show("This feature is not enabled in your firmware.");
return;
@@ -80,7 +80,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
void PopulateData()
{
- Hashtable copy = new Hashtable(MainV2.comPort.param);
+ Hashtable copy = new Hashtable(MainV2.comPort.MAV.param);
foreach (string key in copy.Keys)
{
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs
index 364e64e569..28bed0563f 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs
@@ -29,7 +29,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
}
else
{
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
this.Enabled = true;
}
@@ -42,8 +42,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
startup = true;
- if (MainV2.comPort.param["MANUAL_LEVEL"] != null)
- CHK_manuallevel.Checked = MainV2.comPort.param["MANUAL_LEVEL"].ToString() == "1" ? true : false;
+ if (MainV2.comPort.MAV.param["MANUAL_LEVEL"] != null)
+ CHK_manuallevel.Checked = MainV2.comPort.MAV.param["MANUAL_LEVEL"].ToString() == "1" ? true : false;
startup = false;
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs
index af2a193c96..656840a9fe 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs
@@ -79,13 +79,13 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
public void Activate()
{
- if (!MainV2.comPort.param.ContainsKey("FRAME"))
+ if (!MainV2.comPort.MAV.param.ContainsKey("FRAME"))
{
this.Enabled = false;
return;
}
- if ((float)MainV2.comPort.param["FRAME"] == 0)
+ if ((float)MainV2.comPort.MAV.param["FRAME"] == 0)
{
this.radioButton_Plus.Checked = true;
pictureBoxX.Opacity = DisabledOpacity;
@@ -147,13 +147,13 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
ConfigAccelerometerCalibrationQuad local = (ConfigAccelerometerCalibrationQuad)item;
- while (!(MainV2.cs.message.Contains("Calibration successful") || MainV2.cs.message.Contains("Calibration failed")))
+ while (!(MainV2.comPort.MAV.cs.message.Contains("Calibration successful") || MainV2.comPort.MAV.cs.message.Contains("Calibration failed")))
{
System.Threading.Thread.Sleep(10);
// read the message
MainV2.comPort.readPacket();
// update cs with the message
- MainV2.cs.UpdateCurrentSettings(null);
+ MainV2.comPort.MAV.cs.UpdateCurrentSettings(null);
// update user display
local.UpdateUserMessage();
}
@@ -170,7 +170,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
this.Invoke((MethodInvoker)delegate()
{
- lbl_Accel_user.Text = MainV2.cs.message;
+ lbl_Accel_user.Text = MainV2.comPort.MAV.cs.message;
});
}
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
index 86d030a5c3..6d4714bbea 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
@@ -30,12 +30,9 @@
{
this.components = new System.ComponentModel.Container();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigArducopter));
- this.myLabel3 = new ArdupilotMega.Controls.MyLabel();
this.TUNE_LOW = new System.Windows.Forms.NumericUpDown();
this.TUNE_HIGH = new System.Windows.Forms.NumericUpDown();
- this.myLabel2 = new ArdupilotMega.Controls.MyLabel();
this.TUNE = new System.Windows.Forms.ComboBox();
- this.myLabel1 = new ArdupilotMega.Controls.MyLabel();
this.CH7_OPT = new System.Windows.Forms.ComboBox();
this.groupBox5 = new System.Windows.Forms.GroupBox();
this.THR_RATE_D = new System.Windows.Forms.NumericUpDown();
@@ -126,8 +123,6 @@
this.RATE_RLL_P = new System.Windows.Forms.NumericUpDown();
this.label91 = new System.Windows.Forms.Label();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
- this.BUT_writePIDS = new ArdupilotMega.Controls.MyButton();
- this.BUT_rerequestparams = new ArdupilotMega.Controls.MyButton();
this.groupBox1 = new System.Windows.Forms.GroupBox();
this.LOITER_LAT_D = new System.Windows.Forms.NumericUpDown();
this.label1 = new System.Windows.Forms.Label();
@@ -137,6 +132,11 @@
this.label3 = new System.Windows.Forms.Label();
this.LOITER_LAT_P = new System.Windows.Forms.NumericUpDown();
this.label4 = new System.Windows.Forms.Label();
+ this.BUT_rerequestparams = new ArdupilotMega.Controls.MyButton();
+ this.BUT_writePIDS = new ArdupilotMega.Controls.MyButton();
+ this.myLabel3 = new ArdupilotMega.Controls.MyLabel();
+ this.myLabel2 = new ArdupilotMega.Controls.MyLabel();
+ this.myLabel1 = new ArdupilotMega.Controls.MyLabel();
((System.ComponentModel.ISupportInitialize)(this.TUNE_LOW)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.TUNE_HIGH)).BeginInit();
this.groupBox5.SuspendLayout();
@@ -195,12 +195,6 @@
((System.ComponentModel.ISupportInitialize)(this.LOITER_LAT_P)).BeginInit();
this.SuspendLayout();
//
- // myLabel3
- //
- resources.ApplyResources(this.myLabel3, "myLabel3");
- this.myLabel3.Name = "myLabel3";
- this.myLabel3.resize = false;
- //
// TUNE_LOW
//
resources.ApplyResources(this.TUNE_LOW, "TUNE_LOW");
@@ -211,63 +205,19 @@
resources.ApplyResources(this.TUNE_HIGH, "TUNE_HIGH");
this.TUNE_HIGH.Name = "TUNE_HIGH";
//
- // myLabel2
- //
- resources.ApplyResources(this.myLabel2, "myLabel2");
- this.myLabel2.Name = "myLabel2";
- this.myLabel2.resize = false;
- //
// TUNE
//
this.TUNE.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
this.TUNE.DropDownWidth = 150;
this.TUNE.FormattingEnabled = true;
- this.TUNE.Items.AddRange(new object[] {
- resources.GetString("TUNE.Items"),
- resources.GetString("TUNE.Items1"),
- resources.GetString("TUNE.Items2"),
- resources.GetString("TUNE.Items3"),
- resources.GetString("TUNE.Items4"),
- resources.GetString("TUNE.Items5"),
- resources.GetString("TUNE.Items6"),
- resources.GetString("TUNE.Items7"),
- resources.GetString("TUNE.Items8"),
- resources.GetString("TUNE.Items9"),
- resources.GetString("TUNE.Items10"),
- resources.GetString("TUNE.Items11"),
- resources.GetString("TUNE.Items12"),
- resources.GetString("TUNE.Items13"),
- resources.GetString("TUNE.Items14"),
- resources.GetString("TUNE.Items15"),
- resources.GetString("TUNE.Items16"),
- resources.GetString("TUNE.Items17"),
- resources.GetString("TUNE.Items18"),
- resources.GetString("TUNE.Items19"),
- resources.GetString("TUNE.Items20"),
- resources.GetString("TUNE.Items21")});
resources.ApplyResources(this.TUNE, "TUNE");
this.TUNE.Name = "TUNE";
//
- // myLabel1
- //
- resources.ApplyResources(this.myLabel1, "myLabel1");
- this.myLabel1.Name = "myLabel1";
- this.myLabel1.resize = false;
- //
// CH7_OPT
//
this.CH7_OPT.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
this.CH7_OPT.DropDownWidth = 150;
this.CH7_OPT.FormattingEnabled = true;
- this.CH7_OPT.Items.AddRange(new object[] {
- resources.GetString("CH7_OPT.Items"),
- resources.GetString("CH7_OPT.Items1"),
- resources.GetString("CH7_OPT.Items2"),
- resources.GetString("CH7_OPT.Items3"),
- resources.GetString("CH7_OPT.Items4"),
- resources.GetString("CH7_OPT.Items5"),
- resources.GetString("CH7_OPT.Items6"),
- resources.GetString("CH7_OPT.Items7")});
resources.ApplyResources(this.CH7_OPT, "CH7_OPT");
this.CH7_OPT.Name = "CH7_OPT";
//
@@ -812,20 +762,6 @@
this.toolTip1.InitialDelay = 500;
this.toolTip1.ReshowDelay = 100;
//
- // BUT_writePIDS
- //
- resources.ApplyResources(this.BUT_writePIDS, "BUT_writePIDS");
- this.BUT_writePIDS.Name = "BUT_writePIDS";
- this.BUT_writePIDS.UseVisualStyleBackColor = true;
- this.BUT_writePIDS.Click += new System.EventHandler(this.BUT_writePIDS_Click);
- //
- // BUT_rerequestparams
- //
- resources.ApplyResources(this.BUT_rerequestparams, "BUT_rerequestparams");
- this.BUT_rerequestparams.Name = "BUT_rerequestparams";
- this.BUT_rerequestparams.UseVisualStyleBackColor = true;
- this.BUT_rerequestparams.Click += new System.EventHandler(this.BUT_rerequestparams_Click);
- //
// groupBox1
//
this.groupBox1.Controls.Add(this.LOITER_LAT_D);
@@ -880,6 +816,38 @@
resources.ApplyResources(this.label4, "label4");
this.label4.Name = "label4";
//
+ // BUT_rerequestparams
+ //
+ resources.ApplyResources(this.BUT_rerequestparams, "BUT_rerequestparams");
+ this.BUT_rerequestparams.Name = "BUT_rerequestparams";
+ this.BUT_rerequestparams.UseVisualStyleBackColor = true;
+ this.BUT_rerequestparams.Click += new System.EventHandler(this.BUT_rerequestparams_Click);
+ //
+ // BUT_writePIDS
+ //
+ resources.ApplyResources(this.BUT_writePIDS, "BUT_writePIDS");
+ this.BUT_writePIDS.Name = "BUT_writePIDS";
+ this.BUT_writePIDS.UseVisualStyleBackColor = true;
+ this.BUT_writePIDS.Click += new System.EventHandler(this.BUT_writePIDS_Click);
+ //
+ // myLabel3
+ //
+ resources.ApplyResources(this.myLabel3, "myLabel3");
+ this.myLabel3.Name = "myLabel3";
+ this.myLabel3.resize = false;
+ //
+ // myLabel2
+ //
+ resources.ApplyResources(this.myLabel2, "myLabel2");
+ this.myLabel2.Name = "myLabel2";
+ this.myLabel2.resize = false;
+ //
+ // myLabel1
+ //
+ resources.ApplyResources(this.myLabel1, "myLabel1");
+ this.myLabel1.Name = "myLabel1";
+ this.myLabel1.resize = false;
+ //
// ConfigArducopter
//
resources.ApplyResources(this, "$this");
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs
index f59189f21f..d03dc7878b 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs
@@ -43,7 +43,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
}
else
{
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
this.Enabled = true;
}
@@ -163,7 +163,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
// process hashdefines and update display
- foreach (string value in MainV2.comPort.param.Keys)
+ foreach (string value in MainV2.comPort.MAV.param.Keys)
{
if (value == null || value == "")
continue;
@@ -180,7 +180,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (ctl.GetType() == typeof(NumericUpDown))
{
- float numbervalue = (float)MainV2.comPort.param[value];
+ float numbervalue = (float)MainV2.comPort.MAV.param[value];
MAVLink.modifyParamForDisplay(true, value, ref numbervalue);
@@ -231,7 +231,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
ComboBox thisctl = ((ComboBox)ctl);
- thisctl.SelectedValue = (int)(float)MainV2.comPort.param[value];
+ thisctl.SelectedValue = (int)(float)MainV2.comPort.MAV.param[value];
thisctl.Validated += new EventHandler(ComboBox_Validated);
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx
index faddbe520e..873f222bba 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx
@@ -118,37 +118,13 @@
System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
- 364, 321
-
-
- 29, 23
-
-
-
- 42
-
-
- Min
-
-
- myLabel3
-
-
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4666.36788, Culture=neutral, PublicKeyToken=null
-
-
- $this
-
-
- 3
-
399, 324
51, 20
+
41
@@ -185,96 +161,6 @@
5
-
- 364, 296
-
-
- 53, 23
-
-
- 39
-
-
- Ch6 Opt
-
-
- myLabel2
-
-
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4666.36788, Culture=neutral, PublicKeyToken=null
-
-
- $this
-
-
- 6
-
-
- CH6_NONE
-
-
- CH6_STABILIZE_KP
-
-
- CH6_STABILIZE_KI
-
-
- CH6_YAW_KP
-
-
- CH6_RATE_KP
-
-
- CH6_RATE_KI
-
-
- CH6_YAW_RATE_KP
-
-
- CH6_THROTTLE_KP
-
-
- CH6_TOP_BOTTOM_RATIO
-
-
- CH6_RELAY
-
-
- CH6_TRAVERSE_SPEED
-
-
- CH6_NAV_P
-
-
- CH6_LOITER_P
-
-
- CH6_HELI_EXTERNAL_GYRO
-
-
- CH6_THR_HOLD_KP
-
-
- CH6_Z_GAIN
-
-
- CH6_DAMP
-
-
- CH6_OPTFLOW_KP
-
-
- CH6_OPTFLOW_KI
-
-
- CH6_OPTFLOW_KD
-
-
- CH6_NAV_I
-
-
- CH6_RATE_KD
-
423, 296
@@ -296,54 +182,6 @@
7
-
- 364, 348
-
-
- 53, 23
-
-
- 37
-
-
- Ch7 Opt
-
-
- myLabel1
-
-
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4666.36788, Culture=neutral, PublicKeyToken=null
-
-
- $this
-
-
- 8
-
-
- Do Nothing
-
-
-
-
-
-
-
-
- Simple Mode
-
-
- RTL
-
-
-
-
-
-
-
-
- Save WP
-
423, 348
@@ -2487,63 +2325,6 @@
17, 17
-
- NoControl
-
-
- 255, 383
-
-
- 103, 19
-
-
- 70
-
-
- Write Params
-
-
- BUT_writePIDS
-
-
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4666.36788, Culture=neutral, PublicKeyToken=null
-
-
- $this
-
-
- 2
-
-
- NoControl
-
-
- 364, 383
-
-
- 0, 15, 0, 0
-
-
- 103, 19
-
-
- 74
-
-
- Refresh Params
-
-
- BUT_rerequestparams
-
-
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4666.36788, Culture=neutral, PublicKeyToken=null
-
-
- $this
-
-
- 1
-
80, 60
@@ -2760,6 +2541,135 @@
0
+
+ NoControl
+
+
+ 364, 383
+
+
+ 0, 15, 0, 0
+
+
+ 103, 19
+
+
+ 74
+
+
+ Refresh Params
+
+
+ BUT_rerequestparams
+
+
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4724.22562, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 1
+
+
+ NoControl
+
+
+ 255, 383
+
+
+ 103, 19
+
+
+ 70
+
+
+ Write Params
+
+
+ BUT_writePIDS
+
+
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4724.22562, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 2
+
+
+ 364, 321
+
+
+ 29, 23
+
+
+ 42
+
+
+ Min
+
+
+ myLabel3
+
+
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4724.22562, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 3
+
+
+ 364, 296
+
+
+ 53, 23
+
+
+ 39
+
+
+ Ch6 Opt
+
+
+ myLabel2
+
+
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4724.22562, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 6
+
+
+ 364, 348
+
+
+ 53, 23
+
+
+ 37
+
+
+ Ch7 Opt
+
+
+ myLabel1
+
+
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4724.22562, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 8
+
True
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs
index 7698f75998..ec300cb5ea 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs
@@ -32,7 +32,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
}
else
{
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
this.Enabled = true;
}
@@ -153,7 +153,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
disableNumericUpDownControls(this);
// process hashdefines and update display
- foreach (string value in MainV2.comPort.param.Keys)
+ foreach (string value in MainV2.comPort.MAV.param.Keys)
{
if (value == null || value == "")
continue;
@@ -167,7 +167,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (ctl.GetType() == typeof(NumericUpDown))
{
- float numbervalue = (float)MainV2.comPort.param[value];
+ float numbervalue = (float)MainV2.comPort.MAV.param[value];
MAVLink.modifyParamForDisplay(true, value,ref numbervalue);
@@ -214,7 +214,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
ComboBox thisctl = ((ComboBox)ctl);
- thisctl.SelectedIndex = (int)(float)MainV2.comPort.param[value];
+ thisctl.SelectedIndex = (int)(float)MainV2.comPort.MAV.param[value];
thisctl.Validated += new EventHandler(ComboBox_Validated);
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArdurover.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArdurover.cs
index bc92622f02..d75bc5e2bb 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArdurover.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArdurover.cs
@@ -32,7 +32,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
}
else
{
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduRover)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover)
{
this.Enabled = true;
}
@@ -153,7 +153,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
disableNumericUpDownControls(this);
// process hashdefines and update display
- foreach (string value in MainV2.comPort.param.Keys)
+ foreach (string value in MainV2.comPort.MAV.param.Keys)
{
if (value == null || value == "")
continue;
@@ -167,7 +167,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (ctl.GetType() == typeof(NumericUpDown))
{
- float numbervalue = (float)MainV2.comPort.param[value];
+ float numbervalue = (float)MainV2.comPort.MAV.param[value];
MAVLink.modifyParamForDisplay(true, value, ref numbervalue);
@@ -214,7 +214,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
ComboBox thisctl = ((ComboBox)ctl);
- thisctl.SelectedIndex = (int)(float)MainV2.comPort.param[value];
+ thisctl.SelectedIndex = (int)(float)MainV2.comPort.MAV.param[value];
thisctl.Validated += new EventHandler(ComboBox_Validated);
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAteryx.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAteryx.cs
index d4ea5e74c8..235eec62ba 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAteryx.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAteryx.cs
@@ -38,7 +38,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
}
else
{
- if (MainV2.cs.firmware == MainV2.Firmwares.Ateryx)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.Ateryx)
{
this.Enabled = true;
}
@@ -159,7 +159,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
disableNumericUpDownControls(this);
// process hashdefines and update display
- foreach (string value in MainV2.comPort.param.Keys)
+ foreach (string value in MainV2.comPort.MAV.param.Keys)
{
if (value == null || value == "")
continue;
@@ -176,7 +176,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
NumericUpDown thisctl = ((NumericUpDown)ctl);
thisctl.Maximum = 9000;
thisctl.Minimum = -9000;
- thisctl.Value = (decimal)(float)MainV2.comPort.param[value];
+ thisctl.Value = (decimal)(float)MainV2.comPort.MAV.param[value];
thisctl.Increment = (decimal)0.001;
if (thisctl.Name.EndsWith("_P") || thisctl.Name.EndsWith("_I") || thisctl.Name.EndsWith("_D")
|| thisctl.Name.EndsWith("_LOW") || thisctl.Name.EndsWith("_HIGH") || thisctl.Value == 0
@@ -216,7 +216,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
ComboBox thisctl = ((ComboBox)ctl);
- thisctl.SelectedIndex = (int)(float)MainV2.comPort.param[value];
+ thisctl.SelectedIndex = (int)(float)MainV2.comPort.MAV.param[value];
thisctl.Validated += new EventHandler(ComboBox_Validated);
}
@@ -353,7 +353,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
((Button)sender).Enabled = false;
- if ((MainV2.cs.airspeed > 7.0) || (MainV2.cs.groundspeed > 10.0))
+ if ((MainV2.comPort.MAV.cs.airspeed > 7.0) || (MainV2.comPort.MAV.cs.groundspeed > 10.0))
{
MessageBox.Show("Unable - UAV airborne");
((Button)sender).Enabled = true;
@@ -379,7 +379,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (dr == System.Windows.Forms.DialogResult.Yes)
{
- if ((MainV2.cs.airspeed > 7.0) || (MainV2.cs.groundspeed > 7.0))
+ if ((MainV2.comPort.MAV.cs.airspeed > 7.0) || (MainV2.comPort.MAV.cs.groundspeed > 7.0))
{
MessageBox.Show("Unable - UAV airborne");
((Button)sender).Enabled = true;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAteryxSensors.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAteryxSensors.cs
index 37eef9c720..32b4bc41ee 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAteryxSensors.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAteryxSensors.cs
@@ -29,7 +29,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
}
else
{
- if (MainV2.cs.firmware == MainV2.Firmwares.Ateryx)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.Ateryx)
{
this.Enabled = true;
}
@@ -55,7 +55,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
((Button)sender).Enabled = false;
- if ((MainV2.cs.airspeed > 7.0) || (MainV2.cs.groundspeed > 10.0))
+ if ((MainV2.comPort.MAV.cs.airspeed > 7.0) || (MainV2.comPort.MAV.cs.groundspeed > 10.0))
{
MessageBox.Show("Unable - UAV airborne");
((Button)sender).Enabled = true;
@@ -79,7 +79,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
((Button)sender).Enabled = false;
- if ((MainV2.cs.airspeed > 7.0) || (MainV2.cs.groundspeed > 10.0))
+ if ((MainV2.comPort.MAV.cs.airspeed > 7.0) || (MainV2.comPort.MAV.cs.groundspeed > 10.0))
{
MessageBox.Show("Unable - UAV airborne");
((Button)sender).Enabled = true;
@@ -101,7 +101,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
private void timer1_Tick(object sender, EventArgs e)
{
- MainV2.cs.UpdateCurrentSettings(bindingSource1);
+ MainV2.comPort.MAV.cs.UpdateCurrentSettings(bindingSource1);
}
}
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs
index 109590b04b..0d3689db32 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs
@@ -49,7 +49,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["BATT_CAPACITY"] == null)
+ if (MainV2.comPort.MAV.param["BATT_CAPACITY"] == null)
{
CustomMessageBox.Show("Not Available");
}
@@ -66,7 +66,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["BATT_MONITOR"] == null)
+ if (MainV2.comPort.MAV.param["BATT_MONITOR"] == null)
{
CustomMessageBox.Show("Not Available");
}
@@ -117,7 +117,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["INPUT_VOLTS"] == null)
+ if (MainV2.comPort.MAV.param["INPUT_VOLTS"] == null)
{
CustomMessageBox.Show("Not Available");
}
@@ -151,7 +151,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
try
{
- if (MainV2.comPort.param["VOLT_DIVIDER"] == null)
+ if (MainV2.comPort.MAV.param["VOLT_DIVIDER"] == null)
{
CustomMessageBox.Show("Not Available");
}
@@ -173,7 +173,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["VOLT_DIVIDER"] == null)
+ if (MainV2.comPort.MAV.param["VOLT_DIVIDER"] == null)
{
CustomMessageBox.Show("Not Available");
}
@@ -195,7 +195,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["AMP_PER_VOLT"] == null)
+ if (MainV2.comPort.MAV.param["AMP_PER_VOLT"] == null)
{
CustomMessageBox.Show("Not Available");
}
@@ -304,28 +304,28 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
startup = true;
bool not_supported = false;
- if (MainV2.comPort.param["BATT_MONITOR"] != null)
+ if (MainV2.comPort.MAV.param["BATT_MONITOR"] != null)
{
- if (MainV2.comPort.param["BATT_MONITOR"].ToString() != "0.0")
+ if (MainV2.comPort.MAV.param["BATT_MONITOR"].ToString() != "0.0")
{
- CMB_batmontype.SelectedIndex = getIndex(CMB_batmontype, (int)float.Parse(MainV2.comPort.param["BATT_MONITOR"].ToString()));
+ CMB_batmontype.SelectedIndex = getIndex(CMB_batmontype, (int)float.Parse(MainV2.comPort.MAV.param["BATT_MONITOR"].ToString()));
}
}
- if (MainV2.comPort.param["BATT_CAPACITY"] != null)
- TXT_battcapacity.Text = MainV2.comPort.param["BATT_CAPACITY"].ToString();
- if (MainV2.comPort.param["INPUT_VOLTS"] != null)
- TXT_inputvoltage.Text = MainV2.comPort.param["INPUT_VOLTS"].ToString();
+ if (MainV2.comPort.MAV.param["BATT_CAPACITY"] != null)
+ TXT_battcapacity.Text = MainV2.comPort.MAV.param["BATT_CAPACITY"].ToString();
+ if (MainV2.comPort.MAV.param["INPUT_VOLTS"] != null)
+ TXT_inputvoltage.Text = MainV2.comPort.MAV.param["INPUT_VOLTS"].ToString();
else
not_supported = true;
- TXT_voltage.Text = MainV2.cs.battery_voltage.ToString();
+ TXT_voltage.Text = MainV2.comPort.MAV.cs.battery_voltage.ToString();
TXT_measuredvoltage.Text = TXT_voltage.Text;
- if (MainV2.comPort.param["VOLT_DIVIDER"] != null)
- TXT_divider.Text = MainV2.comPort.param["VOLT_DIVIDER"].ToString();
+ if (MainV2.comPort.MAV.param["VOLT_DIVIDER"] != null)
+ TXT_divider.Text = MainV2.comPort.MAV.param["VOLT_DIVIDER"].ToString();
else
not_supported = true;
- if (MainV2.comPort.param["AMP_PER_VOLT"] != null)
- TXT_ampspervolt.Text = MainV2.comPort.param["AMP_PER_VOLT"].ToString();
+ if (MainV2.comPort.MAV.param["AMP_PER_VOLT"] != null)
+ TXT_ampspervolt.Text = MainV2.comPort.MAV.param["AMP_PER_VOLT"].ToString();
else
not_supported = true;
if (not_supported)
@@ -359,11 +359,11 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
CMB_batmonsensortype.SelectedIndex = 0;
}
- if (MainV2.comPort.param["BATT_VOLT_PIN"] != null)
+ if (MainV2.comPort.MAV.param["BATT_VOLT_PIN"] != null)
{
CMB_apmversion.Enabled = true;
- float value = (float)MainV2.comPort.param["BATT_VOLT_PIN"];
+ float value = (float)MainV2.comPort.MAV.param["BATT_VOLT_PIN"];
if (value == 0) // apm1
{
CMB_apmversion.SelectedIndex = 0;
@@ -402,7 +402,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
private void timer1_Tick(object sender, EventArgs e)
{
- TXT_voltage.Text = MainV2.cs.battery_voltage.ToString();
+ TXT_voltage.Text = MainV2.comPort.MAV.cs.battery_voltage.ToString();
}
private void CMB_apmversion_SelectedIndexChanged(object sender, EventArgs e)
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs
index 85edd7d840..18b998216f 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs
@@ -35,7 +35,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
// update all linked controls - 10hz
try
{
- MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
+ MainV2.comPort.MAV.cs.UpdateCurrentSettings(currentStateBindingSource);
}
catch { }
}
@@ -43,15 +43,15 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
public void Activate()
{
// arducopter
- mavlinkCheckBoxfs_batt_enable.setup(1, 0, "FS_BATT_ENABLE", MainV2.comPort.param);
+ mavlinkCheckBoxfs_batt_enable.setup(1, 0, "FS_BATT_ENABLE", MainV2.comPort.MAV.param);
// plane
- mavlinkCheckBoxthr_fs.setup(1, 0, "THR_FAILSAFE", MainV2.comPort.param, mavlinkNumericUpDownthr_fs_value);
- mavlinkNumericUpDownthr_fs_value.setup(800, 1200, 1, 1, "THR_FS_VALUE", MainV2.comPort.param);
- mavlinkCheckBoxthr_fs_action.setup(1, 0, "THR_FS_ACTION",MainV2.comPort.param);
- mavlinkCheckBoxgcs_fs.setup(1, 0, "FS_GCS_ENABL", MainV2.comPort.param);
- mavlinkCheckBoxshort_fs.setup(1, 0, "FS_SHORT_ACTN", MainV2.comPort.param);
- mavlinkCheckBoxlong_fs.setup(1, 0, "FS_LONG_ACTN", MainV2.comPort.param);
+ mavlinkCheckBoxthr_fs.setup(1, 0, "THR_FAILSAFE", MainV2.comPort.MAV.param, mavlinkNumericUpDownthr_fs_value);
+ mavlinkNumericUpDownthr_fs_value.setup(800, 1200, 1, 1, "THR_FS_VALUE", MainV2.comPort.MAV.param);
+ mavlinkCheckBoxthr_fs_action.setup(1, 0, "THR_FS_ACTION",MainV2.comPort.MAV.param);
+ mavlinkCheckBoxgcs_fs.setup(1, 0, "FS_GCS_ENABL", MainV2.comPort.MAV.param);
+ mavlinkCheckBoxshort_fs.setup(1, 0, "FS_SHORT_ACTN", MainV2.comPort.MAV.param);
+ mavlinkCheckBoxlong_fs.setup(1, 0, "FS_LONG_ACTN", MainV2.comPort.MAV.param);
timer.Enabled = true;
timer.Interval = 100;
@@ -109,7 +109,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
private void lbl_currentmode_TextChanged(object sender, EventArgs e)
{
- if (MainV2.cs.ch3in < (float)MainV2.comPort.param["THR_FS_VALUE"])
+ if (MainV2.comPort.MAV.cs.ch3in < (float)MainV2.comPort.MAV.param["THR_FS_VALUE"])
{
lbl_currentmode.ForeColor = Color.Red;
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs
index 7f4cf09bda..361235278d 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs
@@ -25,43 +25,43 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
try
{
- MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
+ MainV2.comPort.MAV.cs.UpdateCurrentSettings(currentStateBindingSource);
}
catch { }
float pwm = 0;
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane || MainV2.cs.firmware == MainV2.Firmwares.ArduRover) // APM
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane || MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover) // APM
{
- if (MainV2.comPort.param.ContainsKey("FLTMODE_CH"))
+ if (MainV2.comPort.MAV.param.ContainsKey("FLTMODE_CH"))
{
- switch ((int)(float)MainV2.comPort.param["FLTMODE_CH"])
+ switch ((int)(float)MainV2.comPort.MAV.param["FLTMODE_CH"])
{
case 5:
- pwm = MainV2.cs.ch5in;
+ pwm = MainV2.comPort.MAV.cs.ch5in;
break;
case 6:
- pwm = MainV2.cs.ch6in;
+ pwm = MainV2.comPort.MAV.cs.ch6in;
break;
case 7:
- pwm = MainV2.cs.ch7in;
+ pwm = MainV2.comPort.MAV.cs.ch7in;
break;
case 8:
- pwm = MainV2.cs.ch8in;
+ pwm = MainV2.comPort.MAV.cs.ch8in;
break;
default:
break;
}
- LBL_flightmodepwm.Text = MainV2.comPort.param["FLTMODE_CH"].ToString() + ": " + pwm.ToString();
+ LBL_flightmodepwm.Text = MainV2.comPort.MAV.param["FLTMODE_CH"].ToString() + ": " + pwm.ToString();
}
}
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
{
- pwm = MainV2.cs.ch5in;
- LBL_flightmodepwm.Text = "5: " + MainV2.cs.ch5in.ToString();
+ pwm = MainV2.comPort.MAV.cs.ch5in;
+ LBL_flightmodepwm.Text = "5: " + MainV2.comPort.MAV.cs.ch5in.ToString();
}
Control[] fmodelist = new Control[] { CMB_fmode1, CMB_fmode2, CMB_fmode3, CMB_fmode4, CMB_fmode5, CMB_fmode6 };
@@ -100,11 +100,11 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
MainV2.comPort.setParam("FLTMODE5", (float)Int32.Parse(CMB_fmode5.SelectedValue.ToString()));
MainV2.comPort.setParam("FLTMODE6", (float)Int32.Parse(CMB_fmode6.SelectedValue.ToString()));
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
{
float value = (float)(CB_simple1.Checked ? (int)SimpleMode.Simple1 : 0) + (CB_simple2.Checked ? (int)SimpleMode.Simple2 : 0) + (CB_simple3.Checked ? (int)SimpleMode.Simple3 : 0)
+ (CB_simple4.Checked ? (int)SimpleMode.Simple4 : 0) + (CB_simple5.Checked ? (int)SimpleMode.Simple5 : 0) + (CB_simple6.Checked ? (int)SimpleMode.Simple6 : 0);
- if (MainV2.comPort.param.ContainsKey("SIMPLE"))
+ if (MainV2.comPort.MAV.param.ContainsKey("SIMPLE"))
MainV2.comPort.setParam("SIMPLE", value);
}
}
@@ -131,7 +131,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
public void Activate()
{
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
{
CB_simple1.Visible = false;
CB_simple2.Visible = false;
@@ -168,17 +168,17 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
try
{
- CMB_fmode1.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE1"].ToString()));
- CMB_fmode2.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE2"].ToString()));
- CMB_fmode3.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE3"].ToString()));
- CMB_fmode4.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE4"].ToString()));
- CMB_fmode5.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE5"].ToString()));
+ CMB_fmode1.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.MAV.param["FLTMODE1"].ToString()));
+ CMB_fmode2.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.MAV.param["FLTMODE2"].ToString()));
+ CMB_fmode3.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.MAV.param["FLTMODE3"].ToString()));
+ CMB_fmode4.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.MAV.param["FLTMODE4"].ToString()));
+ CMB_fmode5.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.MAV.param["FLTMODE5"].ToString()));
CMB_fmode6.Text = Common.apmmodes.MANUAL.ToString();
CMB_fmode6.Enabled = false;
}
catch { }
}
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduRover) // APM
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover) // APM
{
CB_simple1.Visible = false;
CB_simple2.Visible = false;
@@ -215,16 +215,16 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
try
{
- CMB_fmode1.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.aprovermodes), MainV2.comPort.param["FLTMODE1"].ToString()));
- CMB_fmode2.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.aprovermodes), MainV2.comPort.param["FLTMODE2"].ToString()));
- CMB_fmode3.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.aprovermodes), MainV2.comPort.param["FLTMODE3"].ToString()));
- CMB_fmode4.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.aprovermodes), MainV2.comPort.param["FLTMODE4"].ToString()));
- CMB_fmode5.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.aprovermodes), MainV2.comPort.param["FLTMODE5"].ToString()));
+ CMB_fmode1.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.aprovermodes), MainV2.comPort.MAV.param["FLTMODE1"].ToString()));
+ CMB_fmode2.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.aprovermodes), MainV2.comPort.MAV.param["FLTMODE2"].ToString()));
+ CMB_fmode3.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.aprovermodes), MainV2.comPort.MAV.param["FLTMODE3"].ToString()));
+ CMB_fmode4.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.aprovermodes), MainV2.comPort.MAV.param["FLTMODE4"].ToString()));
+ CMB_fmode5.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.aprovermodes), MainV2.comPort.MAV.param["FLTMODE5"].ToString()));
CMB_fmode6.Text = Common.aprovermodes.MANUAL.ToString();
CMB_fmode6.Enabled = false;
}
catch { }
- } else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
+ } else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
{
var flightModes = EnumTranslator.Translate();
@@ -254,15 +254,15 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
try
{
- CMB_fmode1.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE1"].ToString()));
- CMB_fmode2.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE2"].ToString()));
- CMB_fmode3.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE3"].ToString()));
- CMB_fmode4.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE4"].ToString()));
- CMB_fmode5.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE5"].ToString()));
- CMB_fmode6.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE6"].ToString()));
+ CMB_fmode1.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.MAV.param["FLTMODE1"].ToString()));
+ CMB_fmode2.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.MAV.param["FLTMODE2"].ToString()));
+ CMB_fmode3.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.MAV.param["FLTMODE3"].ToString()));
+ CMB_fmode4.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.MAV.param["FLTMODE4"].ToString()));
+ CMB_fmode5.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.MAV.param["FLTMODE5"].ToString()));
+ CMB_fmode6.Text = EnumTranslator.GetDisplayText(Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.MAV.param["FLTMODE6"].ToString()));
CMB_fmode6.Enabled = true;
- int simple = int.Parse(MainV2.comPort.param["SIMPLE"].ToString());
+ int simple = int.Parse(MainV2.comPort.MAV.param["SIMPLE"].ToString());
CB_simple1.Checked = ((simple >> 0 & 1) == 1);
CB_simple2.Checked = ((simple >> 1 & 1) == 1);
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFriendlyParams.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFriendlyParams.cs
index 657253aa1d..0eb4058204 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFriendlyParams.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFriendlyParams.cs
@@ -158,7 +158,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
_params.Clear();
// When the parameter list is changed, re sort the list for our View's purposes
- MainV2.comPort.param.Keys.ForEach(x =>
+ MainV2.comPort.MAV.param.Keys.ForEach(x =>
{
string displayName = _parameterMetaDataRepository.GetParameterMetaData(x.ToString(), ParameterMetaDataConstants.DisplayName);
string parameterMode = _parameterMetaDataRepository.GetParameterMetaData(x.ToString(), ParameterMetaDataConstants.User);
@@ -216,7 +216,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
bool controlAdded = false;
- string value = ((float)MainV2.comPort.param[x.Key]).ToString("0.###", CultureInfo.InvariantCulture);
+ string value = ((float)MainV2.comPort.MAV.param[x.Key]).ToString("0.###", CultureInfo.InvariantCulture);
string description = _parameterMetaDataRepository.GetParameterMetaData(x.Key, ParameterMetaDataConstants.Description);
string displayName = x.Value + " (" + x.Key + ")";
string units = _parameterMetaDataRepository.GetParameterMetaData(x.Key, ParameterMetaDataConstants.Units);
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs
index 8e89372292..0bfcd406de 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs
@@ -29,9 +29,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
List> data = new List>();
// backup current rate and set to 10 hz
- byte backupratesens = MainV2.cs.ratesensors;
- MainV2.cs.ratesensors = 10;
- MainV2.comPort.requestDatastream((byte)MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors); // mag captures at 10 hz
+ byte backupratesens = MainV2.comPort.MAV.cs.ratesensors;
+ MainV2.comPort.MAV.cs.ratesensors = 10;
+ MainV2.comPort.requestDatastream((byte)MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.comPort.MAV.cs.ratesensors); // mag captures at 10 hz
CustomMessageBox.Show("Data will be collected for 30 seconds, Please click ok and move the apm around all axises");
@@ -46,24 +46,24 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
// dont let the gui hang
Application.DoEvents();
- if (oldmx != MainV2.cs.mx &&
- oldmy != MainV2.cs.my &&
- oldmz != MainV2.cs.mz)
+ if (oldmx != MainV2.comPort.MAV.cs.mx &&
+ oldmy != MainV2.comPort.MAV.cs.my &&
+ oldmz != MainV2.comPort.MAV.cs.mz)
{
data.Add(new Tuple(
- MainV2.cs.mx - (float)MainV2.cs.mag_ofs_x,
- MainV2.cs.my - (float)MainV2.cs.mag_ofs_y,
- MainV2.cs.mz - (float)MainV2.cs.mag_ofs_z));
+ MainV2.comPort.MAV.cs.mx - (float)MainV2.comPort.MAV.cs.mag_ofs_x,
+ MainV2.comPort.MAV.cs.my - (float)MainV2.comPort.MAV.cs.mag_ofs_y,
+ MainV2.comPort.MAV.cs.mz - (float)MainV2.comPort.MAV.cs.mag_ofs_z));
- oldmx = MainV2.cs.mx;
- oldmy = MainV2.cs.my;
- oldmz = MainV2.cs.mz;
+ oldmx = MainV2.comPort.MAV.cs.mx;
+ oldmy = MainV2.comPort.MAV.cs.my;
+ oldmz = MainV2.comPort.MAV.cs.mz;
}
}
// restore old sensor rate
- MainV2.cs.ratesensors = backupratesens;
- MainV2.comPort.requestDatastream((byte)MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors);
+ MainV2.comPort.MAV.cs.ratesensors = backupratesens;
+ MainV2.comPort.requestDatastream((byte)MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.comPort.MAV.cs.ratesensors);
if (data.Count < 10)
{
@@ -98,7 +98,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["COMPASS_DEC"] == null)
+ if (MainV2.comPort.MAV.param["COMPASS_DEC"] == null)
{
CustomMessageBox.Show("Not Available");
}
@@ -148,7 +148,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["MAG_ENABLE"] == null)
+ if (MainV2.comPort.MAV.param["MAG_ENABLE"] == null)
{
CustomMessageBox.Show("Not Available");
}
@@ -166,7 +166,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["SONAR_ENABLE"] == null)
+ if (MainV2.comPort.MAV.param["SONAR_ENABLE"] == null)
{
CustomMessageBox.Show("Not Available");
}
@@ -184,9 +184,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["ARSPD_ENABLE"] == null)
+ if (MainV2.comPort.MAV.param["ARSPD_ENABLE"] == null)
{
- CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ CustomMessageBox.Show("Not Available on " + MainV2.comPort.MAV.cs.firmware.ToString());
}
else
{
@@ -203,9 +203,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["FLOW_ENABLE"] == null)
+ if (MainV2.comPort.MAV.param["FLOW_ENABLE"] == null)
{
- CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ CustomMessageBox.Show("Not Available on " + MainV2.comPort.MAV.cs.firmware.ToString());
}
else
{
@@ -221,9 +221,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["SONAR_TYPE"] == null)
+ if (MainV2.comPort.MAV.param["SONAR_TYPE"] == null)
{
- CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ CustomMessageBox.Show("Not Available on " + MainV2.comPort.MAV.cs.firmware.ToString());
}
else
{
@@ -247,23 +247,23 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
startup = true;
- CHK_airspeeduse.setup(1, 0, "ARSPD_USE", MainV2.comPort.param);
- CHK_enableairspeed.setup(1, 0, "ARSPD_ENABLE", MainV2.comPort.param);
- CHK_enablecompass.setup(1, 0, "MAG_ENABLE", MainV2.comPort.param, TXT_declination);
- CHK_enableoptflow.setup(1,0,"FLOW_ENABLE", MainV2.comPort.param);
- CHK_enablesonar.setup(1, 0, "SONAR_ENABLE", MainV2.comPort.param, CMB_sonartype);
+ CHK_airspeeduse.setup(1, 0, "ARSPD_USE", MainV2.comPort.MAV.param);
+ CHK_enableairspeed.setup(1, 0, "ARSPD_ENABLE", MainV2.comPort.MAV.param);
+ CHK_enablecompass.setup(1, 0, "MAG_ENABLE", MainV2.comPort.MAV.param, TXT_declination);
+ CHK_enableoptflow.setup(1,0,"FLOW_ENABLE", MainV2.comPort.MAV.param);
+ CHK_enablesonar.setup(1, 0, "SONAR_ENABLE", MainV2.comPort.MAV.param, CMB_sonartype);
- if (MainV2.comPort.param["COMPASS_DEC"] != null)
+ if (MainV2.comPort.MAV.param["COMPASS_DEC"] != null)
{
- TXT_declination.Text = (float.Parse(MainV2.comPort.param["COMPASS_DEC"].ToString()) * rad2deg).ToString();
+ TXT_declination.Text = (float.Parse(MainV2.comPort.MAV.param["COMPASS_DEC"].ToString()) * rad2deg).ToString();
}
- if (MainV2.comPort.param["SONAR_TYPE"] != null)
+ if (MainV2.comPort.MAV.param["SONAR_TYPE"] != null)
{
- CMB_sonartype.SelectedIndex = int.Parse(MainV2.comPort.param["SONAR_TYPE"].ToString());
+ CMB_sonartype.SelectedIndex = int.Parse(MainV2.comPort.MAV.param["SONAR_TYPE"].ToString());
}
- if (MainV2.comPort.param["COMPASS_AUTODEC"] != null)
+ if (MainV2.comPort.MAV.param["COMPASS_AUTODEC"] != null)
{
- CHK_autodec.Checked = MainV2.comPort.param["COMPASS_AUTODEC"].ToString() == "1" ? true : false;
+ CHK_autodec.Checked = MainV2.comPort.MAV.param["COMPASS_AUTODEC"].ToString() == "1" ? true : false;
}
startup = false;
@@ -295,9 +295,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["COMPASS_AUTODEC"] == null)
+ if (MainV2.comPort.MAV.param["COMPASS_AUTODEC"] == null)
{
- CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ CustomMessageBox.Show("Not Available on " + MainV2.comPort.MAV.cs.firmware.ToString());
}
else
{
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs
index 213235dd2c..8f9dfd6a3f 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs
@@ -22,19 +22,14 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
public ConfigMount()
{
InitializeComponent();
- PBOX_WarningIcon.Opacity = 0.0F;
- LBL_Error.Opacity = 0.0F;
+
var delay = new Transition(new TransitionType_Linear(2000));
var fadeIn = new Transition(new TransitionType_Linear(800));
- fadeIn.add(PBOX_WarningIcon, "Opacity", 1.0F);
- fadeIn.add(LBL_Error, "Opacity", 1.0F);
_ErrorTransition = new[] { delay, fadeIn };
_NoErrorTransition = new Transition(new TransitionType_Linear(10));
- _NoErrorTransition.add(PBOX_WarningIcon, "Opacity", 0.0F);
- _NoErrorTransition.add(LBL_Error, "Opacity", 0.0F);
//setup button actions
foreach (var btn in Controls.Cast().OfType
- 59
+ 74
17, 150
@@ -166,7 +166,7 @@
$this
- 57
+ 72
Zoom
@@ -193,7 +193,7 @@
$this
- 58
+ 73
17, 23
@@ -214,7 +214,7 @@
$this
- 56
+ 71
True
@@ -247,7 +247,7 @@
$this
- 55
+ 70
True
@@ -280,7 +280,7 @@
$this
- 54
+ 69
Top, Right
@@ -313,7 +313,7 @@
$this
- 51
+ 68
True
@@ -346,7 +346,7 @@
$this
- 48
+ 65
17, 274
@@ -367,7 +367,7 @@
$this
- 49
+ 66
Zoom
@@ -394,7 +394,7 @@
$this
- 50
+ 67
True
@@ -427,7 +427,7 @@
$this
- 37
+ 54
True
@@ -460,7 +460,7 @@
$this
- 38
+ 55
True
@@ -490,7 +490,7 @@
$this
- 39
+ 56
True
@@ -520,7 +520,7 @@
$this
- 40
+ 57
True
@@ -550,7 +550,7 @@
$this
- 43
+ 60
True
@@ -580,7 +580,7 @@
$this
- 44
+ 61
True
@@ -613,7 +613,7 @@
$this
- 26
+ 43
True
@@ -646,7 +646,7 @@
$this
- 27
+ 44
True
@@ -676,7 +676,7 @@
$this
- 28
+ 45
True
@@ -706,7 +706,7 @@
$this
- 29
+ 46
True
@@ -736,7 +736,7 @@
$this
- 32
+ 49
True
@@ -766,7 +766,7 @@
$this
- 33
+ 50
True
@@ -799,7 +799,7 @@
$this
- 15
+ 32
True
@@ -832,7 +832,7 @@
$this
- 16
+ 33
True
@@ -862,7 +862,7 @@
$this
- 17
+ 34
True
@@ -892,7 +892,7 @@
$this
- 18
+ 35
True
@@ -922,7 +922,7 @@
$this
- 21
+ 38
True
@@ -952,10 +952,10 @@
$this
- 22
+ 39
- 71, 3
+ 90, 3
121, 21
@@ -973,10 +973,10 @@
$this
- 14
+ 31
- 71, 131
+ 90, 131
121, 21
@@ -994,10 +994,10 @@
$this
- 13
+ 30
- 71, 255
+ 90, 255
121, 21
@@ -1015,7 +1015,7 @@
$this
- 12
+ 29
True
@@ -1048,7 +1048,7 @@
$this
- 10
+ 27
True
@@ -1081,7 +1081,7 @@
$this
- 8
+ 25
True
@@ -1114,7 +1114,7 @@
$this
- 6
+ 23
False
@@ -1132,13 +1132,13 @@
CMB_inputch_pan
- ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 7
+ 24
False
@@ -1156,13 +1156,13 @@
CMB_inputch_roll
- ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 9
+ 26
False
@@ -1180,13 +1180,13 @@
CMB_inputch_tilt
- ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkComboBox, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 11
+ 28
False
@@ -1204,13 +1204,13 @@
mavlinkNumericUpDownTAM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 19
+ 36
False
@@ -1228,13 +1228,13 @@
mavlinkNumericUpDownTAMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 20
+ 37
False
@@ -1252,13 +1252,13 @@
mavlinkNumericUpDownTSM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 23
+ 40
False
@@ -1276,13 +1276,13 @@
mavlinkNumericUpDownTSMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 24
+ 41
True
@@ -1309,13 +1309,13 @@
mavlinkCheckBoxTR
- ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 25
+ 42
False
@@ -1333,13 +1333,13 @@
mavlinkNumericUpDownPAM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 30
+ 47
False
@@ -1357,13 +1357,13 @@
mavlinkNumericUpDownPAMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 31
+ 48
False
@@ -1381,13 +1381,13 @@
mavlinkNumericUpDownPSM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 34
+ 51
False
@@ -1405,13 +1405,13 @@
mavlinkNumericUpDownPSMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 35
+ 52
True
@@ -1438,13 +1438,13 @@
mavlinkCheckBoxPR
- ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 36
+ 53
False
@@ -1462,13 +1462,13 @@
mavlinkNumericUpDownRAM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 41
+ 58
False
@@ -1486,13 +1486,13 @@
mavlinkNumericUpDownRAMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 42
+ 59
False
@@ -1510,13 +1510,13 @@
mavlinkNumericUpDownRSM
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 45
+ 62
False
@@ -1534,13 +1534,13 @@
mavlinkNumericUpDownRSMX
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 46
+ 63
True
@@ -1567,73 +1567,13 @@
mavlinkCheckBoxRR
- ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 47
-
-
- Bottom, Left, Right
-
-
- True
-
-
- NoControl
-
-
- 303, 402
-
-
- 138, 13
-
-
- 76
-
-
- Error Message of some kind
-
-
- LBL_Error
-
-
- ArdupilotMega.Controls.LabelWithPseudoOpacity, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
-
-
- $this
-
-
- 52
-
-
- Bottom, Left, Right
-
-
- NoControl
-
-
- 264, 389
-
-
- 32, 32
-
-
- 75
-
-
- PBOX_WarningIcon
-
-
- ArdupilotMega.Controls.PictureBoxWithPseudoOpacity, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
-
-
- $this
-
-
- 53
+ 64
label27
@@ -1651,7 +1591,7 @@
NUD_RETRACT_z
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox4
@@ -1675,7 +1615,7 @@
NUD_RETRACT_y
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox4
@@ -1699,7 +1639,7 @@
NUD_RETRACT_x
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox4
@@ -1729,7 +1669,7 @@
$this
- 5
+ 22
True
@@ -1777,7 +1717,7 @@
NUD_RETRACT_z
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox4
@@ -1831,7 +1771,7 @@
NUD_RETRACT_y
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox4
@@ -1882,7 +1822,7 @@
NUD_RETRACT_x
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox4
@@ -1906,7 +1846,7 @@
NUD_NEUTRAL_z
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox5
@@ -1930,7 +1870,7 @@
NUD_NEUTRAL_y
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox5
@@ -1954,7 +1894,7 @@
NUD_NEUTRAL_x
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox5
@@ -1984,7 +1924,7 @@
$this
- 4
+ 21
True
@@ -2032,7 +1972,7 @@
NUD_NEUTRAL_z
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox5
@@ -2086,7 +2026,7 @@
NUD_NEUTRAL_y
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox5
@@ -2140,7 +2080,7 @@
NUD_NEUTRAL_x
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox5
@@ -2164,7 +2104,7 @@
NUD_CONTROL_z
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox6
@@ -2188,7 +2128,7 @@
NUD_CONTROL_y
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox6
@@ -2212,7 +2152,7 @@
NUD_CONTROL_x
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox6
@@ -2242,7 +2182,7 @@
$this
- 3
+ 20
True
@@ -2290,7 +2230,7 @@
NUD_CONTROL_z
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox6
@@ -2344,7 +2284,7 @@
NUD_CONTROL_y
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox6
@@ -2398,7 +2338,7 @@
NUD_CONTROL_x
- ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
groupBox6
@@ -2428,13 +2368,13 @@
CHK_stab_tilt
- ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 2
+ 19
True
@@ -2461,13 +2401,13 @@
CHK_stab_roll
- ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
- 1
+ 18
True
@@ -2494,19 +2434,487 @@
CHK_stab_pan
- ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4698.13768, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
$this
+ 17
+
+
+ 90, 394
+
+
+ 121, 21
+
+
+ 156
+
+
+ comboBox1
+
+
+ System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 3
+
+
+ True
+
+
+ Microsoft Sans Serif, 12pt
+
+
+ NoControl
+
+
+ 402, 421
+
+
+ 62, 20
+
+
+ 155
+
+
+ Shutter
+
+
+ label35
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 4
+
+
+ True
+
+
+ Microsoft Sans Serif, 12pt
+
+
+ NoControl
+
+
+ 251, 421
+
+
+ 95, 20
+
+
+ 154
+
+
+ Servo Limits
+
+
+ label36
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 5
+
+
+ True
+
+
+ NoControl
+
+
+ 354, 474
+
+
+ 63, 13
+
+
+ 153
+
+
+ Not Pushed
+
+
+ label37
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 6
+
+
+ True
+
+
+ NoControl
+
+
+ 374, 446
+
+
+ 43, 13
+
+
+ 152
+
+
+ Pushed
+
+
+ label38
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 7
+
+
+ False
+
+
+ 423, 444
+
+
+ 59, 20
+
+
+ 151
+
+
+ mavlinkNumericUpDown1
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 8
+
+
+ False
+
+
+ 423, 470
+
+
+ 59, 20
+
+
+ 150
+
+
+ mavlinkNumericUpDown2
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 9
+
+
+ True
+
+
+ NoControl
+
+
+ 246, 474
+
+
+ 27, 13
+
+
+ 149
+
+
+ Max
+
+
+ label39
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 10
+
+
+ True
+
+
+ NoControl
+
+
+ 246, 446
+
+
+ 24, 13
+
+
+ 148
+
+
+ Min
+
+
+ label40
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 11
+
+
+ False
+
+
+ 276, 444
+
+
+ 59, 20
+
+
+ 147
+
+
+ mavlinkNumericUpDownShutM
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 12
+
+
+ False
+
+
+ 276, 470
+
+
+ 59, 20
+
+
+ 146
+
+
+ mavlinkNumericUpDownShutMX
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 13
+
+
+ True
+
+
+ Microsoft Sans Serif, 12pt
+
+
+ NoControl
+
+
+ 20, 395
+
+
+ 62, 20
+
+
+ 144
+
+
+ Shutter
+
+
+ label41
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 14
+
+
+ 17, 413
+
+
+ 516, 5
+
+
+ 142
+
+
+ groupBox7
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 15
+
+
+ Zoom
+
+
+ NoControl
+
+
+ 33, 404
+
+
+ 203, 112
+
+
+ 143
+
+
+ pictureBox4
+
+
+ System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 16
+
+
+ NoControl
+
+
+ 346, 493
+
+
+ 71, 28
+
+
+ 158
+
+
+ Duration (1/10th sec)
+
+
+ label34
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 1
+
+
+ False
+
+
+ 423, 496
+
+
+ 59, 20
+
+
+ 157
+
+
+ mavlinkNumericUpDown5
+
+
+ ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4723.32649, Culture=neutral, PublicKeyToken=null
+
+
+ $this
+
+
+ 2
+
+
+ True
+
+
+ Microsoft Sans Serif, 12pt
+
+
+ NoControl
+
+
+ 180, 528
+
+
+ 325, 20
+
+
+ 159
+
+
+ Please set the Ch7 Option to Camera Trigger
+
+
+ label42
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
0
True
- 674, 432
+ 674, 567
ConfigMount
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
index 5689e55e7e..9b77d40d01 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
@@ -332,10 +332,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (startup)
return;
MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
- MainV2.cs.rateattitude = byte.Parse(((ComboBox)sender).Text);
+ MainV2.comPort.MAV.cs.rateattitude = byte.Parse(((ComboBox)sender).Text);
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA1, MainV2.cs.rateattitude); // request attitude
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA2, MainV2.cs.rateattitude); // request vfr
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA1, MainV2.comPort.MAV.cs.rateattitude); // request attitude
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA2, MainV2.comPort.MAV.cs.rateattitude); // request vfr
}
private void CMB_rateposition_SelectedIndexChanged(object sender, EventArgs e)
@@ -343,9 +343,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (startup)
return;
MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
- MainV2.cs.rateposition = byte.Parse(((ComboBox)sender).Text);
+ MainV2.comPort.MAV.cs.rateposition = byte.Parse(((ComboBox)sender).Text);
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.POSITION, MainV2.cs.rateposition); // request gps
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.POSITION, MainV2.comPort.MAV.cs.rateposition); // request gps
}
private void CMB_ratestatus_SelectedIndexChanged(object sender, EventArgs e)
@@ -353,9 +353,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (startup)
return;
MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
- MainV2.cs.ratestatus = byte.Parse(((ComboBox)sender).Text);
+ MainV2.comPort.MAV.cs.ratestatus = byte.Parse(((ComboBox)sender).Text);
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTENDED_STATUS, MainV2.cs.ratestatus); // mode
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTENDED_STATUS, MainV2.comPort.MAV.cs.ratestatus); // mode
}
private void CMB_raterc_SelectedIndexChanged(object sender, EventArgs e)
@@ -363,9 +363,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (startup)
return;
MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
- MainV2.cs.raterc = byte.Parse(((ComboBox)sender).Text);
+ MainV2.comPort.MAV.cs.raterc = byte.Parse(((ComboBox)sender).Text);
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, MainV2.cs.raterc); // request rc info
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, MainV2.comPort.MAV.cs.raterc); // request rc info
}
private void CMB_ratesensors_SelectedIndexChanged(object sender, EventArgs e)
@@ -373,10 +373,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (startup)
return;
MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
- MainV2.cs.ratesensors = byte.Parse(((ComboBox)sender).Text);
+ MainV2.comPort.MAV.cs.ratesensors = byte.Parse(((ComboBox)sender).Text);
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA3, MainV2.cs.ratesensors); // request extra stuff - tridge
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA3, MainV2.comPort.MAV.cs.ratesensors); // request extra stuff - tridge
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.comPort.MAV.cs.ratesensors); // request raw sensor
}
private void CHK_mavdebug_CheckedChanged(object sender, EventArgs e)
@@ -407,7 +407,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (MainV2.config["speechaltheight"] != null)
speechstring = MainV2.config["speechaltheight"].ToString();
Common.InputBox("Min Alt", "What altitude do you want to warn at? (relative to home)", ref speechstring);
- MainV2.config["speechaltheight"] = (double.Parse(speechstring) / MainV2.cs.multiplierdist).ToString(); // save as m
+ MainV2.config["speechaltheight"] = (double.Parse(speechstring) / MainV2.comPort.MAV.cs.multiplierdist).ToString(); // save as m
}
}
@@ -555,11 +555,11 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
// setup other config state
SetCheckboxFromConfig("CHK_resetapmonconnect", CHK_resetapmonconnect);
- CMB_rateattitude.Text = MainV2.cs.rateattitude.ToString();
- CMB_rateposition.Text = MainV2.cs.rateposition.ToString();
- CMB_raterc.Text = MainV2.cs.raterc.ToString();
- CMB_ratestatus.Text = MainV2.cs.ratestatus.ToString();
- CMB_ratesensors.Text = MainV2.cs.ratesensors.ToString();
+ CMB_rateattitude.Text = MainV2.comPort.MAV.cs.rateattitude.ToString();
+ CMB_rateposition.Text = MainV2.comPort.MAV.cs.rateposition.ToString();
+ CMB_raterc.Text = MainV2.comPort.MAV.cs.raterc.ToString();
+ CMB_ratestatus.Text = MainV2.comPort.MAV.cs.ratestatus.ToString();
+ CMB_ratesensors.Text = MainV2.comPort.MAV.cs.ratesensors.ToString();
SetCheckboxFromConfig("CHK_GDIPlus", CHK_GDIPlus);
SetCheckboxFromConfig("CHK_maprotation", CHK_maprotation);
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs
index 88e0234d95..38cd1f4c3a 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs
@@ -48,7 +48,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
// update all linked controls - 10hz
try
{
- MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
+ MainV2.comPort.MAV.cs.UpdateCurrentSettings(currentStateBindingSource);
}
catch { }
}
@@ -61,14 +61,14 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
startup = true;
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
try
{
- CHK_mixmode.Checked = MainV2.comPort.param["ELEVON_MIXING"].ToString() == "1";
- CHK_elevonrev.Checked = MainV2.comPort.param["ELEVON_REVERSE"].ToString() == "1";
- CHK_elevonch1rev.Checked = MainV2.comPort.param["ELEVON_CH1_REV"].ToString() == "1";
- CHK_elevonch2rev.Checked = MainV2.comPort.param["ELEVON_CH2_REV"].ToString() == "1";
+ CHK_mixmode.Checked = MainV2.comPort.MAV.param["ELEVON_MIXING"].ToString() == "1";
+ CHK_elevonrev.Checked = MainV2.comPort.MAV.param["ELEVON_REVERSE"].ToString() == "1";
+ CHK_elevonch1rev.Checked = MainV2.comPort.MAV.param["ELEVON_CH1_REV"].ToString() == "1";
+ CHK_elevonch2rev.Checked = MainV2.comPort.MAV.param["ELEVON_CH2_REV"].ToString() == "1";
}
catch { } // this will fail on arducopter
}
@@ -76,7 +76,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
groupBoxElevons.Visible = false;
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
CHK_revch1.Visible = false;
CHK_revch2.Visible = false;
@@ -86,10 +86,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
}
try
{
- CHK_revch1.Checked = MainV2.comPort.param["RC1_REV"].ToString() == "-1";
- CHK_revch2.Checked = MainV2.comPort.param["RC2_REV"].ToString() == "-1";
- CHK_revch3.Checked = MainV2.comPort.param["RC3_REV"].ToString() == "-1";
- CHK_revch4.Checked = MainV2.comPort.param["RC4_REV"].ToString() == "-1";
+ CHK_revch1.Checked = MainV2.comPort.MAV.param["RC1_REV"].ToString() == "-1";
+ CHK_revch2.Checked = MainV2.comPort.MAV.param["RC2_REV"].ToString() == "-1";
+ CHK_revch3.Checked = MainV2.comPort.MAV.param["RC3_REV"].ToString() == "-1";
+ CHK_revch4.Checked = MainV2.comPort.MAV.param["RC4_REV"].ToString() == "-1";
}
catch {}//(Exception ex) { CustomMessageBox.Show("Missing RC rev Param " + ex.ToString()); }
startup = false;
@@ -106,15 +106,15 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
CustomMessageBox.Show("Ensure your transmitter is on and receiver is powered and connected\nEnsure your motor does not have power/no props!!!");
- byte oldrc = MainV2.cs.raterc;
- byte oldatt = MainV2.cs.rateattitude;
- byte oldpos = MainV2.cs.rateposition;
- byte oldstatus = MainV2.cs.ratestatus;
+ byte oldrc = MainV2.comPort.MAV.cs.raterc;
+ byte oldatt = MainV2.comPort.MAV.cs.rateattitude;
+ byte oldpos = MainV2.comPort.MAV.cs.rateposition;
+ byte oldstatus = MainV2.comPort.MAV.cs.ratestatus;
- MainV2.cs.raterc = 10;
- MainV2.cs.rateattitude = 0;
- MainV2.cs.rateposition = 0;
- MainV2.cs.ratestatus = 0;
+ MainV2.comPort.MAV.cs.raterc = 10;
+ MainV2.comPort.MAV.cs.rateattitude = 0;
+ MainV2.comPort.MAV.cs.rateposition = 0;
+ MainV2.comPort.MAV.cs.ratestatus = 0;
try
{
@@ -135,34 +135,34 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
System.Threading.Thread.Sleep(5);
- MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
+ MainV2.comPort.MAV.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
// check for non 0 values
- if (MainV2.cs.ch1in > 800 && MainV2.cs.ch1in < 2200)
+ if (MainV2.comPort.MAV.cs.ch1in > 800 && MainV2.comPort.MAV.cs.ch1in < 2200)
{
- rcmin[0] = Math.Min(rcmin[0], MainV2.cs.ch1in);
- rcmax[0] = Math.Max(rcmax[0], MainV2.cs.ch1in);
+ rcmin[0] = Math.Min(rcmin[0], MainV2.comPort.MAV.cs.ch1in);
+ rcmax[0] = Math.Max(rcmax[0], MainV2.comPort.MAV.cs.ch1in);
- rcmin[1] = Math.Min(rcmin[1], MainV2.cs.ch2in);
- rcmax[1] = Math.Max(rcmax[1], MainV2.cs.ch2in);
+ rcmin[1] = Math.Min(rcmin[1], MainV2.comPort.MAV.cs.ch2in);
+ rcmax[1] = Math.Max(rcmax[1], MainV2.comPort.MAV.cs.ch2in);
- rcmin[2] = Math.Min(rcmin[2], MainV2.cs.ch3in);
- rcmax[2] = Math.Max(rcmax[2], MainV2.cs.ch3in);
+ rcmin[2] = Math.Min(rcmin[2], MainV2.comPort.MAV.cs.ch3in);
+ rcmax[2] = Math.Max(rcmax[2], MainV2.comPort.MAV.cs.ch3in);
- rcmin[3] = Math.Min(rcmin[3], MainV2.cs.ch4in);
- rcmax[3] = Math.Max(rcmax[3], MainV2.cs.ch4in);
+ rcmin[3] = Math.Min(rcmin[3], MainV2.comPort.MAV.cs.ch4in);
+ rcmax[3] = Math.Max(rcmax[3], MainV2.comPort.MAV.cs.ch4in);
- rcmin[4] = Math.Min(rcmin[4], MainV2.cs.ch5in);
- rcmax[4] = Math.Max(rcmax[4], MainV2.cs.ch5in);
+ rcmin[4] = Math.Min(rcmin[4], MainV2.comPort.MAV.cs.ch5in);
+ rcmax[4] = Math.Max(rcmax[4], MainV2.comPort.MAV.cs.ch5in);
- rcmin[5] = Math.Min(rcmin[5], MainV2.cs.ch6in);
- rcmax[5] = Math.Max(rcmax[5], MainV2.cs.ch6in);
+ rcmin[5] = Math.Min(rcmin[5], MainV2.comPort.MAV.cs.ch6in);
+ rcmax[5] = Math.Max(rcmax[5], MainV2.comPort.MAV.cs.ch6in);
- rcmin[6] = Math.Min(rcmin[6], MainV2.cs.ch7in);
- rcmax[6] = Math.Max(rcmax[6], MainV2.cs.ch7in);
+ rcmin[6] = Math.Min(rcmin[6], MainV2.comPort.MAV.cs.ch7in);
+ rcmax[6] = Math.Max(rcmax[6], MainV2.comPort.MAV.cs.ch7in);
- rcmin[7] = Math.Min(rcmin[7], MainV2.cs.ch8in);
- rcmax[7] = Math.Max(rcmax[7], MainV2.cs.ch8in);
+ rcmin[7] = Math.Min(rcmin[7], MainV2.comPort.MAV.cs.ch8in);
+ rcmax[7] = Math.Max(rcmax[7], MainV2.comPort.MAV.cs.ch8in);
BARroll.minline = (int)rcmin[0];
BARroll.maxline = (int)rcmax[0];
@@ -193,16 +193,16 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
CustomMessageBox.Show("Ensure all your sticks are centered and throttle is down, and click ok to continue");
- MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
+ MainV2.comPort.MAV.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
- rctrim[0] = MainV2.cs.ch1in;
- rctrim[1] = MainV2.cs.ch2in;
- rctrim[2] = MainV2.cs.ch3in;
- rctrim[3] = MainV2.cs.ch4in;
- rctrim[4] = MainV2.cs.ch5in;
- rctrim[5] = MainV2.cs.ch6in;
- rctrim[6] = MainV2.cs.ch7in;
- rctrim[7] = MainV2.cs.ch8in;
+ rctrim[0] = MainV2.comPort.MAV.cs.ch1in;
+ rctrim[1] = MainV2.comPort.MAV.cs.ch2in;
+ rctrim[2] = MainV2.comPort.MAV.cs.ch3in;
+ rctrim[3] = MainV2.comPort.MAV.cs.ch4in;
+ rctrim[4] = MainV2.comPort.MAV.cs.ch5in;
+ rctrim[5] = MainV2.comPort.MAV.cs.ch6in;
+ rctrim[6] = MainV2.comPort.MAV.cs.ch7in;
+ rctrim[7] = MainV2.comPort.MAV.cs.ch8in;
string data = "---------------\n";
@@ -225,10 +225,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
data = data + "CH" + (a + 1) + " " + rcmin[a] + " | " + rcmax[a] + "\n";
}
- MainV2.cs.raterc = oldrc;
- MainV2.cs.rateattitude = oldatt;
- MainV2.cs.rateposition = oldpos;
- MainV2.cs.ratestatus = oldstatus;
+ MainV2.comPort.MAV.cs.raterc = oldrc;
+ MainV2.comPort.MAV.cs.rateattitude = oldatt;
+ MainV2.comPort.MAV.cs.rateposition = oldpos;
+ MainV2.comPort.MAV.cs.ratestatus = oldstatus;
try
{
@@ -249,9 +249,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["ELEVON_MIXING"] == null)
+ if (MainV2.comPort.MAV.param["ELEVON_MIXING"] == null)
{
- CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ CustomMessageBox.Show("Not Available on " + MainV2.comPort.MAV.cs.firmware.ToString());
}
else
{
@@ -267,9 +267,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["ELEVON_REVERSE"] == null)
+ if (MainV2.comPort.MAV.param["ELEVON_REVERSE"] == null)
{
- CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ CustomMessageBox.Show("Not Available on " + MainV2.comPort.MAV.cs.firmware.ToString());
}
else
{
@@ -285,9 +285,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["ELEVON_CH1_REV"] == null)
+ if (MainV2.comPort.MAV.param["ELEVON_CH1_REV"] == null)
{
- CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ CustomMessageBox.Show("Not Available on " + MainV2.comPort.MAV.cs.firmware.ToString());
}
else
{
@@ -303,9 +303,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["ELEVON_CH2_REV"] == null)
+ if (MainV2.comPort.MAV.param["ELEVON_CH2_REV"] == null)
{
- CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ CustomMessageBox.Show("Not Available on " + MainV2.comPort.MAV.cs.firmware.ToString());
}
else
{
@@ -352,7 +352,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (startup)
return;
- if (MainV2.comPort.param["SWITCH_ENABLE"] != null && (float)MainV2.comPort.param["SWITCH_ENABLE"] == 1)
+ if (MainV2.comPort.MAV.param["SWITCH_ENABLE"] != null && (float)MainV2.comPort.MAV.param["SWITCH_ENABLE"] == 1)
{
try
{
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
index a5a50e76f6..80de700d21 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
@@ -31,6 +31,7 @@
this.components = new System.ComponentModel.Container();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigRawParams));
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
this.BUT_compare = new ArdupilotMega.Controls.MyButton();
this.BUT_rerequestparams = new ArdupilotMega.Controls.MyButton();
@@ -38,11 +39,13 @@
this.BUT_save = new ArdupilotMega.Controls.MyButton();
this.BUT_load = new ArdupilotMega.Controls.MyButton();
this.Params = new System.Windows.Forms.DataGridView();
- this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
- this.label1 = new System.Windows.Forms.Label();
this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn();
+ this.Units = new System.Windows.Forms.DataGridViewTextBoxColumn();
+ this.Options = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Desc = new System.Windows.Forms.DataGridViewTextBoxColumn();
+ this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
+ this.label1 = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit();
this.SuspendLayout();
//
@@ -86,6 +89,7 @@
this.Params.AllowUserToAddRows = false;
this.Params.AllowUserToDeleteRows = false;
resources.ApplyResources(this.Params, "Params");
+ this.Params.AutoSizeRowsMode = System.Windows.Forms.DataGridViewAutoSizeRowsMode.AllCells;
dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
dataGridViewCellStyle1.BackColor = System.Drawing.Color.Maroon;
dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
@@ -98,30 +102,22 @@
this.Params.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
this.Command,
this.Value,
+ this.Units,
+ this.Options,
this.Desc});
this.Params.Name = "Params";
- dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
- dataGridViewCellStyle2.BackColor = System.Drawing.SystemColors.ActiveCaption;
- dataGridViewCellStyle2.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
- dataGridViewCellStyle2.ForeColor = System.Drawing.SystemColors.WindowText;
- dataGridViewCellStyle2.SelectionBackColor = System.Drawing.SystemColors.Highlight;
- dataGridViewCellStyle2.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
- dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
- this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2;
+ dataGridViewCellStyle3.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
+ dataGridViewCellStyle3.BackColor = System.Drawing.SystemColors.ActiveCaption;
+ dataGridViewCellStyle3.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
+ dataGridViewCellStyle3.ForeColor = System.Drawing.SystemColors.WindowText;
+ dataGridViewCellStyle3.SelectionBackColor = System.Drawing.SystemColors.Highlight;
+ dataGridViewCellStyle3.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
+ dataGridViewCellStyle3.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
+ this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle3;
this.Params.RowHeadersVisible = false;
+ this.Params.RowHeadersWidthSizeMode = System.Windows.Forms.DataGridViewRowHeadersWidthSizeMode.AutoSizeToDisplayedHeaders;
this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged);
//
- // toolTip1
- //
- this.toolTip1.AutoPopDelay = 180000;
- this.toolTip1.InitialDelay = 500;
- this.toolTip1.ReshowDelay = 100;
- //
- // label1
- //
- resources.ApplyResources(this.label1, "label1");
- this.label1.Name = "label1";
- //
// Command
//
resources.ApplyResources(this.Command, "Command");
@@ -133,13 +129,38 @@
resources.ApplyResources(this.Value, "Value");
this.Value.Name = "Value";
//
+ // Units
+ //
+ resources.ApplyResources(this.Units, "Units");
+ this.Units.Name = "Units";
+ this.Units.ReadOnly = true;
+ //
+ // Options
+ //
+ resources.ApplyResources(this.Options, "Options");
+ this.Options.Name = "Options";
+ this.Options.ReadOnly = true;
+ //
// Desc
//
- this.Desc.AutoSizeMode = System.Windows.Forms.DataGridViewAutoSizeColumnMode.AllCells;
+ this.Desc.AutoSizeMode = System.Windows.Forms.DataGridViewAutoSizeColumnMode.Fill;
+ dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
+ this.Desc.DefaultCellStyle = dataGridViewCellStyle2;
resources.ApplyResources(this.Desc, "Desc");
this.Desc.Name = "Desc";
this.Desc.ReadOnly = true;
//
+ // toolTip1
+ //
+ this.toolTip1.AutoPopDelay = 180000;
+ this.toolTip1.InitialDelay = 500;
+ this.toolTip1.ReshowDelay = 100;
+ //
+ // label1
+ //
+ resources.ApplyResources(this.label1, "label1");
+ this.label1.Name = "label1";
+ //
// ConfigRawParams
//
resources.ApplyResources(this, "$this");
@@ -170,6 +191,8 @@
private System.Windows.Forms.Label label1;
private System.Windows.Forms.DataGridViewTextBoxColumn Command;
private System.Windows.Forms.DataGridViewTextBoxColumn Value;
+ private System.Windows.Forms.DataGridViewTextBoxColumn Units;
+ private System.Windows.Forms.DataGridViewTextBoxColumn Options;
private System.Windows.Forms.DataGridViewTextBoxColumn Desc;
}
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
index 8a95dcac51..064b241499 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
@@ -172,7 +172,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
StreamWriter sw = new StreamWriter(sfd.OpenFile());
string input = DateTime.Now + " Frame : ";
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
input = DateTime.Now + " Plane: Skywalker";
}
@@ -254,7 +254,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
param2 = loadParamFile(ofd.FileName);
- Form paramCompareForm = new ParamCompare(Params, MainV2.comPort.param, param2);
+ Form paramCompareForm = new ParamCompare(Params, MainV2.comPort.MAV.param, param2);
ThemeManager.ApplyThemeTo(paramCompareForm);
paramCompareForm.ShowDialog();
@@ -385,7 +385,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
Params.Rows.Clear();
// process hashdefines and update display
- foreach (string value in MainV2.comPort.param.Keys)
+ foreach (string value in MainV2.comPort.MAV.param.Keys)
{
if (value == null || value == "")
continue;
@@ -394,7 +394,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
Params.Rows.Add();
Params.Rows[Params.RowCount - 1].Cells[Command.Index].Value = value;
- Params.Rows[Params.RowCount - 1].Cells[Value.Index].Value = ((float)MainV2.comPort.param[value]).ToString("0.###");
+ Params.Rows[Params.RowCount - 1].Cells[Value.Index].Value = ((float)MainV2.comPort.MAV.param[value]).ToString("0.###");
try
{
string metaDataDescription = _parameterMetaDataRepository.GetParameterMetaData(value, ParameterMetaDataConstants.Description);
@@ -405,27 +405,20 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
string range = _parameterMetaDataRepository.GetParameterMetaData(value, ParameterMetaDataConstants.Range);
string options = _parameterMetaDataRepository.GetParameterMetaData(value, ParameterMetaDataConstants.Values);
+ string units = _parameterMetaDataRepository.GetParameterMetaData(value, ParameterMetaDataConstants.Units);
- if (!string.IsNullOrEmpty(range))
- {
- range = " Range: " + range;
- }
-
- if (!string.IsNullOrEmpty(options))
- {
- options = " Options: " + options;
- }
-
- Params.Rows[Params.RowCount - 1].Cells[Desc.Index].Value = range + options;
+ Params.Rows[Params.RowCount - 1].Cells[Units.Index].Value = units;
+ Params.Rows[Params.RowCount - 1].Cells[Options.Index].Value = range + options;
+ Params.Rows[Params.RowCount - 1].Cells[Desc.Index].Value = metaDataDescription;
}
else if (tooltips[value] != null)
{
- Params.Rows[Params.RowCount - 1].Cells[Command.Index].ToolTipText = ((paramsettings)tooltips[value]).desc;
+ //Params.Rows[Params.RowCount - 1].Cells[Command.Index].ToolTipText = ((paramsettings)tooltips[value]).desc;
//Params.Rows[Params.RowCount - 1].Cells[RawValue.Index].ToolTipText = ((paramsettings)tooltips[value]).desc;
- Params.Rows[Params.RowCount - 1].Cells[Value.Index].ToolTipText = ((paramsettings)tooltips[value]).desc;
+ // Params.Rows[Params.RowCount - 1].Cells[Value.Index].ToolTipText = ((paramsettings)tooltips[value]).desc;
- Params.Rows[Params.RowCount - 1].Cells[Desc.Index].Value = "Old: "+((paramsettings)tooltips[value]).desc;
+ // Params.Rows[Params.RowCount - 1].Cells[Desc.Index].Value = "Old: "+((paramsettings)tooltips[value]).desc;
//Params.Rows[Params.RowCount - 1].Cells[Default.Index].Value = ((paramsettings)tooltips[value]).normalvalue;
//Params.Rows[Params.RowCount - 1].Cells[mavScale.Index].Value = ((paramsettings)tooltips[value]).scale;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx
index cc1cef2c3a..a91cbb817c 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx
@@ -126,7 +126,7 @@
- 506, 119
+ 631, 119
103, 19
@@ -142,7 +142,7 @@
BUT_compare
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4711.17948, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4724.30400, Culture=neutral, PublicKeyToken=null
$this
@@ -157,7 +157,7 @@
NoControl
- 506, 94
+ 631, 94
103, 19
@@ -172,7 +172,7 @@
BUT_rerequestparams
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4711.17948, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4724.30400, Culture=neutral, PublicKeyToken=null
$this
@@ -187,7 +187,7 @@
NoControl
- 506, 69
+ 631, 69
103, 19
@@ -202,7 +202,7 @@
BUT_writePIDS
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4711.17948, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4724.30400, Culture=neutral, PublicKeyToken=null
$this
@@ -217,7 +217,7 @@
NoControl
- 506, 35
+ 631, 35
0, 0, 0, 0
@@ -235,7 +235,7 @@
BUT_save
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4711.17948, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4724.30400, Culture=neutral, PublicKeyToken=null
$this
@@ -250,7 +250,7 @@
NoControl
- 506, 7
+ 631, 7
0, 0, 0, 0
@@ -268,7 +268,7 @@
BUT_load
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4711.17948, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4724.30400, Culture=neutral, PublicKeyToken=null
$this
@@ -297,23 +297,32 @@
80
+
+ True
+
+
+ Units
+
+
+ 60
+
+
+ True
+
+
+ Options
+
True
Desc
-
- 57
-
14, 3
-
- 150
-
- 486, 302
+ 611, 302
68
@@ -340,7 +349,7 @@
True
- 506, 169
+ 631, 169
109, 26
@@ -374,13 +383,7 @@ format with no scaling
6, 13
- 625, 305
-
-
- toolTip1
-
-
- System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+ 750, 305
Command
@@ -394,12 +397,30 @@ format with no scaling
System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+ Units
+
+
+ System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Options
+
+
+ System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
Desc
System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+ toolTip1
+
+
+ System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
ConfigRawParams
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigSignalization.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigSignalization.cs
new file mode 100644
index 0000000000..0cb081a5a9
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigSignalization.cs
@@ -0,0 +1,287 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
+using System.Reflection;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ public partial class ConfigSignalization : UserControl, IActivate
+ {
+ [Flags]
+ public enum BeeperMode : byte
+ {
+ Startup = 1,
+ Arm = 2,
+ Disarm = 4,
+ Armed = 8,
+ GPS = 16,
+ Voltage = 32,
+ CH7 = 64,
+ Landing = 128
+ }
+
+ public enum LedStyle : byte
+ {
+ None = 0,
+ Legacy = 1,
+ Features = 2,
+ Disco = 3
+ }
+
+ [Flags]
+ public enum LedMode : byte
+ {
+ [Description("Motor, TODO: add description")]
+ Motor = 1,
+ [Description("GPS, TODO: add description")]
+ GPS = 2,
+ [Description("Aux, TODO: add description")]
+ Aux = 4,
+ [Description("Assign AN5 to LED (0) or beeper (1)")]
+ Beeper = 8,
+ [Description("Low battery - fast flash (0) / oscillate (1)")]
+ Voltage = 16,
+ [Description("Nav blink - motors")]
+ Nav_blink_motor = 32,
+ [Description("Nav blink - GPS")]
+ Nav_blink_GPS = 64
+ }
+
+ public enum LedModeX : byte
+ {
+ Off = 0,
+ On = 1,
+ Armed = 2,
+ GPS = 3,
+ Aux = 4,
+ [Description("Low battery - fast flash")]
+ Low_batt_fast = 5,
+ [Description("Low battery - oscillate")]
+ Low_batt_oscillate = 6,
+ [Description("Nav blink - motors")]
+ Nav_blink_motor = 7,
+ [Description("Nav blink - GPS")]
+ Nav_blink_GPS = 8
+ }
+
+ public ConfigSignalization()
+ {
+ InitializeComponent();
+ }
+
+ public void Activate()
+ {
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
+ {
+ }
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover)
+ {
+ }
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ {
+ Object value;
+ //read BEEPER_MODE
+ try
+ {
+ value = MainV2.comPort.param["BEEPER_MODE"];
+ if (value == null)
+ {
+ Setup.flashMessage.FadeInOut("Reading BEEPER_MODE failed", false);
+ }
+ else
+ {
+ BeeperMode beeper_mode = (BeeperMode)System.Convert.ToSByte(value);
+ CB_beeper_0.Checked = (beeper_mode & BeeperMode.Startup) == BeeperMode.Startup;
+ CB_beeper_1.Checked = (beeper_mode & BeeperMode.Arm) == BeeperMode.Arm;
+ CB_beeper_2.Checked = (beeper_mode & BeeperMode.Disarm) == BeeperMode.Disarm;
+ CB_beeper_3.Checked = (beeper_mode & BeeperMode.Armed) == BeeperMode.Armed;
+ CB_beeper_4.Checked = (beeper_mode & BeeperMode.GPS) == BeeperMode.GPS;
+ CB_beeper_5.Checked = (beeper_mode & BeeperMode.Voltage) == BeeperMode.Voltage;
+ CB_beeper_6.Checked = (beeper_mode & BeeperMode.CH7) == BeeperMode.CH7;
+ CB_beeper_7.Checked = (beeper_mode & BeeperMode.Landing) == BeeperMode.Landing;
+ Setup.flashMessage.FadeInOut("Reading BEEPER_MODE succeed", true);
+ }
+ }
+ catch {
+ Setup.flashMessage.FadeInOut("Reading BEEPER_MODE failed", false);
+ }
+
+ //read LED_STYLE
+ try
+ {
+ value = MainV2.comPort.param["LED_STYLE"];
+ if (value == null)
+ {
+ Setup.flashMessage.FadeInOut("Reading LED_STYLE failed", false);
+ }
+ else
+ {
+ LedStyle led_style = (LedStyle)System.Convert.ToSByte(value);
+ CMB_leds_style.DataSource = Enum.GetValues(typeof(LedStyle));
+ CMB_leds_style.SelectedItem = led_style;
+ Setup.flashMessage.FadeInOut("Reading LED_STYLE succeed", true);
+ }
+ }
+ catch
+ {
+ Setup.flashMessage.FadeInOut("Reading LED_STYLE failed", false);
+ }
+ CMB_led_1.DataSource = Enum.GetValues(typeof(LedMode));
+
+ //read LED_MODE
+ try
+ {
+ value = MainV2.comPort.param["LED_MODE"];
+ if (value == null)
+ {
+ Setup.flashMessage.FadeInOut("Reading LED_MODE failed", false);
+ }
+ else
+ {
+ LedMode led_mode = (LedMode)System.Convert.ToSByte(value);
+ CB_leds_legacy_1.Checked = (led_mode & LedMode.Motor) == LedMode.Motor;
+ CB_leds_legacy_2.Checked = (led_mode & LedMode.GPS) == LedMode.GPS;
+ CB_leds_legacy_3.Checked = (led_mode & LedMode.Aux) == LedMode.Aux;
+ CB_leds_legacy_4.Checked = (led_mode & LedMode.Beeper) == LedMode.Beeper;
+ CB_leds_legacy_5.Checked = (led_mode & LedMode.Voltage) == LedMode.Voltage;
+ CB_leds_legacy_6.Checked = (led_mode & LedMode.Nav_blink_motor) == LedMode.Nav_blink_motor;
+ CB_leds_legacy_7.Checked = (led_mode & LedMode.Nav_blink_GPS) == LedMode.Nav_blink_GPS;
+ Setup.flashMessage.FadeInOut("Reading LED_MODE succeed", true);
+ }
+ }
+ catch
+ {
+ Setup.flashMessage.FadeInOut("Reading LED_MODE failed", false);
+ }
+
+ }
+ }
+
+ private void B_beeper_write_Click(object sender, EventArgs e)
+ {
+ try
+ {
+ BeeperMode beeper_mode =
+ (CB_beeper_0.Checked ? BeeperMode.Startup : 0) |
+ (CB_beeper_1.Checked ? BeeperMode.Arm : 0) |
+ (CB_beeper_2.Checked ? BeeperMode.Disarm : 0) |
+ (CB_beeper_3.Checked ? BeeperMode.Armed : 0) |
+ (CB_beeper_4.Checked ? BeeperMode.GPS : 0) |
+ (CB_beeper_5.Checked ? BeeperMode.Voltage : 0) |
+ (CB_beeper_6.Checked ? BeeperMode.CH7 : 0) |
+ (CB_beeper_7.Checked ? BeeperMode.Landing : 0);
+ if (MainV2.comPort.setParam("BEEPER_MODE", (byte)beeper_mode))
+ {
+ Setup.flashMessage.FadeInOut("Writing BEEPER_MODE succeed", true);
+ }
+ else
+ {
+ Setup.flashMessage.FadeInOut("Writing BEEPER_MODE failed", false);
+ }
+ }
+ catch
+ {
+ Setup.flashMessage.FadeInOut("Writing BEEPER_MODE failed", false);
+ }
+ }
+
+ private void B_leds_write_Click(object sender, EventArgs e)
+ {
+ //write LED_STYLE
+ try
+ {
+ LedStyle led_style = (LedStyle)Enum.Parse(typeof(LedStyle), CMB_leds_style.SelectedItem.ToString());
+ if (MainV2.comPort.setParam("LED_STYLE", (byte)led_style))
+ {
+ Setup.flashMessage.FadeInOut("Writing LED_STYLE succeed", true);
+ }
+ else
+ {
+ Setup.flashMessage.FadeInOut("Writing LED_STYLE failed", false);
+ }
+ }
+ catch
+ {
+ Setup.flashMessage.FadeInOut("Writing LED_STYLE failed", false);
+ }
+
+ //write LED_MODE
+ try
+ {
+ LedMode led_mode =
+ (CB_leds_legacy_1.Checked ? LedMode.Motor : 0) |
+ (CB_leds_legacy_2.Checked ? LedMode.GPS : 0) |
+ (CB_leds_legacy_3.Checked ? LedMode.Aux : 0) |
+ (CB_leds_legacy_4.Checked ? LedMode.Beeper : 0) |
+ (CB_leds_legacy_5.Checked ? LedMode.Voltage : 0) |
+ (CB_leds_legacy_6.Checked ? LedMode.Nav_blink_motor : 0) |
+ (CB_leds_legacy_7.Checked ? LedMode.Nav_blink_GPS : 0);
+ if (MainV2.comPort.setParam("LED_MODE", (byte)led_mode))
+ {
+ Setup.flashMessage.FadeInOut("Writing LED_MODE succeed", true);
+ }
+ else
+ {
+ Setup.flashMessage.FadeInOut("Writing LED_MODE failed", false);
+ }
+ }
+ catch
+ {
+ Setup.flashMessage.FadeInOut("Writing LED_MODE failed", false);
+ }
+
+ }
+
+ private void CMB_leds_style_SelectedIndexChanged(object sender, EventArgs e)
+ {
+ LedStyle led_style = (LedStyle)Enum.Parse(typeof(LedStyle), ((ComboBox)sender).SelectedItem.ToString());
+ switch (led_style)
+ {
+ case LedStyle.None:
+ P_leds_mode_combo.Visible = false;
+ P_leds_mode_legacy.Visible = false;
+ break;
+ case LedStyle.Legacy:
+ P_leds_mode_combo.Visible = false;
+ P_leds_mode_legacy.Visible = true;
+ break;
+ case LedStyle.Features:
+ P_leds_mode_combo.Visible = true;
+ P_leds_mode_legacy.Visible = false;
+ break;
+ case LedStyle.Disco:
+ P_leds_mode_combo.Visible = false;
+ P_leds_mode_legacy.Visible = false;
+ break;
+ }
+ }
+
+ private void CMB_Format(object sender, ListControlConvertEventArgs e)
+ {
+ LedMode item = (LedMode)e.ListItem;
+ e.Value = GetEnumDescription((LedMode)item);
+ }
+
+ public static string GetEnumDescription(Enum value)
+ {
+ FieldInfo fi = value.GetType().GetField(value.ToString());
+
+ DescriptionAttribute[] attributes = (DescriptionAttribute[])fi.GetCustomAttributes(typeof(DescriptionAttribute), false);
+
+ if (attributes != null && attributes.Length > 0)
+ {
+ return attributes[0].Description;
+ }
+ else
+ {
+ return value.ToString();
+ }
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigSignalization.designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigSignalization.designer.cs
new file mode 100644
index 0000000000..40fdfbd922
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigSignalization.designer.cs
@@ -0,0 +1,623 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class ConfigSignalization
+ {
+ ///
+ /// Required designer variable.
+ ///
+ private System.ComponentModel.IContainer components = null;
+
+ ///
+ /// Clean up any resources being used.
+ ///
+ /// true if managed resources should be disposed; otherwise, false.
+ protected override void Dispose(bool disposing)
+ {
+ if (disposing && (components != null))
+ {
+ components.Dispose();
+ }
+ base.Dispose(disposing);
+ }
+
+ #region Component Designer generated code
+
+ ///
+ /// Required method for Designer support - do not modify
+ /// the contents of this method with the code editor.
+ ///
+ private void InitializeComponent()
+ {
+ this.L_beeper_pin = new System.Windows.Forms.Label();
+ this.L_beeper_functions = new System.Windows.Forms.Label();
+ this.CB_beeper_0 = new System.Windows.Forms.CheckBox();
+ this.CB_beeper_1 = new System.Windows.Forms.CheckBox();
+ this.CB_beeper_2 = new System.Windows.Forms.CheckBox();
+ this.CB_beeper_3 = new System.Windows.Forms.CheckBox();
+ this.CB_beeper_4 = new System.Windows.Forms.CheckBox();
+ this.CB_beeper_5 = new System.Windows.Forms.CheckBox();
+ this.CB_beeper_6 = new System.Windows.Forms.CheckBox();
+ this.CB_beeper_7 = new System.Windows.Forms.CheckBox();
+ this.CMB_beeper_pin = new System.Windows.Forms.ComboBox();
+ this.GB_leds = new System.Windows.Forms.GroupBox();
+ this.P_leds_mode_legacy = new System.Windows.Forms.Panel();
+ this.CB_leds_legacy_1 = new System.Windows.Forms.CheckBox();
+ this.CB_leds_legacy_2 = new System.Windows.Forms.CheckBox();
+ this.CB_leds_legacy_3 = new System.Windows.Forms.CheckBox();
+ this.CB_leds_legacy_4 = new System.Windows.Forms.CheckBox();
+ this.CB_leds_legacy_5 = new System.Windows.Forms.CheckBox();
+ this.CB_leds_legacy_6 = new System.Windows.Forms.CheckBox();
+ this.CB_leds_legacy_7 = new System.Windows.Forms.CheckBox();
+ this.CB_leds_legacy_8 = new System.Windows.Forms.CheckBox();
+ this.L_leds_type = new System.Windows.Forms.Label();
+ this.CMB_leds_style = new System.Windows.Forms.ComboBox();
+ this.P_leds_mode_combo = new System.Windows.Forms.Panel();
+ this.L_led_1 = new System.Windows.Forms.Label();
+ this.CMB_led_1 = new System.Windows.Forms.ComboBox();
+ this.L_led_2 = new System.Windows.Forms.Label();
+ this.CMB_led_2 = new System.Windows.Forms.ComboBox();
+ this.L_led_3 = new System.Windows.Forms.Label();
+ this.CMB_led_3 = new System.Windows.Forms.ComboBox();
+ this.L_led_4 = new System.Windows.Forms.Label();
+ this.CMB_led_4 = new System.Windows.Forms.ComboBox();
+ this.L_led_5 = new System.Windows.Forms.Label();
+ this.CMB_led_5 = new System.Windows.Forms.ComboBox();
+ this.L_led_6 = new System.Windows.Forms.Label();
+ this.CMB_led_6 = new System.Windows.Forms.ComboBox();
+ this.L_led_7 = new System.Windows.Forms.Label();
+ this.CMB_led_7 = new System.Windows.Forms.ComboBox();
+ this.L_led_8 = new System.Windows.Forms.Label();
+ this.CMB_led_8 = new System.Windows.Forms.ComboBox();
+ this.GB_beeper = new System.Windows.Forms.GroupBox();
+ this.B_beeper_write = new ArdupilotMega.Controls.MyButton();
+ this.B_leds_write = new ArdupilotMega.Controls.MyButton();
+ this.GB_leds.SuspendLayout();
+ this.P_leds_mode_legacy.SuspendLayout();
+ this.P_leds_mode_combo.SuspendLayout();
+ this.GB_beeper.SuspendLayout();
+ this.SuspendLayout();
+ //
+ // L_beeper_pin
+ //
+ this.L_beeper_pin.AutoSize = true;
+ this.L_beeper_pin.Location = new System.Drawing.Point(6, 31);
+ this.L_beeper_pin.Name = "L_beeper_pin";
+ this.L_beeper_pin.Size = new System.Drawing.Size(186, 13);
+ this.L_beeper_pin.TabIndex = 4;
+ this.L_beeper_pin.Text = "Select pin where beeper is connected\r\n";
+ //
+ // L_beeper_functions
+ //
+ this.L_beeper_functions.AutoSize = true;
+ this.L_beeper_functions.Location = new System.Drawing.Point(6, 75);
+ this.L_beeper_functions.Name = "L_beeper_functions";
+ this.L_beeper_functions.Size = new System.Drawing.Size(105, 13);
+ this.L_beeper_functions.TabIndex = 5;
+ this.L_beeper_functions.Text = "Select when to beep";
+ //
+ // CB_beeper_0
+ //
+ this.CB_beeper_0.AutoSize = true;
+ this.CB_beeper_0.Location = new System.Drawing.Point(9, 91);
+ this.CB_beeper_0.Name = "CB_beeper_0";
+ this.CB_beeper_0.Size = new System.Drawing.Size(75, 17);
+ this.CB_beeper_0.TabIndex = 2;
+ this.CB_beeper_0.Text = "On startup";
+ this.CB_beeper_0.UseVisualStyleBackColor = true;
+ //
+ // CB_beeper_1
+ //
+ this.CB_beeper_1.AutoSize = true;
+ this.CB_beeper_1.Location = new System.Drawing.Point(9, 114);
+ this.CB_beeper_1.Name = "CB_beeper_1";
+ this.CB_beeper_1.Size = new System.Drawing.Size(74, 17);
+ this.CB_beeper_1.TabIndex = 3;
+ this.CB_beeper_1.Text = "On arming";
+ this.CB_beeper_1.UseVisualStyleBackColor = true;
+ //
+ // CB_beeper_2
+ //
+ this.CB_beeper_2.AutoSize = true;
+ this.CB_beeper_2.Location = new System.Drawing.Point(9, 137);
+ this.CB_beeper_2.Name = "CB_beeper_2";
+ this.CB_beeper_2.Size = new System.Drawing.Size(87, 17);
+ this.CB_beeper_2.TabIndex = 4;
+ this.CB_beeper_2.Text = "On disarming";
+ this.CB_beeper_2.UseVisualStyleBackColor = true;
+ //
+ // CB_beeper_3
+ //
+ this.CB_beeper_3.AutoSize = true;
+ this.CB_beeper_3.Location = new System.Drawing.Point(9, 160);
+ this.CB_beeper_3.Name = "CB_beeper_3";
+ this.CB_beeper_3.Size = new System.Drawing.Size(159, 17);
+ this.CB_beeper_3.TabIndex = 5;
+ this.CB_beeper_3.Text = "When armed and on ground";
+ this.CB_beeper_3.UseVisualStyleBackColor = true;
+ //
+ // CB_beeper_4
+ //
+ this.CB_beeper_4.AutoSize = true;
+ this.CB_beeper_4.Location = new System.Drawing.Point(9, 181);
+ this.CB_beeper_4.Name = "CB_beeper_4";
+ this.CB_beeper_4.Size = new System.Drawing.Size(111, 17);
+ this.CB_beeper_4.TabIndex = 6;
+ this.CB_beeper_4.Text = "On GPS home set";
+ this.CB_beeper_4.UseVisualStyleBackColor = true;
+ //
+ // CB_beeper_5
+ //
+ this.CB_beeper_5.AutoSize = true;
+ this.CB_beeper_5.Location = new System.Drawing.Point(9, 204);
+ this.CB_beeper_5.Name = "CB_beeper_5";
+ this.CB_beeper_5.Size = new System.Drawing.Size(97, 17);
+ this.CB_beeper_5.TabIndex = 7;
+ this.CB_beeper_5.Text = "On low voltage";
+ this.CB_beeper_5.UseVisualStyleBackColor = true;
+ //
+ // CB_beeper_6
+ //
+ this.CB_beeper_6.AutoSize = true;
+ this.CB_beeper_6.Location = new System.Drawing.Point(9, 227);
+ this.CB_beeper_6.Name = "CB_beeper_6";
+ this.CB_beeper_6.Size = new System.Drawing.Size(112, 17);
+ this.CB_beeper_6.TabIndex = 8;
+ this.CB_beeper_6.Text = "When CH7 is high";
+ this.CB_beeper_6.UseVisualStyleBackColor = true;
+ //
+ // CB_beeper_7
+ //
+ this.CB_beeper_7.AutoSize = true;
+ this.CB_beeper_7.Location = new System.Drawing.Point(9, 250);
+ this.CB_beeper_7.Name = "CB_beeper_7";
+ this.CB_beeper_7.Size = new System.Drawing.Size(142, 17);
+ this.CB_beeper_7.TabIndex = 9;
+ this.CB_beeper_7.Text = "When in auto land mode";
+ this.CB_beeper_7.UseVisualStyleBackColor = true;
+ //
+ // CMB_beeper_pin
+ //
+ this.CMB_beeper_pin.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+ this.CMB_beeper_pin.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+ this.CMB_beeper_pin.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_beeper_pin.Enabled = false;
+ this.CMB_beeper_pin.FormattingEnabled = true;
+ this.CMB_beeper_pin.Items.AddRange(new object[] {
+ "AN0",
+ "AN1",
+ "AN2",
+ "AN3",
+ "AN4",
+ "AN5",
+ "AN6",
+ "AN7",
+ "AN8",
+ "AN9",
+ "AN10",
+ "AN11",
+ "AN12",
+ "AN13",
+ "AN14",
+ "AN15"});
+ this.CMB_beeper_pin.Location = new System.Drawing.Point(6, 47);
+ this.CMB_beeper_pin.Name = "CMB_beeper_pin";
+ this.CMB_beeper_pin.Size = new System.Drawing.Size(121, 21);
+ this.CMB_beeper_pin.TabIndex = 1;
+ //
+ // GB_leds
+ //
+ this.GB_leds.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom)
+ | System.Windows.Forms.AnchorStyles.Left)));
+ this.GB_leds.Controls.Add(this.P_leds_mode_legacy);
+ this.GB_leds.Controls.Add(this.B_leds_write);
+ this.GB_leds.Controls.Add(this.L_leds_type);
+ this.GB_leds.Controls.Add(this.CMB_leds_style);
+ this.GB_leds.Controls.Add(this.P_leds_mode_combo);
+ this.GB_leds.Location = new System.Drawing.Point(253, 0);
+ this.GB_leds.Name = "GB_leds";
+ this.GB_leds.Size = new System.Drawing.Size(252, 347);
+ this.GB_leds.TabIndex = 10;
+ this.GB_leds.TabStop = false;
+ this.GB_leds.Text = "LEDs settings";
+ //
+ // P_leds_mode_legacy
+ //
+ this.P_leds_mode_legacy.Controls.Add(this.CB_leds_legacy_1);
+ this.P_leds_mode_legacy.Controls.Add(this.CB_leds_legacy_2);
+ this.P_leds_mode_legacy.Controls.Add(this.CB_leds_legacy_3);
+ this.P_leds_mode_legacy.Controls.Add(this.CB_leds_legacy_4);
+ this.P_leds_mode_legacy.Controls.Add(this.CB_leds_legacy_5);
+ this.P_leds_mode_legacy.Controls.Add(this.CB_leds_legacy_6);
+ this.P_leds_mode_legacy.Controls.Add(this.CB_leds_legacy_7);
+ this.P_leds_mode_legacy.Controls.Add(this.CB_leds_legacy_8);
+ this.P_leds_mode_legacy.Location = new System.Drawing.Point(2, 73);
+ this.P_leds_mode_legacy.Name = "P_leds_mode_legacy";
+ this.P_leds_mode_legacy.Size = new System.Drawing.Size(247, 214);
+ this.P_leds_mode_legacy.TabIndex = 23;
+ //
+ // CB_leds_legacy_1
+ //
+ this.CB_leds_legacy_1.AutoSize = true;
+ this.CB_leds_legacy_1.Location = new System.Drawing.Point(7, 2);
+ this.CB_leds_legacy_1.Name = "CB_leds_legacy_1";
+ this.CB_leds_legacy_1.Size = new System.Drawing.Size(53, 17);
+ this.CB_leds_legacy_1.TabIndex = 0;
+ this.CB_leds_legacy_1.Text = "Motor";
+ this.CB_leds_legacy_1.UseVisualStyleBackColor = true;
+ //
+ // CB_leds_legacy_2
+ //
+ this.CB_leds_legacy_2.AutoSize = true;
+ this.CB_leds_legacy_2.Location = new System.Drawing.Point(7, 23);
+ this.CB_leds_legacy_2.Name = "CB_leds_legacy_2";
+ this.CB_leds_legacy_2.Size = new System.Drawing.Size(48, 17);
+ this.CB_leds_legacy_2.TabIndex = 1;
+ this.CB_leds_legacy_2.Text = "GPS";
+ this.CB_leds_legacy_2.UseVisualStyleBackColor = true;
+ //
+ // CB_leds_legacy_3
+ //
+ this.CB_leds_legacy_3.AutoSize = true;
+ this.CB_leds_legacy_3.Location = new System.Drawing.Point(7, 46);
+ this.CB_leds_legacy_3.Name = "CB_leds_legacy_3";
+ this.CB_leds_legacy_3.Size = new System.Drawing.Size(44, 17);
+ this.CB_leds_legacy_3.TabIndex = 2;
+ this.CB_leds_legacy_3.Text = "Aux";
+ this.CB_leds_legacy_3.UseVisualStyleBackColor = true;
+ //
+ // CB_leds_legacy_4
+ //
+ this.CB_leds_legacy_4.AutoSize = true;
+ this.CB_leds_legacy_4.Location = new System.Drawing.Point(7, 69);
+ this.CB_leds_legacy_4.Name = "CB_leds_legacy_4";
+ this.CB_leds_legacy_4.Size = new System.Drawing.Size(60, 17);
+ this.CB_leds_legacy_4.TabIndex = 3;
+ this.CB_leds_legacy_4.Text = "Beeper";
+ this.CB_leds_legacy_4.UseVisualStyleBackColor = true;
+ //
+ // CB_leds_legacy_5
+ //
+ this.CB_leds_legacy_5.AutoSize = true;
+ this.CB_leds_legacy_5.Location = new System.Drawing.Point(7, 92);
+ this.CB_leds_legacy_5.Name = "CB_leds_legacy_5";
+ this.CB_leds_legacy_5.Size = new System.Drawing.Size(219, 17);
+ this.CB_leds_legacy_5.TabIndex = 4;
+ this.CB_leds_legacy_5.Text = "Fast flash (0) / oscillate (1) on low battery";
+ this.CB_leds_legacy_5.UseVisualStyleBackColor = true;
+ //
+ // CB_leds_legacy_6
+ //
+ this.CB_leds_legacy_6.AutoSize = true;
+ this.CB_leds_legacy_6.Location = new System.Drawing.Point(7, 115);
+ this.CB_leds_legacy_6.Name = "CB_leds_legacy_6";
+ this.CB_leds_legacy_6.Size = new System.Drawing.Size(99, 17);
+ this.CB_leds_legacy_6.TabIndex = 5;
+ this.CB_leds_legacy_6.Text = "Motor nav blink";
+ this.CB_leds_legacy_6.UseVisualStyleBackColor = true;
+ //
+ // CB_leds_legacy_7
+ //
+ this.CB_leds_legacy_7.AutoSize = true;
+ this.CB_leds_legacy_7.Location = new System.Drawing.Point(7, 138);
+ this.CB_leds_legacy_7.Name = "CB_leds_legacy_7";
+ this.CB_leds_legacy_7.Size = new System.Drawing.Size(94, 17);
+ this.CB_leds_legacy_7.TabIndex = 6;
+ this.CB_leds_legacy_7.Text = "GPS nav blink";
+ this.CB_leds_legacy_7.UseVisualStyleBackColor = true;
+ //
+ // CB_leds_legacy_8
+ //
+ this.CB_leds_legacy_8.AutoSize = true;
+ this.CB_leds_legacy_8.Enabled = false;
+ this.CB_leds_legacy_8.Location = new System.Drawing.Point(7, 161);
+ this.CB_leds_legacy_8.Name = "CB_leds_legacy_8";
+ this.CB_leds_legacy_8.Size = new System.Drawing.Size(63, 17);
+ this.CB_leds_legacy_8.TabIndex = 7;
+ this.CB_leds_legacy_8.Text = "Unused";
+ this.CB_leds_legacy_8.UseVisualStyleBackColor = true;
+ //
+ // L_leds_type
+ //
+ this.L_leds_type.AutoSize = true;
+ this.L_leds_type.Location = new System.Drawing.Point(6, 31);
+ this.L_leds_type.Name = "L_leds_type";
+ this.L_leds_type.Size = new System.Drawing.Size(139, 13);
+ this.L_leds_type.TabIndex = 10;
+ this.L_leds_type.Text = "Select type of LEDs handler";
+ //
+ // CMB_leds_style
+ //
+ this.CMB_leds_style.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_leds_style.Enabled = false;
+ this.CMB_leds_style.FormattingEnabled = true;
+ this.CMB_leds_style.Location = new System.Drawing.Point(7, 46);
+ this.CMB_leds_style.Name = "CMB_leds_style";
+ this.CMB_leds_style.Size = new System.Drawing.Size(121, 21);
+ this.CMB_leds_style.TabIndex = 21;
+ this.CMB_leds_style.SelectedIndexChanged += new System.EventHandler(this.CMB_leds_style_SelectedIndexChanged);
+ //
+ // P_leds_mode_combo
+ //
+ this.P_leds_mode_combo.Controls.Add(this.L_led_1);
+ this.P_leds_mode_combo.Controls.Add(this.CMB_led_1);
+ this.P_leds_mode_combo.Controls.Add(this.L_led_2);
+ this.P_leds_mode_combo.Controls.Add(this.CMB_led_2);
+ this.P_leds_mode_combo.Controls.Add(this.L_led_3);
+ this.P_leds_mode_combo.Controls.Add(this.CMB_led_3);
+ this.P_leds_mode_combo.Controls.Add(this.L_led_4);
+ this.P_leds_mode_combo.Controls.Add(this.CMB_led_4);
+ this.P_leds_mode_combo.Controls.Add(this.L_led_5);
+ this.P_leds_mode_combo.Controls.Add(this.CMB_led_5);
+ this.P_leds_mode_combo.Controls.Add(this.L_led_6);
+ this.P_leds_mode_combo.Controls.Add(this.CMB_led_6);
+ this.P_leds_mode_combo.Controls.Add(this.L_led_7);
+ this.P_leds_mode_combo.Controls.Add(this.CMB_led_7);
+ this.P_leds_mode_combo.Controls.Add(this.L_led_8);
+ this.P_leds_mode_combo.Controls.Add(this.CMB_led_8);
+ this.P_leds_mode_combo.Location = new System.Drawing.Point(2, 73);
+ this.P_leds_mode_combo.Name = "P_leds_mode_combo";
+ this.P_leds_mode_combo.Size = new System.Drawing.Size(247, 214);
+ this.P_leds_mode_combo.TabIndex = 23;
+ //
+ // L_led_1
+ //
+ this.L_led_1.AutoSize = true;
+ this.L_led_1.Location = new System.Drawing.Point(6, 7);
+ this.L_led_1.Name = "L_led_1";
+ this.L_led_1.Size = new System.Drawing.Size(34, 13);
+ this.L_led_1.TabIndex = 23;
+ this.L_led_1.Text = "LED1";
+ //
+ // CMB_led_1
+ //
+ this.CMB_led_1.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_led_1.FormattingEnabled = true;
+ this.CMB_led_1.Location = new System.Drawing.Point(46, 5);
+ this.CMB_led_1.Name = "CMB_led_1";
+ this.CMB_led_1.Size = new System.Drawing.Size(166, 21);
+ this.CMB_led_1.TabIndex = 24;
+ this.CMB_led_1.Format += new System.Windows.Forms.ListControlConvertEventHandler(this.CMB_Format);
+ //
+ // L_led_2
+ //
+ this.L_led_2.AutoSize = true;
+ this.L_led_2.Location = new System.Drawing.Point(6, 34);
+ this.L_led_2.Name = "L_led_2";
+ this.L_led_2.Size = new System.Drawing.Size(34, 13);
+ this.L_led_2.TabIndex = 25;
+ this.L_led_2.Text = "LED2";
+ //
+ // CMB_led_2
+ //
+ this.CMB_led_2.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_led_2.FormattingEnabled = true;
+ this.CMB_led_2.Location = new System.Drawing.Point(46, 31);
+ this.CMB_led_2.Name = "CMB_led_2";
+ this.CMB_led_2.Size = new System.Drawing.Size(166, 21);
+ this.CMB_led_2.TabIndex = 26;
+ this.CMB_led_2.Format += new System.Windows.Forms.ListControlConvertEventHandler(this.CMB_Format);
+ //
+ // L_led_3
+ //
+ this.L_led_3.AutoSize = true;
+ this.L_led_3.Location = new System.Drawing.Point(6, 61);
+ this.L_led_3.Name = "L_led_3";
+ this.L_led_3.Size = new System.Drawing.Size(34, 13);
+ this.L_led_3.TabIndex = 27;
+ this.L_led_3.Text = "LED3";
+ //
+ // CMB_led_3
+ //
+ this.CMB_led_3.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_led_3.FormattingEnabled = true;
+ this.CMB_led_3.Location = new System.Drawing.Point(46, 57);
+ this.CMB_led_3.Name = "CMB_led_3";
+ this.CMB_led_3.Size = new System.Drawing.Size(166, 21);
+ this.CMB_led_3.TabIndex = 28;
+ this.CMB_led_3.Format += new System.Windows.Forms.ListControlConvertEventHandler(this.CMB_Format);
+ //
+ // L_led_4
+ //
+ this.L_led_4.AutoSize = true;
+ this.L_led_4.Location = new System.Drawing.Point(6, 88);
+ this.L_led_4.Name = "L_led_4";
+ this.L_led_4.Size = new System.Drawing.Size(34, 13);
+ this.L_led_4.TabIndex = 29;
+ this.L_led_4.Text = "LED4";
+ //
+ // CMB_led_4
+ //
+ this.CMB_led_4.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_led_4.FormattingEnabled = true;
+ this.CMB_led_4.Location = new System.Drawing.Point(46, 83);
+ this.CMB_led_4.Name = "CMB_led_4";
+ this.CMB_led_4.Size = new System.Drawing.Size(166, 21);
+ this.CMB_led_4.TabIndex = 30;
+ this.CMB_led_4.Format += new System.Windows.Forms.ListControlConvertEventHandler(this.CMB_Format);
+ //
+ // L_led_5
+ //
+ this.L_led_5.AutoSize = true;
+ this.L_led_5.Location = new System.Drawing.Point(6, 115);
+ this.L_led_5.Name = "L_led_5";
+ this.L_led_5.Size = new System.Drawing.Size(34, 13);
+ this.L_led_5.TabIndex = 31;
+ this.L_led_5.Text = "LED5";
+ //
+ // CMB_led_5
+ //
+ this.CMB_led_5.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_led_5.FormattingEnabled = true;
+ this.CMB_led_5.Location = new System.Drawing.Point(46, 109);
+ this.CMB_led_5.Name = "CMB_led_5";
+ this.CMB_led_5.Size = new System.Drawing.Size(166, 21);
+ this.CMB_led_5.TabIndex = 32;
+ this.CMB_led_5.Format += new System.Windows.Forms.ListControlConvertEventHandler(this.CMB_Format);
+ //
+ // L_led_6
+ //
+ this.L_led_6.AutoSize = true;
+ this.L_led_6.Location = new System.Drawing.Point(6, 142);
+ this.L_led_6.Name = "L_led_6";
+ this.L_led_6.Size = new System.Drawing.Size(34, 13);
+ this.L_led_6.TabIndex = 33;
+ this.L_led_6.Text = "LED6";
+ //
+ // CMB_led_6
+ //
+ this.CMB_led_6.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_led_6.FormattingEnabled = true;
+ this.CMB_led_6.Location = new System.Drawing.Point(46, 135);
+ this.CMB_led_6.Name = "CMB_led_6";
+ this.CMB_led_6.Size = new System.Drawing.Size(166, 21);
+ this.CMB_led_6.TabIndex = 34;
+ this.CMB_led_6.Format += new System.Windows.Forms.ListControlConvertEventHandler(this.CMB_Format);
+ //
+ // L_led_7
+ //
+ this.L_led_7.AutoSize = true;
+ this.L_led_7.Location = new System.Drawing.Point(6, 169);
+ this.L_led_7.Name = "L_led_7";
+ this.L_led_7.Size = new System.Drawing.Size(34, 13);
+ this.L_led_7.TabIndex = 35;
+ this.L_led_7.Text = "LED7";
+ //
+ // CMB_led_7
+ //
+ this.CMB_led_7.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_led_7.FormattingEnabled = true;
+ this.CMB_led_7.Location = new System.Drawing.Point(46, 161);
+ this.CMB_led_7.Name = "CMB_led_7";
+ this.CMB_led_7.Size = new System.Drawing.Size(166, 21);
+ this.CMB_led_7.TabIndex = 36;
+ this.CMB_led_7.Format += new System.Windows.Forms.ListControlConvertEventHandler(this.CMB_Format);
+ //
+ // L_led_8
+ //
+ this.L_led_8.AutoSize = true;
+ this.L_led_8.Location = new System.Drawing.Point(6, 196);
+ this.L_led_8.Name = "L_led_8";
+ this.L_led_8.Size = new System.Drawing.Size(34, 13);
+ this.L_led_8.TabIndex = 37;
+ this.L_led_8.Text = "LED8";
+ //
+ // CMB_led_8
+ //
+ this.CMB_led_8.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_led_8.FormattingEnabled = true;
+ this.CMB_led_8.Location = new System.Drawing.Point(46, 187);
+ this.CMB_led_8.Name = "CMB_led_8";
+ this.CMB_led_8.Size = new System.Drawing.Size(166, 21);
+ this.CMB_led_8.TabIndex = 38;
+ this.CMB_led_8.Format += new System.Windows.Forms.ListControlConvertEventHandler(this.CMB_Format);
+ //
+ // GB_beeper
+ //
+ this.GB_beeper.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom)
+ | System.Windows.Forms.AnchorStyles.Left)));
+ this.GB_beeper.Controls.Add(this.B_beeper_write);
+ this.GB_beeper.Controls.Add(this.L_beeper_pin);
+ this.GB_beeper.Controls.Add(this.CB_beeper_0);
+ this.GB_beeper.Controls.Add(this.CB_beeper_4);
+ this.GB_beeper.Controls.Add(this.CMB_beeper_pin);
+ this.GB_beeper.Controls.Add(this.CB_beeper_5);
+ this.GB_beeper.Controls.Add(this.L_beeper_functions);
+ this.GB_beeper.Controls.Add(this.CB_beeper_6);
+ this.GB_beeper.Controls.Add(this.CB_beeper_1);
+ this.GB_beeper.Controls.Add(this.CB_beeper_7);
+ this.GB_beeper.Controls.Add(this.CB_beeper_3);
+ this.GB_beeper.Controls.Add(this.CB_beeper_2);
+ this.GB_beeper.Location = new System.Drawing.Point(0, 0);
+ this.GB_beeper.Name = "GB_beeper";
+ this.GB_beeper.Size = new System.Drawing.Size(252, 347);
+ this.GB_beeper.TabIndex = 11;
+ this.GB_beeper.TabStop = false;
+ this.GB_beeper.Text = "Beeper settings";
+ //
+ // B_beeper_write
+ //
+ this.B_beeper_write.Location = new System.Drawing.Point(83, 318);
+ this.B_beeper_write.Name = "B_beeper_write";
+ this.B_beeper_write.Size = new System.Drawing.Size(85, 23);
+ this.B_beeper_write.TabIndex = 10;
+ this.B_beeper_write.Text = "Write changes";
+ this.B_beeper_write.UseVisualStyleBackColor = true;
+ this.B_beeper_write.Click += new System.EventHandler(this.B_beeper_write_Click);
+ //
+ // B_leds_write
+ //
+ this.B_leds_write.Location = new System.Drawing.Point(82, 318);
+ this.B_leds_write.Name = "B_leds_write";
+ this.B_leds_write.Size = new System.Drawing.Size(85, 23);
+ this.B_leds_write.TabIndex = 22;
+ this.B_leds_write.Text = "Write changes";
+ this.B_leds_write.UseVisualStyleBackColor = true;
+ this.B_leds_write.Click += new System.EventHandler(this.B_leds_write_Click);
+ //
+ // ConfigSignalization
+ //
+ this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+ this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+ this.Controls.Add(this.GB_beeper);
+ this.Controls.Add(this.GB_leds);
+ this.Name = "ConfigSignalization";
+ this.Size = new System.Drawing.Size(506, 350);
+ this.GB_leds.ResumeLayout(false);
+ this.GB_leds.PerformLayout();
+ this.P_leds_mode_legacy.ResumeLayout(false);
+ this.P_leds_mode_legacy.PerformLayout();
+ this.P_leds_mode_combo.ResumeLayout(false);
+ this.P_leds_mode_combo.PerformLayout();
+ this.GB_beeper.ResumeLayout(false);
+ this.GB_beeper.PerformLayout();
+ this.ResumeLayout(false);
+
+ }
+
+ #endregion
+
+ private System.Windows.Forms.ComboBox CMB_beeper_pin;
+ private System.Windows.Forms.Label L_beeper_pin;
+ private System.Windows.Forms.Label L_beeper_functions;
+ private System.Windows.Forms.CheckBox CB_beeper_0;
+ private System.Windows.Forms.CheckBox CB_beeper_1;
+ private System.Windows.Forms.CheckBox CB_beeper_2;
+ private System.Windows.Forms.CheckBox CB_beeper_3;
+ private System.Windows.Forms.CheckBox CB_beeper_4;
+ private System.Windows.Forms.CheckBox CB_beeper_5;
+ private System.Windows.Forms.CheckBox CB_beeper_6;
+ private System.Windows.Forms.CheckBox CB_beeper_7;
+ private System.Windows.Forms.GroupBox GB_leds;
+ private System.Windows.Forms.GroupBox GB_beeper;
+ private System.Windows.Forms.Label L_leds_type;
+ private System.Windows.Forms.ComboBox CMB_leds_style;
+ private Controls.MyButton B_leds_write;
+ private Controls.MyButton B_beeper_write;
+ private System.Windows.Forms.Panel P_leds_mode_combo;
+ private System.Windows.Forms.Panel P_leds_mode_legacy;
+ private System.Windows.Forms.Label L_led_1;
+ private System.Windows.Forms.ComboBox CMB_led_1;
+ private System.Windows.Forms.Label L_led_2;
+ private System.Windows.Forms.ComboBox CMB_led_2;
+ private System.Windows.Forms.Label L_led_3;
+ private System.Windows.Forms.ComboBox CMB_led_3;
+ private System.Windows.Forms.Label L_led_4;
+ private System.Windows.Forms.ComboBox CMB_led_4;
+ private System.Windows.Forms.Label L_led_5;
+ private System.Windows.Forms.ComboBox CMB_led_5;
+ private System.Windows.Forms.Label L_led_6;
+ private System.Windows.Forms.ComboBox CMB_led_6;
+ private System.Windows.Forms.Label L_led_7;
+ private System.Windows.Forms.ComboBox CMB_led_7;
+ private System.Windows.Forms.Label L_led_8;
+ private System.Windows.Forms.ComboBox CMB_led_8;
+ private System.Windows.Forms.CheckBox CB_leds_legacy_8;
+ private System.Windows.Forms.CheckBox CB_leds_legacy_7;
+ private System.Windows.Forms.CheckBox CB_leds_legacy_6;
+ private System.Windows.Forms.CheckBox CB_leds_legacy_5;
+ private System.Windows.Forms.CheckBox CB_leds_legacy_4;
+ private System.Windows.Forms.CheckBox CB_leds_legacy_3;
+ private System.Windows.Forms.CheckBox CB_leds_legacy_2;
+ private System.Windows.Forms.CheckBox CB_leds_legacy_1;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigSignalization.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigSignalization.resx
new file mode 100644
index 0000000000..7080a7d118
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigSignalization.resx
@@ -0,0 +1,120 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 2.0
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs
index 6d8f4f328b..33878ae97f 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs
@@ -29,9 +29,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
return;
try
{
- if (MainV2.comPort.param["H_SWASH_TYPE"] == null)
+ if (MainV2.comPort.MAV.param["H_SWASH_TYPE"] == null)
{
- CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ CustomMessageBox.Show("Not Available on " + MainV2.comPort.MAV.cs.firmware.ToString());
}
else
{
@@ -45,7 +45,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
try
{
- if (MainV2.comPort.param["H_SV_MAN"].ToString() == "1")
+ if (MainV2.comPort.MAV.param["H_SV_MAN"].ToString() == "1")
{
MainV2.comPort.setParam("H_COL_MIN", int.Parse(H_COL_MIN.Text));
MainV2.comPort.setParam("H_COL_MAX", int.Parse(H_COL_MAX.Text));
@@ -77,7 +77,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
try
{
- if (MainV2.comPort.param["H_SV_MAN"].ToString() == "1")
+ if (MainV2.comPort.MAV.param["H_SV_MAN"].ToString() == "1")
{
MainV2.comPort.setParam("HS4_MIN", int.Parse(HS4_MIN.Text));
MainV2.comPort.setParam("HS4_MAX", int.Parse(HS4_MAX.Text));
@@ -255,9 +255,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
try
{
- MainV2.comPort.setParam("H_COL_MID", MainV2.cs.ch3in);
+ MainV2.comPort.setParam("H_COL_MID", MainV2.comPort.MAV.cs.ch3in);
- H_COL_MID.Text = MainV2.comPort.param["H_COL_MID"].ToString();
+ H_COL_MID.Text = MainV2.comPort.MAV.param["H_COL_MID"].ToString();
}
catch { CustomMessageBox.Show("Set H_COL_MID failed"); }
}
@@ -371,7 +371,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
public void Activate()
{
- if (MainV2.comPort.param["H_GYR_ENABLE"] == null)
+ if (MainV2.comPort.MAV.param["H_GYR_ENABLE"] == null)
{
this.Enabled = false;
return;
@@ -383,26 +383,26 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
timer.Interval = 100;
timer.Start();
- mavlinkNumericUpDown1min.setup(800,1400,1,1,"HS1_MIN",MainV2.comPort.param);
- mavlinkNumericUpDown1max.setup(1600,2200,1,1,"HS1_MAX",MainV2.comPort.param);
- mavlinkNumericUpDown2min.setup(800, 1400, 1, 1, "HS2_MIN", MainV2.comPort.param);
- mavlinkNumericUpDown2max.setup(1600, 2200, 1, 1, "HS2_MAX", MainV2.comPort.param);
- mavlinkNumericUpDown3min.setup(800, 1400, 1, 1, "HS3_MIN", MainV2.comPort.param);
- mavlinkNumericUpDown3max.setup(1600, 2200, 1, 1, "HS3_MAX", MainV2.comPort.param);
+ mavlinkNumericUpDown1min.setup(800,1400,1,1,"HS1_MIN",MainV2.comPort.MAV.param);
+ mavlinkNumericUpDown1max.setup(1600,2200,1,1,"HS1_MAX",MainV2.comPort.MAV.param);
+ mavlinkNumericUpDown2min.setup(800, 1400, 1, 1, "HS2_MIN", MainV2.comPort.MAV.param);
+ mavlinkNumericUpDown2max.setup(1600, 2200, 1, 1, "HS2_MAX", MainV2.comPort.MAV.param);
+ mavlinkNumericUpDown3min.setup(800, 1400, 1, 1, "HS3_MIN", MainV2.comPort.MAV.param);
+ mavlinkNumericUpDown3max.setup(1600, 2200, 1, 1, "HS3_MAX", MainV2.comPort.MAV.param);
- mavlinkNumericUpDownpitchmax.setup(10, 65, 100, 1, "H_PIT_MAX", MainV2.comPort.param);
- mavlinkNumericUpDownrollmax.setup(10, 65, 100, 1, "H_ROL_MAX", MainV2.comPort.param);
+ mavlinkNumericUpDownpitchmax.setup(10, 65, 100, 1, "H_PIT_MAX", MainV2.comPort.MAV.param);
+ mavlinkNumericUpDownrollmax.setup(10, 65, 100, 1, "H_ROL_MAX", MainV2.comPort.MAV.param);
startup = true;
try
{
- if (MainV2.comPort.param.ContainsKey("H_SWASH_TYPE"))
+ if (MainV2.comPort.MAV.param.ContainsKey("H_SWASH_TYPE"))
{
- CCPM.Checked = MainV2.comPort.param["H_SWASH_TYPE"].ToString() == "0" ? true : false;
+ CCPM.Checked = MainV2.comPort.MAV.param["H_SWASH_TYPE"].ToString() == "0" ? true : false;
H_SWASH_TYPE.Checked = !CCPM.Checked;
}
- foreach (string value in MainV2.comPort.param.Keys)
+ foreach (string value in MainV2.comPort.MAV.param.Keys)
{
if (value == "")
continue;
@@ -413,34 +413,34 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (control[0].GetType() == typeof(TextBox))
{
TextBox temp = (TextBox)control[0];
- string option = MainV2.comPort.param[value].ToString();
+ string option = MainV2.comPort.MAV.param[value].ToString();
temp.Text = option;
}
if (control[0].GetType() == typeof(NumericUpDown))
{
NumericUpDown temp = (NumericUpDown)control[0];
- string option = MainV2.comPort.param[value].ToString();
+ string option = MainV2.comPort.MAV.param[value].ToString();
temp.Text = option;
}
if (control[0].GetType() == typeof(CheckBox))
{
CheckBox temp = (CheckBox)control[0];
- string option = MainV2.comPort.param[value].ToString();
+ string option = MainV2.comPort.MAV.param[value].ToString();
temp.Checked = option == "1" ? true : false;
}
if (control[0].GetType() == typeof(MyTrackBar))
{
ArdupilotMega.Controls.MyTrackBar temp = (MyTrackBar)control[0];
- string option = MainV2.comPort.param[value].ToString();
+ string option = MainV2.comPort.MAV.param[value].ToString();
temp.Value = int.Parse(option);
}
}
}
- HS1_REV.Checked = MainV2.comPort.param["HS1_REV"].ToString() == "-1";
- HS2_REV.Checked = MainV2.comPort.param["HS2_REV"].ToString() == "-1";
- HS3_REV.Checked = MainV2.comPort.param["HS3_REV"].ToString() == "-1";
- HS4_REV.Checked = MainV2.comPort.param["HS4_REV"].ToString() == "-1";
+ HS1_REV.Checked = MainV2.comPort.MAV.param["HS1_REV"].ToString() == "-1";
+ HS2_REV.Checked = MainV2.comPort.MAV.param["HS2_REV"].ToString() == "-1";
+ HS3_REV.Checked = MainV2.comPort.MAV.param["HS3_REV"].ToString() == "-1";
+ HS4_REV.Checked = MainV2.comPort.MAV.param["HS4_REV"].ToString() == "-1";
}
catch { }
@@ -451,11 +451,11 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
try
{
- MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
+ MainV2.comPort.MAV.cs.UpdateCurrentSettings(currentStateBindingSource);
}
catch { }
- if (MainV2.comPort.param["H_SV_MAN"] == null || MainV2.comPort.param["H_SV_MAN"].ToString() == "0")
+ if (MainV2.comPort.MAV.param["H_SV_MAN"] == null || MainV2.comPort.MAV.param["H_SV_MAN"].ToString() == "0")
return;
if (HS3.minline == 0)
@@ -464,11 +464,11 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
if (HS4.minline == 0)
HS4.minline = 2200;
- HS3.minline = Math.Min(HS3.minline, (int)MainV2.cs.ch3in);
- HS3.maxline = Math.Max(HS3.maxline, (int)MainV2.cs.ch3in);
+ HS3.minline = Math.Min(HS3.minline, (int)MainV2.comPort.MAV.cs.ch3in);
+ HS3.maxline = Math.Max(HS3.maxline, (int)MainV2.comPort.MAV.cs.ch3in);
- HS4.minline = Math.Min(HS4.minline, (int)MainV2.cs.ch4in);
- HS4.maxline = Math.Max(HS4.maxline, (int)MainV2.cs.ch4in);
+ HS4.minline = Math.Min(HS4.minline, (int)MainV2.comPort.MAV.cs.ch4in);
+ HS4.maxline = Math.Max(HS4.maxline, (int)MainV2.comPort.MAV.cs.ch4in);
if (!inpwmdetect)
{
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
index aa260d7f0c..259c75603b 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
@@ -15,6 +15,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
// remember the last page accessed
static string lastpagename = "";
+ public static Controls.FlashMessage flashMessage = new Controls.FlashMessage();
BackstageView.BackstageViewPage hardware;
BackstageView.BackstageViewPage standardpage;
@@ -24,6 +25,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
InitializeComponent();
ThemeManager.ApplyThemeTo(this);
+ this.Controls.Add(flashMessage);
}
private void Setup_Load(object sender, EventArgs e)
@@ -70,7 +72,7 @@ If you are just setting up 3DR radios, you may continue without connecting.");
{
/****************************** Common **************************/
- if ((MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) || (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) || (MainV2.cs.firmware == MainV2.Firmwares.ArduRover))
+ if ((MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2) || (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane) || (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover))
{
AddBackstageViewPage(new ConfigRadioInput(), "Radio Calibration");
AddBackstageViewPage(new ConfigFlightModes(), "Flight Modes");
@@ -79,7 +81,7 @@ If you are just setting up 3DR radios, you may continue without connecting.");
AddBackstageViewPage(new ConfigBatteryMonitoring(), "Battery Monitor", hardware);
}
- if ((MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) || (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) || (MainV2.cs.firmware == MainV2.Firmwares.ArduRover))
+ if ((MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2) || (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane) || (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover))
{
standardpage = AddBackstageViewPage(new ConfigFriendlyParams { ParameterMode = ParameterMetaDataConstants.Standard }, "Standard Params");
advancedpage = AddBackstageViewPage(new ConfigFriendlyParams { ParameterMode = ParameterMetaDataConstants.Advanced }, "Advanced Params");
@@ -87,8 +89,10 @@ If you are just setting up 3DR radios, you may continue without connecting.");
AddBackstageViewPage(new ConfigRawParams(), "Adv Parameter List", advancedpage);
/******************************HELI **************************/
- if (MainV2.comPort.param["H_GYR_ENABLE"] != null) // heli
+ if (MainV2.comPort.MAV.param["H_GYR_ENABLE"] != null) // heli
{
+ // AddBackstageViewPage(new ConfigSignalization(), "Signalization", hardware);
+
AddBackstageViewPage(new ConfigMount(), "Camera Gimbal", hardware);
AddBackstageViewPage(new ConfigAccelerometerCalibrationQuad(), "ArduCopter Level");
@@ -102,8 +106,10 @@ If you are just setting up 3DR radios, you may continue without connecting.");
// AddBackstageViewPage(new ConfigAP_Limits(), "GeoFence");
}
/****************************** ArduCopter **************************/
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
+ // AddBackstageViewPage(new ConfigSignalization(), "Signalization", hardware);
+
AddBackstageViewPage(new ConfigMount(), "Camera Gimbal", hardware);
AddBackstageViewPage(new ConfigAccelerometerCalibrationQuad(), "ArduCopter Level");
@@ -115,7 +121,7 @@ If you are just setting up 3DR radios, you may continue without connecting.");
AddBackstageViewPage(new ConfigAP_Limits(), "GeoFence");
}
/****************************** ArduPlane **************************/
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
AddBackstageViewPage(new ConfigMount(), "Camera Gimbal", hardware);
@@ -123,12 +129,12 @@ If you are just setting up 3DR radios, you may continue without connecting.");
AddBackstageViewPage(new ConfigArduplane(), "ArduPlane Pids", standardpage);
}
/****************************** ArduRover **************************/
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduRover)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover)
{
//AddBackstageViewPage(new ConfigAccelerometerCalibrationPlane(), "ArduRover Level"));
AddBackstageViewPage(new ConfigArdurover(), "ArduRover Pids", standardpage);
}
- else if (MainV2.cs.firmware == MainV2.Firmwares.Ateryx)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.Ateryx)
{
AddBackstageViewPage(new ConfigAteryxSensors(), "Ateryx Zero Sensors");
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
index c78b9f7cbd..116c12929d 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
@@ -34,7 +34,7 @@ namespace ArdupilotMega.GCSViews
//"http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex"
readonly string oldurl = ("https://meee146-planner.googlecode.com/git-history/!Hash!/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml");
readonly string oldfirmwareurl = ("https://meee146-planner.googlecode.com/git-history/!Hash!/Tools/ArdupilotMegaPlanner/Firmware/!Firmware!");
- string[] oldurls = new string[] { "55ec5eaf662a56044ea25c894d235d17185f0660", "cb5b736976c7ed791ea45675c31f588ecb8228d4", "bcd5239322df38db011f183e48d596f215803838", "8709cc418e00326295abc562530413c0089807a7", "06a64192df594b0f81233dfb1f0214aab2cb2603", "7853ef3fad98e5053f228b7c1748c76858c4d282", "abe930ce723267697542388ef181328f00371f40", "26305d5790333f730cd396afcd08c165cde33ed7", "bc1f26ca40b076e3d06f173adad772fb25aa6512", "dfc5737c5efc1e7b78e908829a097624c273d9d7", "682065db449b6c79d89717908ed8beea1ed6a03a", "b21116847d35472b9ab770408cbeb88ed2ed0a95", "511e00bc89a554aea8768a274bff28af532cd335", "1da56714aa1ed88dcdb078a90d33bcef4eb4315f", "8aa4c7a1ed07648f31335926cc6bcc06c87dc536" };
+ string[] oldurls = new string[] { "bb5ee0e1c3e643e7e359ffb4c8bde34aa7d4f996", "55ec5eaf662a56044ea25c894d235d17185f0660", "cb5b736976c7ed791ea45675c31f588ecb8228d4", "bcd5239322df38db011f183e48d596f215803838", "8709cc418e00326295abc562530413c0089807a7", "06a64192df594b0f81233dfb1f0214aab2cb2603", "7853ef3fad98e5053f228b7c1748c76858c4d282", "abe930ce723267697542388ef181328f00371f40", "26305d5790333f730cd396afcd08c165cde33ed7", "bc1f26ca40b076e3d06f173adad772fb25aa6512", "dfc5737c5efc1e7b78e908829a097624c273d9d7", "682065db449b6c79d89717908ed8beea1ed6a03a", "b21116847d35472b9ab770408cbeb88ed2ed0a95", "511e00bc89a554aea8768a274bff28af532cd335", "1da56714aa1ed88dcdb078a90d33bcef4eb4315f", "8aa4c7a1ed07648f31335926cc6bcc06c87dc536" };
List softwares = new List();
bool flashing = false;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs
index d001d2a114..8b458c00dc 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs
@@ -1116,12 +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);
+ this.splitContainer1.Panel2.Controls.Add(this.TRK_zoom);
//
// zg1
//
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
index 287fc018a0..3a8c17d3e7 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
@@ -235,7 +235,7 @@ namespace ArdupilotMega.GCSViews
int x = 10;
int y = 10;
- object thisBoxed = MainV2.cs;
+ object thisBoxed = MainV2.comPort.MAV.cs;
Type test = thisBoxed.GetType();
foreach (var field in test.GetProperties())
@@ -336,7 +336,7 @@ namespace ArdupilotMega.GCSViews
if (ctls.Length > 0)
{
// set description
- ((QuickView)ctls[0]).desc = MainV2.cs.GetNameandUnit(MainV2.config["quickView" + f].ToString());
+ ((QuickView)ctls[0]).desc = MainV2.comPort.MAV.cs.GetNameandUnit(MainV2.config["quickView" + f].ToString());
// set databinding for value
((QuickView)ctls[0]).DataBindings.Clear();
@@ -351,14 +351,14 @@ namespace ArdupilotMega.GCSViews
Control[] ctls = this.Controls.Find("quickView" + f, true);
if (ctls.Length > 0)
{
- ((QuickView)ctls[0]).desc = MainV2.cs.GetNameandUnit(((QuickView)ctls[0]).desc);
+ ((QuickView)ctls[0]).desc = MainV2.comPort.MAV.cs.GetNameandUnit(((QuickView)ctls[0]).desc);
}
}
catch { }
}
}
- if (MainV2.comPort.param.ContainsKey("BATT_MONITOR") && (float)MainV2.comPort.param["BATT_MONITOR"] != 0)
+ if (MainV2.comPort.MAV.param.ContainsKey("BATT_MONITOR") && (float)MainV2.comPort.MAV.param["BATT_MONITOR"] != 0)
{
hud1.batteryon = true;
}
@@ -490,13 +490,13 @@ namespace ArdupilotMega.GCSViews
//System.Threading.Thread.Sleep(1000);
//comPort.requestDatastream((byte)ArdupilotMega.MAVLink09.MAV_DATA_STREAM.RAW_CONTROLLER, 0); // request servoout
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTENDED_STATUS, MainV2.cs.ratestatus); // mode
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.POSITION, MainV2.cs.rateposition); // request gps
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA1, MainV2.cs.rateattitude); // request attitude
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA2, MainV2.cs.rateattitude); // request vfr
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA3, MainV2.cs.ratesensors); // request extra stuff - tridge
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
- MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, MainV2.cs.raterc); // request rc info
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTENDED_STATUS, MainV2.comPort.MAV.cs.ratestatus); // mode
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.POSITION, MainV2.comPort.MAV.cs.rateposition); // request gps
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA1, MainV2.comPort.MAV.cs.rateattitude); // request attitude
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA2, MainV2.comPort.MAV.cs.rateattitude); // request vfr
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA3, MainV2.comPort.MAV.cs.ratesensors); // request extra stuff - tridge
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.comPort.MAV.cs.ratesensors); // request raw sensor
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, MainV2.comPort.MAV.cs.raterc); // request rc info
}
catch { log.Error("Failed to request rates"); }
lastdata = DateTime.Now.AddSeconds(120); // prevent flooding
@@ -643,8 +643,8 @@ namespace ArdupilotMega.GCSViews
if (ArdupilotMega.Controls.OpenGLtest.instance != null)
{
- ArdupilotMega.Controls.OpenGLtest.instance.rpy = new OpenTK.Vector3(MainV2.cs.roll, MainV2.cs.pitch, MainV2.cs.yaw);
- ArdupilotMega.Controls.OpenGLtest.instance.LocationCenter = new PointLatLngAlt(MainV2.cs.lat, MainV2.cs.lng, MainV2.cs.alt, "here");
+ ArdupilotMega.Controls.OpenGLtest.instance.rpy = new OpenTK.Vector3(MainV2.comPort.MAV.cs.roll, MainV2.comPort.MAV.cs.pitch, MainV2.comPort.MAV.cs.yaw);
+ ArdupilotMega.Controls.OpenGLtest.instance.LocationCenter = new PointLatLngAlt(MainV2.comPort.MAV.cs.lat, MainV2.comPort.MAV.cs.lng, MainV2.comPort.MAV.cs.alt, "here");
}
if (tunning.AddMilliseconds(50) < DateTime.Now && CB_tuning.Checked == true)
@@ -652,25 +652,25 @@ namespace ArdupilotMega.GCSViews
double time = (Environment.TickCount - tickStart) / 1000.0;
if (list1item != null)
- list1.Add(time, (float)list1item.GetValue((object)MainV2.cs, null));
+ list1.Add(time, (float)list1item.GetValue((object)MainV2.comPort.MAV.cs, null));
if (list2item != null)
- list2.Add(time, (float)list2item.GetValue((object)MainV2.cs, null));
+ list2.Add(time, (float)list2item.GetValue((object)MainV2.comPort.MAV.cs, null));
if (list3item != null)
- list3.Add(time, (float)list3item.GetValue((object)MainV2.cs, null));
+ list3.Add(time, (float)list3item.GetValue((object)MainV2.comPort.MAV.cs, null));
if (list4item != null)
- list4.Add(time, (float)list4item.GetValue((object)MainV2.cs, null));
+ list4.Add(time, (float)list4item.GetValue((object)MainV2.comPort.MAV.cs, null));
if (list5item != null)
- list5.Add(time, (float)list5item.GetValue((object)MainV2.cs, null));
+ list5.Add(time, (float)list5item.GetValue((object)MainV2.comPort.MAV.cs, null));
if (list6item != null)
- list6.Add(time, (float)list6item.GetValue((object)MainV2.cs, null));
+ list6.Add(time, (float)list6item.GetValue((object)MainV2.comPort.MAV.cs, null));
if (list7item != null)
- list7.Add(time, (float)list7item.GetValue((object)MainV2.cs, null));
+ list7.Add(time, (float)list7item.GetValue((object)MainV2.comPort.MAV.cs, null));
if (list8item != null)
- list8.Add(time, (float)list8item.GetValue((object)MainV2.cs, null));
+ list8.Add(time, (float)list8item.GetValue((object)MainV2.comPort.MAV.cs, null));
if (list9item != null)
- list9.Add(time, (float)list9item.GetValue((object)MainV2.cs, null));
+ list9.Add(time, (float)list9item.GetValue((object)MainV2.comPort.MAV.cs, null));
if (list10item != null)
- list10.Add(time, (float)list10item.GetValue((object)MainV2.cs, null));
+ list10.Add(time, (float)list10item.GetValue((object)MainV2.comPort.MAV.cs, null));
}
if (tracklast.AddSeconds(1) < DateTime.Now)
@@ -687,7 +687,7 @@ namespace ArdupilotMega.GCSViews
routes.Routes.Add(route);
}
- PointLatLng currentloc = new PointLatLng(MainV2.cs.lat, MainV2.cs.lng);
+ PointLatLng currentloc = new PointLatLng(MainV2.comPort.MAV.cs.lat, MainV2.comPort.MAV.cs.lng);
gMapControl1.HoldInvalidation = true;
@@ -704,7 +704,7 @@ namespace ArdupilotMega.GCSViews
// trackPoints.RemoveRange(0, trackPoints.Count - int.Parse(MainV2.config["NUM_tracklength"].ToString()));
route.Points.RemoveRange(0, route.Points.Count - int.Parse(MainV2.config["NUM_tracklength"].ToString()));
}
- if (MainV2.cs.lat != 0)
+ if (MainV2.comPort.MAV.cs.lat != 0)
{
// trackPoints.Add(currentloc);
route.Points.Add(currentloc);
@@ -734,7 +734,7 @@ namespace ArdupilotMega.GCSViews
//Console.WriteLine("Doing FD WP's");
updateMissionRouteMarkers();
- foreach (MAVLink.mavlink_mission_item_t plla in MainV2.comPort.wps.Values)
+ foreach (MAVLink.mavlink_mission_item_t plla in MainV2.comPort.MAV.wps.Values)
{
if (plla.x == 0 || plla.y == 0)
continue;
@@ -774,22 +774,22 @@ namespace ArdupilotMega.GCSViews
routes.Markers.Add(new GMapMarkerCross(currentloc));
}
- if (MainV2.cs.mode.ToLower() == "guided" && MainV2.comPort.GuidedMode.x != 0)
+ if (MainV2.comPort.MAV.cs.mode.ToLower() == "guided" && MainV2.comPort.MAV.GuidedMode.x != 0)
{
- addpolygonmarker("Guided Mode", MainV2.comPort.GuidedMode.y, MainV2.comPort.GuidedMode.x, (int)MainV2.comPort.GuidedMode.z, Color.Blue, routes);
+ addpolygonmarker("Guided Mode", MainV2.comPort.MAV.GuidedMode.y, MainV2.comPort.MAV.GuidedMode.x, (int)MainV2.comPort.MAV.GuidedMode.z, Color.Blue, routes);
}
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
- routes.Markers[0] = (new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing, gMapControl1) { ToolTipText = MainV2.cs.alt.ToString("0"), ToolTipMode = MarkerTooltipMode.Always });
+ routes.Markers[0] = (new GMapMarkerPlane(currentloc, MainV2.comPort.MAV.cs.yaw, MainV2.comPort.MAV.cs.groundcourse, MainV2.comPort.MAV.cs.nav_bearing, MainV2.comPort.MAV.cs.target_bearing, gMapControl1) { ToolTipText = MainV2.comPort.MAV.cs.alt.ToString("0"), ToolTipMode = MarkerTooltipMode.Always });
}
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduRover)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover)
{
- routes.Markers[0] = (new GMapMarkerRover(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing, gMapControl1));
+ routes.Markers[0] = (new GMapMarkerRover(currentloc, MainV2.comPort.MAV.cs.yaw, MainV2.comPort.MAV.cs.groundcourse, MainV2.comPort.MAV.cs.nav_bearing, MainV2.comPort.MAV.cs.target_bearing, gMapControl1));
}
else
{
- routes.Markers[0] = (new GMapMarkerQuad(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing));
+ routes.Markers[0] = (new GMapMarkerQuad(currentloc, MainV2.comPort.MAV.cs.yaw, MainV2.comPort.MAV.cs.groundcourse, MainV2.comPort.MAV.cs.nav_bearing));
}
if (route.Points[route.Points.Count - 1].Lat != 0 && (mapupdate.AddSeconds(3) < DateTime.Now) && CHK_autopan.Checked)
@@ -823,7 +823,7 @@ namespace ArdupilotMega.GCSViews
{
this.Invoke((System.Windows.Forms.MethodInvoker)delegate()
{
- gMapControl1.Bearing = (int)MainV2.cs.yaw;
+ gMapControl1.Bearing = (int)MainV2.comPort.MAV.cs.yaw;
});
}
@@ -889,7 +889,7 @@ namespace ArdupilotMega.GCSViews
{
try
{
- MainV2.cs.UpdateCurrentSettings(bindingSource1);
+ MainV2.comPort.MAV.cs.UpdateCurrentSettings(bindingSource1);
}
catch { }
});
@@ -951,7 +951,7 @@ namespace ArdupilotMega.GCSViews
mBorders.InnerMarker = m;
try
{
- mBorders.wprad = (int)(float.Parse(ArdupilotMega.MainV2.config["TXT_WPRad"].ToString()) / MainV2.cs.multiplierdist);
+ mBorders.wprad = (int)(float.Parse(ArdupilotMega.MainV2.config["TXT_WPRad"].ToString()) / MainV2.comPort.MAV.cs.multiplierdist);
}
catch { }
mBorders.MainMap = gMapControl1;
@@ -1243,11 +1243,11 @@ namespace ArdupilotMega.GCSViews
return;
}
- if (MainV2.comPort.GuidedMode.z == 0)
+ if (MainV2.comPort.MAV.GuidedMode.z == 0)
{
flyToHereAltToolStripMenuItem_Click(null, null);
- if (MainV2.comPort.GuidedMode.z == 0)
+ if (MainV2.comPort.MAV.GuidedMode.z == 0)
return;
}
@@ -1260,7 +1260,7 @@ namespace ArdupilotMega.GCSViews
Locationwp gotohere = new Locationwp();
gotohere.id = (byte)MAVLink.MAV_CMD.WAYPOINT;
- gotohere.alt = (float)(MainV2.comPort.GuidedMode.z); // back to m
+ gotohere.alt = (float)(MainV2.comPort.MAV.GuidedMode.z); // back to m
gotohere.lat = (float)(gotolocation.Lat);
gotohere.lng = (float)(gotolocation.Lng);
@@ -1317,7 +1317,7 @@ namespace ArdupilotMega.GCSViews
marker = new GMapMarkerRect(point);
marker.ToolTip = new GMapToolTip(marker);
marker.ToolTipMode = MarkerTooltipMode.Always;
- marker.ToolTipText = "Dist to Home: " + ((gMapControl1.Manager.GetDistance(point, MainV2.cs.HomeLocation.Point()) * 1000) * MainV2.cs.multiplierdist).ToString("0");
+ marker.ToolTipText = "Dist to Home: " + ((gMapControl1.Manager.GetDistance(point, MainV2.comPort.MAV.cs.HomeLocation.Point()) * 1000) * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
routes.Markers.Add(marker);
}
@@ -1332,20 +1332,20 @@ namespace ArdupilotMega.GCSViews
}
// QUAD
- if (MainV2.comPort.param.ContainsKey("WP_SPEED_MAX"))
+ if (MainV2.comPort.MAV.param.ContainsKey("WP_SPEED_MAX"))
{
- modifyandSetSpeed.Value = (decimal)((float)MainV2.comPort.param["WP_SPEED_MAX"] / 100.0);
+ modifyandSetSpeed.Value = (decimal)((float)MainV2.comPort.MAV.param["WP_SPEED_MAX"] / 100.0);
} // plane with airspeed
- else if (MainV2.comPort.param.ContainsKey("TRIM_ARSPD_CM") && MainV2.comPort.param.ContainsKey("ARSPD_ENABLE")
- && MainV2.comPort.param.ContainsKey("ARSPD_USE") && (float)MainV2.comPort.param["ARSPD_ENABLE"] == 1
- && (float)MainV2.comPort.param["ARSPD_USE"] == 1)
+ else if (MainV2.comPort.MAV.param.ContainsKey("TRIM_ARSPD_CM") && MainV2.comPort.MAV.param.ContainsKey("ARSPD_ENABLE")
+ && MainV2.comPort.MAV.param.ContainsKey("ARSPD_USE") && (float)MainV2.comPort.MAV.param["ARSPD_ENABLE"] == 1
+ && (float)MainV2.comPort.MAV.param["ARSPD_USE"] == 1)
{
- modifyandSetSpeed.Value = (decimal)((float)MainV2.comPort.param["TRIM_ARSPD_CM"] / 100.0);
+ modifyandSetSpeed.Value = (decimal)((float)MainV2.comPort.MAV.param["TRIM_ARSPD_CM"] / 100.0);
} // plane without airspeed
- else if (MainV2.comPort.param.ContainsKey("TRIM_THROTTLE") && MainV2.comPort.param.ContainsKey("ARSPD_USE")
- && (float)MainV2.comPort.param["ARSPD_USE"] == 0)
+ else if (MainV2.comPort.MAV.param.ContainsKey("TRIM_THROTTLE") && MainV2.comPort.MAV.param.ContainsKey("ARSPD_USE")
+ && (float)MainV2.comPort.MAV.param["ARSPD_USE"] == 0)
{
- modifyandSetSpeed.Value = (decimal)(float)MainV2.comPort.param["TRIM_THROTTLE"]; // percent
+ modifyandSetSpeed.Value = (decimal)(float)MainV2.comPort.MAV.param["TRIM_THROTTLE"]; // percent
}
MainV2.comPort.ParamListChanged += FlightData_ParentChanged;
@@ -1358,13 +1358,13 @@ namespace ArdupilotMega.GCSViews
private void BUT_Homealt_Click(object sender, EventArgs e)
{
- if (MainV2.cs.altoffsethome != 0)
+ if (MainV2.comPort.MAV.cs.altoffsethome != 0)
{
- MainV2.cs.altoffsethome = 0;
+ MainV2.comPort.MAV.cs.altoffsethome = 0;
}
else
{
- MainV2.cs.altoffsethome = MainV2.cs.alt / MainV2.cs.multiplierdist;
+ MainV2.comPort.MAV.cs.altoffsethome = MainV2.comPort.MAV.cs.alt / MainV2.comPort.MAV.cs.multiplierdist;
}
}
@@ -1542,9 +1542,9 @@ namespace ArdupilotMega.GCSViews
CMB_setwp.Items.Add("0 (Home)");
- if (MainV2.comPort.param["CMD_TOTAL"] != null)
+ if (MainV2.comPort.MAV.param["CMD_TOTAL"] != null)
{
- int wps = int.Parse(MainV2.comPort.param["CMD_TOTAL"].ToString());
+ int wps = int.Parse(MainV2.comPort.MAV.param["CMD_TOTAL"].ToString());
for (int z = 1; z <= wps; z++)
{
CMB_setwp.Items.Add(z.ToString());
@@ -1579,9 +1579,9 @@ namespace ArdupilotMega.GCSViews
try
{
((Button)sender).Enabled = false;
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
MainV2.comPort.setMode("Manual");
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
MainV2.comPort.setMode("Stabilize");
}
@@ -1763,7 +1763,7 @@ namespace ArdupilotMega.GCSViews
y += 20;
- object thisBoxed = MainV2.cs;
+ object thisBoxed = MainV2.comPort.MAV.cs;
Type test = thisBoxed.GetType();
foreach (var field in test.GetProperties())
@@ -1844,7 +1844,7 @@ namespace ArdupilotMega.GCSViews
int x = 10;
int y = 10;
- object thisBoxed = MainV2.cs;
+ object thisBoxed = MainV2.comPort.MAV.cs;
Type test = thisBoxed.GetType();
foreach (var field in test.GetProperties())
@@ -1898,7 +1898,7 @@ namespace ArdupilotMega.GCSViews
void addHudUserItem(ref HUD.Custom cust, CheckBox sender)
{
- setupPropertyInfo(ref cust.Item, (sender).Name, MainV2.cs);
+ setupPropertyInfo(ref cust.Item, (sender).Name, MainV2.comPort.MAV.cs);
hud1.CustomItems.Add((sender).Name, cust);
@@ -1952,7 +1952,7 @@ namespace ArdupilotMega.GCSViews
{
if (list1item == null)
{
- if (setupPropertyInfo(ref list1item, ((CheckBox)sender).Name, MainV2.cs))
+ if (setupPropertyInfo(ref list1item, ((CheckBox)sender).Name, MainV2.comPort.MAV.cs))
{
list1.Clear();
list1curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list1, Color.Red, SymbolType.None);
@@ -1960,7 +1960,7 @@ namespace ArdupilotMega.GCSViews
}
else if (list2item == null)
{
- if (setupPropertyInfo(ref list2item, ((CheckBox)sender).Name, MainV2.cs))
+ if (setupPropertyInfo(ref list2item, ((CheckBox)sender).Name, MainV2.comPort.MAV.cs))
{
list2.Clear();
list2curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list2, Color.Blue, SymbolType.None);
@@ -1968,7 +1968,7 @@ namespace ArdupilotMega.GCSViews
}
else if (list3item == null)
{
- if (setupPropertyInfo(ref list3item, ((CheckBox)sender).Name, MainV2.cs))
+ if (setupPropertyInfo(ref list3item, ((CheckBox)sender).Name, MainV2.comPort.MAV.cs))
{
list3.Clear();
list3curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list3, Color.Green, SymbolType.None);
@@ -1976,7 +1976,7 @@ namespace ArdupilotMega.GCSViews
}
else if (list4item == null)
{
- if (setupPropertyInfo(ref list4item, ((CheckBox)sender).Name, MainV2.cs))
+ if (setupPropertyInfo(ref list4item, ((CheckBox)sender).Name, MainV2.comPort.MAV.cs))
{
list4.Clear();
list4curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list4, Color.Orange, SymbolType.None);
@@ -1984,7 +1984,7 @@ namespace ArdupilotMega.GCSViews
}
else if (list5item == null)
{
- if (setupPropertyInfo(ref list5item, ((CheckBox)sender).Name, MainV2.cs))
+ if (setupPropertyInfo(ref list5item, ((CheckBox)sender).Name, MainV2.comPort.MAV.cs))
{
list5.Clear();
list5curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list5, Color.Yellow, SymbolType.None);
@@ -1992,7 +1992,7 @@ namespace ArdupilotMega.GCSViews
}
else if (list6item == null)
{
- if (setupPropertyInfo(ref list6item, ((CheckBox)sender).Name, MainV2.cs))
+ if (setupPropertyInfo(ref list6item, ((CheckBox)sender).Name, MainV2.comPort.MAV.cs))
{
list6.Clear();
list6curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list6, Color.Magenta, SymbolType.None);
@@ -2000,7 +2000,7 @@ namespace ArdupilotMega.GCSViews
}
else if (list7item == null)
{
- if (setupPropertyInfo(ref list7item, ((CheckBox)sender).Name, MainV2.cs))
+ if (setupPropertyInfo(ref list7item, ((CheckBox)sender).Name, MainV2.comPort.MAV.cs))
{
list7.Clear();
list7curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list7, Color.Purple, SymbolType.None);
@@ -2008,7 +2008,7 @@ namespace ArdupilotMega.GCSViews
}
else if (list8item == null)
{
- if (setupPropertyInfo(ref list8item, ((CheckBox)sender).Name, MainV2.cs))
+ if (setupPropertyInfo(ref list8item, ((CheckBox)sender).Name, MainV2.comPort.MAV.cs))
{
list8.Clear();
list8curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list8, Color.LimeGreen, SymbolType.None);
@@ -2016,7 +2016,7 @@ namespace ArdupilotMega.GCSViews
}
else if (list9item == null)
{
- if (setupPropertyInfo(ref list9item, ((CheckBox)sender).Name, MainV2.cs))
+ if (setupPropertyInfo(ref list9item, ((CheckBox)sender).Name, MainV2.comPort.MAV.cs))
{
list9.Clear();
list9curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list9, Color.Cyan, SymbolType.None);
@@ -2024,7 +2024,7 @@ namespace ArdupilotMega.GCSViews
}
else if (list10item == null)
{
- if (setupPropertyInfo(ref list10item, ((CheckBox)sender).Name, MainV2.cs))
+ if (setupPropertyInfo(ref list10item, ((CheckBox)sender).Name, MainV2.comPort.MAV.cs))
{
list10.Clear();
list10curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list10, Color.Violet, SymbolType.None);
@@ -2119,10 +2119,10 @@ namespace ArdupilotMega.GCSViews
return;
}
- string alt = (100 * MainV2.cs.multiplierdist).ToString("0");
+ string alt = (100 * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
Common.InputBox("Enter Alt", "Enter Target Alt (absolute)", ref alt);
- int intalt = (int)(100 * MainV2.cs.multiplierdist);
+ int intalt = (int)(100 * MainV2.comPort.MAV.cs.multiplierdist);
if (!int.TryParse(alt, out intalt))
{
CustomMessageBox.Show("Bad Alt");
@@ -2136,7 +2136,7 @@ namespace ArdupilotMega.GCSViews
}
MainV2.comPort.setMountConfigure(MAVLink.MAV_MOUNT_MODE.GPS_POINT, true, true, true);
- MainV2.comPort.setMountControl(gotolocation.Lat, gotolocation.Lng, (int)(intalt / MainV2.cs.multiplierdist), true);
+ MainV2.comPort.setMountControl(gotolocation.Lat, gotolocation.Lng, (int)(intalt / MainV2.comPort.MAV.cs.multiplierdist), true);
}
@@ -2305,7 +2305,7 @@ print 'Roll complete'
int x = 10;
int y = 10;
- object thisBoxed = MainV2.cs;
+ object thisBoxed = MainV2.comPort.MAV.cs;
Type test = thisBoxed.GetType();
foreach (var field in test.GetProperties())
@@ -2326,7 +2326,7 @@ print 'Roll complete'
CheckBox chk_box = new CheckBox();
- if (((QuickView)sender).Tag == field.Name)
+ if (((QuickView)sender).Tag.ToString() == field.Name)
chk_box.Checked = true;
chk_box.Text = field.Name;
@@ -2366,7 +2366,7 @@ print 'Roll complete'
string desc = ((CheckBox)sender).Name;
((QuickView)((CheckBox)sender).Tag).Tag = desc;
- desc = MainV2.cs.GetNameandUnit(desc);
+ desc = MainV2.comPort.MAV.cs.GetNameandUnit(desc);
((QuickView)((CheckBox)sender).Tag).desc = desc;
@@ -2383,13 +2383,13 @@ print 'Roll complete'
{
string alt = "100";
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
- alt = (10 * MainV2.cs.multiplierdist).ToString("0");
+ alt = (10 * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
}
else
{
- alt = (100 * MainV2.cs.multiplierdist).ToString("0");
+ alt = (100 * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
}
if (MainV2.config.ContainsKey("guided_alt"))
@@ -2400,18 +2400,18 @@ print 'Roll complete'
MainV2.config["guided_alt"] = alt;
- int intalt = (int)(100 * MainV2.cs.multiplierdist);
+ int intalt = (int)(100 * MainV2.comPort.MAV.cs.multiplierdist);
if (!int.TryParse(alt, out intalt))
{
CustomMessageBox.Show("Bad Alt");
return;
}
- MainV2.comPort.GuidedMode.z = intalt;
+ MainV2.comPort.MAV.GuidedMode.z = intalt;
- if (MainV2.cs.mode == "Guided")
+ if (MainV2.comPort.MAV.cs.mode == "Guided")
{
- MainV2.comPort.setGuidedModeWP(new Locationwp() { alt = (float)MainV2.comPort.GuidedMode.z, lat = (float)MainV2.comPort.GuidedMode.x, lng = (float)MainV2.comPort.GuidedMode.y });
+ MainV2.comPort.setGuidedModeWP(new Locationwp() { alt = (float)MainV2.comPort.MAV.GuidedMode.z, lat = (float)MainV2.comPort.MAV.GuidedMode.x, lng = (float)MainV2.comPort.MAV.GuidedMode.y });
}
}
@@ -2511,7 +2511,7 @@ print 'Roll complete'
// arm the MAV
try
{
- bool ans = MainV2.comPort.doARM(MainV2.cs.armed);
+ bool ans = MainV2.comPort.doARM(MainV2.comPort.MAV.cs.armed);
if (ans == false)
CustomMessageBox.Show("Error: Arm message rejected by MAV");
}
@@ -2525,10 +2525,10 @@ print 'Roll complete'
int newalt = (int)modifyandSetAlt.Value;
try
{
- MainV2.comPort.setNewWPAlt(new Locationwp() { alt = newalt / MainV2.cs.multiplierdist });
+ MainV2.comPort.setNewWPAlt(new Locationwp() { alt = newalt / MainV2.comPort.MAV.cs.multiplierdist });
}
- catch { CustomMessageBox.Show("Error sending command"); }
- //MainV2.comPort.setNextWPTargetAlt((ushort)MainV2.cs.wpno, newalt);
+ catch { CustomMessageBox.Show("Error sending new Alt"); }
+ //MainV2.comPort.setNextWPTargetAlt((ushort)MainV2.comPort.MAV.cs.wpno, newalt);
}
private void gMapControl1_MouseLeave(object sender, EventArgs e)
@@ -2543,32 +2543,32 @@ print 'Roll complete'
private void modifyandSetSpeed_Click(object sender, EventArgs e)
{
// QUAD
- if (MainV2.comPort.param.ContainsKey("WP_SPEED_MAX"))
+ if (MainV2.comPort.MAV.param.ContainsKey("WP_SPEED_MAX"))
{
try
{
MainV2.comPort.setParam("WP_SPEED_MAX", ((float)modifyandSetSpeed.Value * 100.0f));
}
- catch { CustomMessageBox.Show("Error sending command"); }
+ catch { CustomMessageBox.Show("Error sending WP_SPEED_MAX command"); }
} // plane with airspeed
- else if (MainV2.comPort.param.ContainsKey("TRIM_ARSPD_CM") && MainV2.comPort.param.ContainsKey("ARSPD_ENABLE")
- && MainV2.comPort.param.ContainsKey("ARSPD_USE") && (float)MainV2.comPort.param["ARSPD_ENABLE"] == 1
- && (float)MainV2.comPort.param["ARSPD_USE"] == 1)
+ else if (MainV2.comPort.MAV.param.ContainsKey("TRIM_ARSPD_CM") && MainV2.comPort.MAV.param.ContainsKey("ARSPD_ENABLE")
+ && MainV2.comPort.MAV.param.ContainsKey("ARSPD_USE") && (float)MainV2.comPort.MAV.param["ARSPD_ENABLE"] == 1
+ && (float)MainV2.comPort.MAV.param["ARSPD_USE"] == 1)
{
try
{
MainV2.comPort.setParam("TRIM_ARSPD_CM", ((float)modifyandSetSpeed.Value * 100.0f));
}
- catch { CustomMessageBox.Show("Error sending command"); }
+ catch { CustomMessageBox.Show("Error sending TRIM_ARSPD_CM command"); }
} // plane without airspeed
- else if (MainV2.comPort.param.ContainsKey("TRIM_THROTTLE") && MainV2.comPort.param.ContainsKey("ARSPD_USE")
- && (float)MainV2.comPort.param["ARSPD_USE"] == 0)
+ else if (MainV2.comPort.MAV.param.ContainsKey("TRIM_THROTTLE") && MainV2.comPort.MAV.param.ContainsKey("ARSPD_USE")
+ && (float)MainV2.comPort.MAV.param["ARSPD_USE"] == 0)
{
try
{
MainV2.comPort.setParam("TRIM_THROTTLE", (float)modifyandSetSpeed.Value);
}
- catch { CustomMessageBox.Show("Error sending command"); }
+ catch { CustomMessageBox.Show("Error sending TRIM_THROTTLE command"); }
}
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
index a5414c30f1..73d54c83a9 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
@@ -244,7 +244,7 @@
hud1
- ArdupilotMega.Controls.HUD, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.HUD, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
SubMainLeft.Panel1
@@ -283,7 +283,7 @@
quickView6
- ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabQuick
@@ -307,7 +307,7 @@
quickView5
- ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabQuick
@@ -331,7 +331,7 @@
quickView4
- ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabQuick
@@ -355,7 +355,7 @@
quickView3
- ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabQuick
@@ -379,7 +379,7 @@
quickView2
- ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabQuick
@@ -409,7 +409,7 @@
quickView1
- ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabQuick
@@ -457,7 +457,7 @@
modifyandSetSpeed
- ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -478,7 +478,7 @@
modifyandSetAlt
- ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -511,7 +511,7 @@
BUT_ARM
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -538,7 +538,7 @@
BUT_script
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -568,7 +568,7 @@
BUT_joystick
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -598,7 +598,7 @@
BUT_quickmanual
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -628,7 +628,7 @@
BUT_quickrtl
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -658,7 +658,7 @@
BUT_quickauto
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -712,7 +712,7 @@
BUT_setwp
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -763,7 +763,7 @@
BUT_setmode
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -793,7 +793,7 @@
BUT_clear_track
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -844,7 +844,7 @@
BUT_Homealt
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -874,7 +874,7 @@
BUT_RAWSensor
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -904,7 +904,7 @@
BUTrestartmission
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -934,7 +934,7 @@
BUTactiondo
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabActions
@@ -988,7 +988,7 @@
Gvspeed
- AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabGauges
@@ -1018,7 +1018,7 @@
Gheading
- ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabGauges
@@ -1048,7 +1048,7 @@
Galt
- AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabGauges
@@ -1081,7 +1081,7 @@
Gspeed
- AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabGauges
@@ -1165,7 +1165,7 @@
lbl_playbackspeed
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabTLogs
@@ -1192,7 +1192,7 @@
lbl_logpercent
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabTLogs
@@ -1219,7 +1219,7 @@
NUM_playbackspeed
- ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabTLogs
@@ -1246,7 +1246,7 @@
BUT_log2kml
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabTLogs
@@ -1300,7 +1300,7 @@
BUT_playlog
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabTLogs
@@ -1327,7 +1327,7 @@
BUT_loadtelem
- ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
tabTLogs
@@ -1491,6 +1491,132 @@
0
+
+ NoControl
+
+
+ 4, 3
+
+
+ 46, 12
+
+
+ 68
+
+
+ Dir: 0
+
+
+ Estimated Wind Direction
+
+
+ lbl_winddir
+
+
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, 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.4723.32619, 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.4723.32619, 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.4723.32619, Culture=neutral, PublicKeyToken=null
+
+
+ splitContainer1.Panel2
+
+
+ 3
+
Fill
@@ -1655,13 +1781,13 @@
gMapControl1
- ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
splitContainer1.Panel2
- 0
+ 4
Right
@@ -1682,138 +1808,12 @@
TRK_zoom
- ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4723.32619, 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.4716.12475, 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.4716.12475, 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.4716.12475, 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.4716.12475, Culture=neutral, PublicKeyToken=null
-
-
- splitContainer1.Panel2
-
-
5
@@ -1871,7 +1871,7 @@
TXT_lat
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
panel1
@@ -1928,7 +1928,7 @@
label1
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
panel1
@@ -1958,7 +1958,7 @@
TXT_long
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
panel1
@@ -1988,7 +1988,7 @@
TXT_alt
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
panel1
@@ -2279,6 +2279,6 @@
FlightData
- System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4716.12475, Culture=neutral, PublicKeyToken=null
+ System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4723.32619, Culture=neutral, PublicKeyToken=null
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
index 7036fb8b4d..cee0ca4d5a 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
@@ -174,7 +174,7 @@ namespace ArdupilotMega.GCSViews
if (pointno == "Tracker Home")
{
- MainV2.cs.TrackerLocation = new PointLatLngAlt(lat, lng, alt, "");
+ MainV2.comPort.MAV.cs.TrackerLocation = new PointLatLngAlt(lat, lng, alt, "");
return;
}
@@ -249,7 +249,7 @@ namespace ArdupilotMega.GCSViews
cell.Value = alt.ToString();
if (ans == 0) // default
cell.Value = 50;
- if (ans == 0 && MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ if (ans == 0 && MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
cell.Value = 15;
// online verify height
if (isonline && CHK_geheight.Checked)
@@ -495,11 +495,11 @@ namespace ArdupilotMega.GCSViews
{
reader.Read();
reader.ReadStartElement("CMD");
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
reader.ReadToFollowing("APM");
}
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduRover)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover)
{
reader.ReadToFollowing("APRover");
}
@@ -595,13 +595,13 @@ namespace ArdupilotMega.GCSViews
config(false);
- if (MainV2.cs.HomeLocation.Lat != 0 && MainV2.cs.HomeLocation.Lng != 0)
+ if (MainV2.comPort.MAV.cs.HomeLocation.Lat != 0 && MainV2.comPort.MAV.cs.HomeLocation.Lng != 0)
{
- TXT_homelat.Text = MainV2.cs.HomeLocation.Lat.ToString();
+ TXT_homelat.Text = MainV2.comPort.MAV.cs.HomeLocation.Lat.ToString();
- TXT_homelng.Text = MainV2.cs.HomeLocation.Lng.ToString();
+ TXT_homelng.Text = MainV2.comPort.MAV.cs.HomeLocation.Lng.ToString();
- TXT_homealt.Text = MainV2.cs.HomeLocation.Alt.ToString();
+ TXT_homealt.Text = MainV2.comPort.MAV.cs.HomeLocation.Alt.ToString();
}
@@ -848,7 +848,7 @@ namespace ArdupilotMega.GCSViews
GMapMarkerRect mBorders = new GMapMarkerRect(point);
{
mBorders.InnerMarker = m;
- mBorders.wprad = (int)(float.Parse(TXT_WPRad.Text) / MainV2.cs.multiplierdist);
+ mBorders.wprad = (int)(float.Parse(TXT_WPRad.Text) / MainV2.comPort.MAV.cs.multiplierdist);
mBorders.MainMap = MainMap;
if (color.HasValue)
{
@@ -1151,7 +1151,7 @@ namespace ArdupilotMega.GCSViews
sw.Write("\t" + double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write("\t" + double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write("\t" + double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
- sw.Write("\t" + (double.Parse(Commands.Rows[a].Cells[Alt.Index].Value.ToString()) / MainV2.cs.multiplierdist).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
+ sw.Write("\t" + (double.Parse(Commands.Rows[a].Cells[Alt.Index].Value.ToString()) / MainV2.comPort.MAV.cs.multiplierdist).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write("\t" + 1);
sw.WriteLine("");
}
@@ -1205,7 +1205,7 @@ namespace ArdupilotMega.GCSViews
MainV2.giveComport = true;
- param = port.param;
+ param = port.MAV.param;
log.Info("Getting WP #");
@@ -1322,7 +1322,7 @@ namespace ArdupilotMega.GCSViews
home.id = (byte)MAVLink.MAV_CMD.WAYPOINT;
home.lat = (float.Parse(TXT_homelat.Text));
home.lng = (float.Parse(TXT_homelng.Text));
- home.alt = (float.Parse(TXT_homealt.Text) / MainV2.cs.multiplierdist); // use saved home
+ home.alt = (float.Parse(TXT_homealt.Text) / MainV2.comPort.MAV.cs.multiplierdist); // use saved home
}
catch { throw new Exception("Your home location is invalid"); }
@@ -1356,7 +1356,7 @@ namespace ArdupilotMega.GCSViews
}
}
- temp.alt = (float)(double.Parse(Commands.Rows[a].Cells[Alt.Index].Value.ToString()) / MainV2.cs.multiplierdist);
+ temp.alt = (float)(double.Parse(Commands.Rows[a].Cells[Alt.Index].Value.ToString()) / MainV2.comPort.MAV.cs.multiplierdist);
temp.lat = (float)(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()));
temp.lng = (float)(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()));
@@ -1379,22 +1379,22 @@ namespace ArdupilotMega.GCSViews
if (CHK_holdalt.Checked)
{
- port.setParam("ALT_HOLD_RTL", int.Parse(TXT_DefaultAlt.Text) / MainV2.cs.multiplierdist * 100);
+ port.setParam("ALT_HOLD_RTL", int.Parse(TXT_DefaultAlt.Text) / MainV2.comPort.MAV.cs.multiplierdist * 100);
}
else
{
port.setParam("ALT_HOLD_RTL", -1);
}
- port.setParam("WP_RADIUS", (byte)int.Parse(TXT_WPRad.Text) / MainV2.cs.multiplierdist);
+ port.setParam("WP_RADIUS", (byte)int.Parse(TXT_WPRad.Text) / MainV2.comPort.MAV.cs.multiplierdist);
try
{
- port.setParam("WP_LOITER_RAD", (byte)(int.Parse(TXT_loiterrad.Text) / MainV2.cs.multiplierdist));
+ port.setParam("WP_LOITER_RAD", (byte)(int.Parse(TXT_loiterrad.Text) / MainV2.comPort.MAV.cs.multiplierdist));
}
catch
{
- port.setParam("LOITER_RAD", (byte)int.Parse(TXT_loiterrad.Text) / MainV2.cs.multiplierdist);
+ port.setParam("LOITER_RAD", (byte)int.Parse(TXT_loiterrad.Text) / MainV2.comPort.MAV.cs.multiplierdist);
}
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(100, "Done.");
@@ -1465,7 +1465,7 @@ namespace ArdupilotMega.GCSViews
}
cell = Commands.Rows[i].Cells[Alt.Index] as DataGridViewTextBoxCell;
- cell.Value = Math.Round((temp.alt * MainV2.cs.multiplierdist), 0);
+ cell.Value = Math.Round((temp.alt * MainV2.comPort.MAV.cs.multiplierdist), 0);
cell = Commands.Rows[i].Cells[Lat.Index] as DataGridViewTextBoxCell;
cell.Value = (double)temp.lat;
cell = Commands.Rows[i].Cells[Lon.Index] as DataGridViewTextBoxCell;
@@ -1484,7 +1484,7 @@ namespace ArdupilotMega.GCSViews
{
log.Info("Setting wp params");
- string hold_alt = ((int)((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist / 100.0)).ToString();
+ string hold_alt = ((int)((float)param["ALT_HOLD_RTL"] * MainV2.comPort.MAV.cs.multiplierdist / 100.0)).ToString();
log.Info("param ALT_HOLD_RTL " + hold_alt);
@@ -1493,17 +1493,17 @@ namespace ArdupilotMega.GCSViews
TXT_DefaultAlt.Text = hold_alt;
}
- TXT_WPRad.Text = ((int)((float)param["WP_RADIUS"] * MainV2.cs.multiplierdist)).ToString();
+ TXT_WPRad.Text = ((int)((float)param["WP_RADIUS"] * MainV2.comPort.MAV.cs.multiplierdist)).ToString();
log.Info("param WP_RADIUS " + TXT_WPRad.Text);
try
{
if (param["LOITER_RADIUS"] != null)
- TXT_loiterrad.Text = ((int)((float)param["LOITER_RADIUS"] * MainV2.cs.multiplierdist)).ToString();
+ TXT_loiterrad.Text = ((int)((float)param["LOITER_RADIUS"] * MainV2.comPort.MAV.cs.multiplierdist)).ToString();
if (param["WP_LOITER_RAD"] != null)
- TXT_loiterrad.Text = ((int)((float)param["WP_LOITER_RAD"] * MainV2.cs.multiplierdist)).ToString();
+ TXT_loiterrad.Text = ((int)((float)param["WP_LOITER_RAD"] * MainV2.comPort.MAV.cs.multiplierdist)).ToString();
log.Info("param LOITER_RADIUS " + TXT_loiterrad.Text);
}
@@ -1534,7 +1534,7 @@ namespace ArdupilotMega.GCSViews
cellhome = Commands.Rows[0].Cells[Lon.Index] as DataGridViewTextBoxCell;
TXT_homelng.Text = (double.Parse(cellhome.Value.ToString())).ToString();
cellhome = Commands.Rows[0].Cells[Alt.Index] as DataGridViewTextBoxCell;
- TXT_homealt.Text = (double.Parse(cellhome.Value.ToString()) * MainV2.cs.multiplierdist).ToString();
+ TXT_homealt.Text = (double.Parse(cellhome.Value.ToString()) * MainV2.comPort.MAV.cs.multiplierdist).ToString();
}
}
}
@@ -1719,7 +1719,7 @@ namespace ArdupilotMega.GCSViews
sethome = false;
try
{
- MainV2.cs.HomeLocation.Lat = double.Parse(TXT_homelat.Text);
+ MainV2.comPort.MAV.cs.HomeLocation.Lat = double.Parse(TXT_homelat.Text);
}
catch { }
writeKML();
@@ -1731,7 +1731,7 @@ namespace ArdupilotMega.GCSViews
sethome = false;
try
{
- MainV2.cs.HomeLocation.Lng = double.Parse(TXT_homelng.Text);
+ MainV2.comPort.MAV.cs.HomeLocation.Lng = double.Parse(TXT_homelng.Text);
}
catch { }
writeKML();
@@ -1742,7 +1742,7 @@ namespace ArdupilotMega.GCSViews
sethome = false;
try
{
- MainV2.cs.HomeLocation.Alt = double.Parse(TXT_homealt.Text);
+ MainV2.comPort.MAV.cs.HomeLocation.Alt = double.Parse(TXT_homealt.Text);
}
catch { }
writeKML();
@@ -2340,7 +2340,7 @@ namespace ArdupilotMega.GCSViews
}
catch { }
- return alt * MainV2.cs.multiplierdist;
+ return alt * MainV2.comPort.MAV.cs.multiplierdist;
}
private void TXT_homelat_Enter(object sender, EventArgs e)
@@ -2468,11 +2468,11 @@ namespace ArdupilotMega.GCSViews
private void label4_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e)
{
- if (MainV2.cs.lat != 0)
+ if (MainV2.comPort.MAV.cs.lat != 0)
{
- TXT_homealt.Text = (MainV2.cs.alt).ToString("0");
- TXT_homelat.Text = MainV2.cs.lat.ToString();
- TXT_homelng.Text = MainV2.cs.lng.ToString();
+ TXT_homealt.Text = (MainV2.comPort.MAV.cs.alt).ToString("0");
+ TXT_homelat.Text = MainV2.comPort.MAV.cs.lat.ToString();
+ TXT_homelng.Text = MainV2.comPort.MAV.cs.lng.ToString();
}
else
{
@@ -2659,7 +2659,11 @@ namespace ArdupilotMega.GCSViews
{
if (int.TryParse(CurentRectMarker.InnerMarker.Tag.ToString(), out no))
{
- Commands.Rows.RemoveAt(no - 1); // home is 0
+ try
+ {
+ Commands.Rows.RemoveAt(no - 1); // home is 0
+ }
+ catch { CustomMessageBox.Show("error selecting wp, please try again."); }
}
else if (int.TryParse(CurentRectMarker.InnerMarker.Tag.ToString().Replace("grid", ""), out no))
{
@@ -2762,32 +2766,32 @@ namespace ArdupilotMega.GCSViews
routes.Markers.Clear();
- if (MainV2.cs.TrackerLocation != MainV2.cs.HomeLocation && MainV2.cs.TrackerLocation.Lng != 0)
+ if (MainV2.comPort.MAV.cs.TrackerLocation != MainV2.comPort.MAV.cs.HomeLocation && MainV2.comPort.MAV.cs.TrackerLocation.Lng != 0)
{
- addpolygonmarker("Tracker Home", MainV2.cs.TrackerLocation.Lng, MainV2.cs.TrackerLocation.Lat, (int)MainV2.cs.TrackerLocation.Alt, Color.Blue, routes);
+ addpolygonmarker("Tracker Home", MainV2.comPort.MAV.cs.TrackerLocation.Lng, MainV2.comPort.MAV.cs.TrackerLocation.Lat, (int)MainV2.comPort.MAV.cs.TrackerLocation.Alt, Color.Blue, routes);
}
- if (MainV2.cs.lat == 0 || MainV2.cs.lng == 0)
+ if (MainV2.comPort.MAV.cs.lat == 0 || MainV2.comPort.MAV.cs.lng == 0)
return;
- PointLatLng currentloc = new PointLatLng(MainV2.cs.lat, MainV2.cs.lng);
+ PointLatLng currentloc = new PointLatLng(MainV2.comPort.MAV.cs.lat, MainV2.comPort.MAV.cs.lng);
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
- routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing, MainMap));
+ routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.comPort.MAV.cs.yaw, MainV2.comPort.MAV.cs.groundcourse, MainV2.comPort.MAV.cs.nav_bearing, MainV2.comPort.MAV.cs.target_bearing, MainMap));
}
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduRover)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover)
{
- routes.Markers.Add(new GMapMarkerRover(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing, MainMap));
+ routes.Markers.Add(new GMapMarkerRover(currentloc, MainV2.comPort.MAV.cs.yaw, MainV2.comPort.MAV.cs.groundcourse, MainV2.comPort.MAV.cs.nav_bearing, MainV2.comPort.MAV.cs.target_bearing, MainMap));
}
else
{
- routes.Markers.Add(new GMapMarkerQuad(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing));
+ routes.Markers.Add(new GMapMarkerQuad(currentloc, MainV2.comPort.MAV.cs.yaw, MainV2.comPort.MAV.cs.groundcourse, MainV2.comPort.MAV.cs.nav_bearing));
}
- if (MainV2.cs.mode.ToLower() == "guided" && MainV2.comPort.GuidedMode.x != 0)
+ if (MainV2.comPort.MAV.cs.mode.ToLower() == "guided" && MainV2.comPort.MAV.GuidedMode.x != 0)
{
- addpolygonmarker("Guided Mode", MainV2.comPort.GuidedMode.y, MainV2.comPort.GuidedMode.x, (int)MainV2.comPort.GuidedMode.z, Color.Blue, routes);
+ addpolygonmarker("Guided Mode", MainV2.comPort.MAV.GuidedMode.y, MainV2.comPort.MAV.GuidedMode.x, (int)MainV2.comPort.MAV.GuidedMode.z, Color.Blue, routes);
}
@@ -2811,7 +2815,7 @@ namespace ArdupilotMega.GCSViews
mBorders.InnerMarker = m;
try
{
- mBorders.wprad = (int)(float.Parse(ArdupilotMega.MainV2.config["TXT_WPRad"].ToString()) / MainV2.cs.multiplierdist);
+ mBorders.wprad = (int)(float.Parse(ArdupilotMega.MainV2.config["TXT_WPRad"].ToString()) / MainV2.comPort.MAV.cs.multiplierdist);
}
catch { }
mBorders.MainMap = MainMap;
@@ -2831,7 +2835,7 @@ namespace ArdupilotMega.GCSViews
{
polygongridmode = false;
//FENCE_TOTAL
- if (MainV2.comPort.param["FENCE_ACTION"] == null)
+ if (MainV2.comPort.MAV.param["FENCE_ACTION"] == null)
{
CustomMessageBox.Show("Not Supported");
return;
@@ -2866,10 +2870,10 @@ namespace ArdupilotMega.GCSViews
return;
}
- string minalts = (int.Parse(MainV2.comPort.param["FENCE_MINALT"].ToString()) * MainV2.cs.multiplierdist).ToString("0");
+ string minalts = (int.Parse(MainV2.comPort.MAV.param["FENCE_MINALT"].ToString()) * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
Common.InputBox("Min Alt", "Box Minimum Altitude?", ref minalts);
- string maxalts = (int.Parse(MainV2.comPort.param["FENCE_MAXALT"].ToString()) * MainV2.cs.multiplierdist).ToString("0");
+ string maxalts = (int.Parse(MainV2.comPort.MAV.param["FENCE_MAXALT"].ToString()) * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
Common.InputBox("Max Alt", "Box Maximum Altitude?", ref maxalts);
int minalt = 0;
@@ -2900,7 +2904,7 @@ namespace ArdupilotMega.GCSViews
try
{
- if (MainV2.comPort.param["FENCE_ACTION"].ToString() != "0")
+ if (MainV2.comPort.MAV.param["FENCE_ACTION"].ToString() != "0")
MainV2.comPort.setParam("FENCE_ACTION", 0);
}
catch
@@ -2959,13 +2963,13 @@ namespace ArdupilotMega.GCSViews
polygongridmode = false;
int count = 1;
- if (MainV2.comPort.param["FENCE_ACTION"] == null || MainV2.comPort.param["FENCE_TOTAL"] == null)
+ if (MainV2.comPort.MAV.param["FENCE_ACTION"] == null || MainV2.comPort.MAV.param["FENCE_TOTAL"] == null)
{
CustomMessageBox.Show("Not Supported");
return;
}
- if (int.Parse(MainV2.comPort.param["FENCE_TOTAL"].ToString()) <= 1)
+ if (int.Parse(MainV2.comPort.MAV.param["FENCE_TOTAL"].ToString()) <= 1)
{
CustomMessageBox.Show("Nothing to download");
return;
@@ -3225,7 +3229,7 @@ namespace ArdupilotMega.GCSViews
{
timer1.Start();
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
CHK_altmode.Visible = false;
}
@@ -3297,13 +3301,13 @@ namespace ArdupilotMega.GCSViews
double heightdist = MainMap.Manager.GetDistance(arearect.LocationTopLeft, bottomleft) * 1000;
double widthdist = MainMap.Manager.GetDistance(arearect.LocationTopLeft, topright) * 1000;
- string alt = (100 * MainV2.cs.multiplierdist).ToString("0");
+ string alt = (100 * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
Common.InputBox("Altitude", "Relative Altitude", ref alt);
- string distance = (50 * MainV2.cs.multiplierdist).ToString("0");
+ string distance = (50 * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
Common.InputBox("Distance", "Distance between lines", ref distance);
- string wpevery = (40 * MainV2.cs.multiplierdist).ToString("0");
+ string wpevery = (40 * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
Common.InputBox("Every", "Put a WP every x distance (-1 for none)", ref wpevery);
string angle = (90).ToString("0");
@@ -3337,8 +3341,8 @@ namespace ArdupilotMega.GCSViews
double x1 = Math.Sin((double.Parse(angle)) * deg2rad);
// get x y step amount in lat lng from m
- double latdiff = arearect.HeightLat / ((heightdist / (double.Parse(distance) * (x1) / MainV2.cs.multiplierdist)));
- double lngdiff = arearect.WidthLng / ((widthdist / (double.Parse(distance) * (y1) / MainV2.cs.multiplierdist)));
+ double latdiff = arearect.HeightLat / ((heightdist / (double.Parse(distance) * (x1) / MainV2.comPort.MAV.cs.multiplierdist)));
+ double lngdiff = arearect.WidthLng / ((widthdist / (double.Parse(distance) * (y1) / MainV2.comPort.MAV.cs.multiplierdist)));
double latlngdiff = Math.Sqrt(latdiff * latdiff + lngdiff * lngdiff);
@@ -3347,7 +3351,7 @@ namespace ArdupilotMega.GCSViews
double fulllatdiff = arearect.HeightLat * x1 * 2;
double fulllngdiff = arearect.WidthLng * y1 * 2;
- int altitude = (int)(double.Parse(alt) / MainV2.cs.multiplierdist);
+ int altitude = (int)(double.Parse(alt) / MainV2.comPort.MAV.cs.multiplierdist);
// draw a grid
double x = arearect.LocationMiddle.Lng;
@@ -3363,8 +3367,8 @@ namespace ArdupilotMega.GCSViews
x1 = Math.Sin((double.Parse(angle) + 90) * deg2rad);
// get x y step amount in lat lng from m
- latdiff = arearect.HeightLat / ((heightdist / (double.Parse(distance) * (y1) / MainV2.cs.multiplierdist)));
- lngdiff = arearect.WidthLng / ((widthdist / (double.Parse(distance) * (x1) / MainV2.cs.multiplierdist)));
+ latdiff = arearect.HeightLat / ((heightdist / (double.Parse(distance) * (y1) / MainV2.comPort.MAV.cs.multiplierdist)));
+ lngdiff = arearect.WidthLng / ((widthdist / (double.Parse(distance) * (x1) / MainV2.comPort.MAV.cs.multiplierdist)));
quickadd = true;
@@ -3507,7 +3511,7 @@ namespace ArdupilotMega.GCSViews
// int fixme;
- // foreach (PointLatLng pnt in PathFind.FindPath(MainV2.cs.HomeLocation.Point(),grid))
+ // foreach (PointLatLng pnt in PathFind.FindPath(MainV2.comPort.MAV.cs.HomeLocation.Point(),grid))
// {
// callMe(pnt.Lat, pnt.Lng, altitude);
// }
@@ -3516,11 +3520,11 @@ namespace ArdupilotMega.GCSViews
quickadd = true;
- linelatlng closest = findClosestLine(MainV2.cs.HomeLocation.Point(), grid);
+ linelatlng closest = findClosestLine(MainV2.comPort.MAV.cs.HomeLocation.Point(), grid);
PointLatLng lastpnt;
- if (MainMap.Manager.GetDistance(closest.p1, MainV2.cs.HomeLocation.Point()) < MainMap.Manager.GetDistance(closest.p2, MainV2.cs.HomeLocation.Point()))
+ if (MainMap.Manager.GetDistance(closest.p1, MainV2.comPort.MAV.cs.HomeLocation.Point()) < MainMap.Manager.GetDistance(closest.p2, MainV2.comPort.MAV.cs.HomeLocation.Point()))
{
lastpnt = closest.p1;
}
@@ -3666,14 +3670,14 @@ namespace ArdupilotMega.GCSViews
- string alt = (100 * MainV2.cs.multiplierdist).ToString("0");
+ string alt = (100 * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
Common.InputBox("Altitude", "Relative Altitude", ref alt);
- string distance = (50 * MainV2.cs.multiplierdist).ToString("0");
+ string distance = (50 * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
Common.InputBox("Distance", "Distance between lines", ref distance);
- string wpevery = (40 * MainV2.cs.multiplierdist).ToString("0");
+ string wpevery = (40 * MainV2.comPort.MAV.cs.multiplierdist).ToString("0");
Common.InputBox("Every", "Put a WP every x distance (-1 for none)", ref wpevery);
string angle = (90).ToString("0");
@@ -3710,8 +3714,8 @@ namespace ArdupilotMega.GCSViews
double y1 = Math.Sin((double.Parse(angle)) * deg2rad);
// get x y step amount in lat lng from m
- double latdiff = arearect.HeightLat / ((heightdist / (double.Parse(distance) * (y1) / MainV2.cs.multiplierdist)));
- double lngdiff = arearect.WidthLng / ((widthdist / (double.Parse(distance) * (x1) / MainV2.cs.multiplierdist)));
+ double latdiff = arearect.HeightLat / ((heightdist / (double.Parse(distance) * (y1) / MainV2.comPort.MAV.cs.multiplierdist)));
+ double lngdiff = arearect.WidthLng / ((widthdist / (double.Parse(distance) * (x1) / MainV2.comPort.MAV.cs.multiplierdist)));
double latlngdiff = Math.Sqrt(latdiff * latdiff + lngdiff * lngdiff);
@@ -3721,9 +3725,9 @@ namespace ArdupilotMega.GCSViews
// lat - up down
// lng - left right
- int overshootdist = 0;// (int)(double.Parse(overshoot) / MainV2.cs.multiplierdist);
+ int overshootdist = 0;// (int)(double.Parse(overshoot) / MainV2.comPort.MAV.cs.multiplierdist);
- int altitude = (int)(double.Parse(alt) / MainV2.cs.multiplierdist);
+ int altitude = (int)(double.Parse(alt) / MainV2.comPort.MAV.cs.multiplierdist);
double overshootdistlng = arearect.WidthLng / widthdist * overshootdist;
@@ -4150,7 +4154,7 @@ namespace ArdupilotMega.GCSViews
// take off pitch
int topi = 0;
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
string top = "15";
@@ -4188,7 +4192,7 @@ namespace ArdupilotMega.GCSViews
private void trackerHomeToolStripMenuItem_Click(object sender, EventArgs e)
{
- MainV2.cs.TrackerLocation = new PointLatLngAlt(end) { Alt = MainV2.cs.HomeAlt };
+ MainV2.comPort.MAV.cs.TrackerLocation = new PointLatLngAlt(end) { Alt = MainV2.comPort.MAV.cs.HomeAlt };
}
private void gridV2ToolStripMenuItem_Click(object sender, EventArgs e)
@@ -4316,7 +4320,7 @@ namespace ArdupilotMega.GCSViews
private void contextMenuStrip1_Opening(object sender, CancelEventArgs e)
{
- if (MainV2.cs.firmware != MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware != MainV2.Firmwares.ArduPlane)
{
geoFenceToolStripMenuItem.Enabled = false;
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Help.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Help.zh-Hans.resx
index 17e947b71c..2593bbd3c3 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Help.zh-Hans.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Help.zh-Hans.resx
@@ -123,8 +123,4 @@
检查更新
-
-
- ..\Resources\Welcome_CN.rtf;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252
-
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Help.zh-TW.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Help.zh-TW.resx
index adcfb18b22..dd71e2b154 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Help.zh-TW.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Help.zh-TW.resx
@@ -123,8 +123,4 @@
檢查更新
-
-
- ..\Resources\Welcome_TW.rtf;System.String, mscorlib, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;utf-8
-
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
index 0bbe2662ce..ff43090a90 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
@@ -566,7 +566,7 @@ namespace ArdupilotMega.GCSViews
DateTime lastdata = DateTime.MinValue;
// set enable hil status flag - sends base_mode = 0
- MainV2.comPort.setMode(new MAVLink.mavlink_set_mode_t() { target_system = MainV2.comPort.sysid }, MAVLink.MAV_MODE_FLAG.HIL_ENABLED);
+ MainV2.comPort.setMode(new MAVLink.mavlink_set_mode_t() { target_system = MainV2.comPort.MAV.sysid }, MAVLink.MAV_MODE_FLAG.HIL_ENABLED);
while (threadrun == 1)
{
@@ -623,7 +623,7 @@ namespace ArdupilotMega.GCSViews
try
{
- MainV2.cs.UpdateCurrentSettings(null); // when true this uses alot more cpu time
+ MainV2.comPort.MAV.cs.UpdateCurrentSettings(null); // when true this uses alot more cpu time
if ((DateTime.Now - simsendtime).TotalMilliseconds > 19)
{
@@ -677,8 +677,8 @@ namespace ArdupilotMega.GCSViews
//JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set position/h-agl-ft 0\r\n"));
- JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set position/lat-gc-deg " + MainV2.cs.HomeLocation.Lat + "\r\n"));
- JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set position/long-gc-deg " + MainV2.cs.HomeLocation.Lng + "\r\n"));
+ JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set position/lat-gc-deg " + MainV2.comPort.MAV.cs.HomeLocation.Lat + "\r\n"));
+ JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set position/long-gc-deg " + MainV2.comPort.MAV.cs.HomeLocation.Lng + "\r\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set attitude/phi-rad 0\r\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set attitude/theta-rad 0\r\n"));
@@ -1026,9 +1026,9 @@ namespace ArdupilotMega.GCSViews
hilstate.yaw = (float)sitldata.yawDeg * deg2rad; // (rad)
hilstate.yawspeed = (float)sitldata.yawRate * deg2rad; // (rad/s)
- hilstate.vx = (short)(sitldata.speedN * 100); // m/s * 100
- hilstate.vy = (short)(sitldata.speedE * 100); // m/s * 100
- hilstate.vz = 0; // m/s * 100
+ hilstate.vx = (short)(sitldata.speedE * 100); // m/s * 100
+ hilstate.vy = (short)(sitldata.speedN * 100); // m/s * 100
+ hilstate.vz = 0; // m/s * 100 - + speed down
hilstate.xacc = (short)(sitldata.xAccel * 1000); // (mg)
hilstate.yacc = (short)(sitldata.yAccel * 1000); // (mg)
@@ -1084,11 +1084,11 @@ namespace ArdupilotMega.GCSViews
TXT_heading.Text = (heading * rad2deg).ToString("0.000");
TXT_yaw.Text = (yaw * rad2deg).ToString("0.000");
- TXT_wpdist.Text = MainV2.cs.wp_dist.ToString();
- TXT_bererror.Text = MainV2.cs.ber_error.ToString();
- TXT_alterror.Text = MainV2.cs.alt_error.ToString();
- TXT_WP.Text = MainV2.cs.wpno.ToString();
- TXT_control_mode.Text = MainV2.cs.mode;
+ TXT_wpdist.Text = MainV2.comPort.MAV.cs.wp_dist.ToString();
+ TXT_bererror.Text = MainV2.comPort.MAV.cs.ber_error.ToString();
+ TXT_alterror.Text = MainV2.comPort.MAV.cs.alt_error.ToString();
+ TXT_WP.Text = MainV2.comPort.MAV.cs.wpno.ToString();
+ TXT_control_mode.Text = MainV2.comPort.MAV.cs.mode;
});
}
catch { this.Invoke((MethodInvoker)delegate { OutputLog.AppendText("NO SIM data - exep\n"); }); }
@@ -1104,10 +1104,10 @@ namespace ArdupilotMega.GCSViews
double[] m = new double[4];
- m[0] = (ushort)MainV2.cs.ch1out;
- m[1] = (ushort)MainV2.cs.ch2out;
- m[2] = (ushort)MainV2.cs.ch3out;
- m[3] = (ushort)MainV2.cs.ch4out;
+ m[0] = (ushort)MainV2.comPort.MAV.cs.ch1out;
+ m[1] = (ushort)MainV2.comPort.MAV.cs.ch2out;
+ m[2] = (ushort)MainV2.comPort.MAV.cs.ch3out;
+ m[3] = (ushort)MainV2.comPort.MAV.cs.ch4out;
if (!RAD_softFlightGear.Checked)
{
@@ -1176,24 +1176,24 @@ namespace ArdupilotMega.GCSViews
if (heli)
{
- roll_out = (float)MainV2.cs.hilch1 / rollgain;
- pitch_out = (float)MainV2.cs.hilch2 / pitchgain;
+ roll_out = (float)MainV2.comPort.MAV.cs.hilch1 / rollgain;
+ pitch_out = (float)MainV2.comPort.MAV.cs.hilch2 / pitchgain;
throttle_out = 1;
- rudder_out = (float)MainV2.cs.hilch4 / -ruddergain;
+ rudder_out = (float)MainV2.comPort.MAV.cs.hilch4 / -ruddergain;
- collective_out = (float)(MainV2.cs.hilch3 - 1500) / throttlegain;
+ collective_out = (float)(MainV2.comPort.MAV.cs.hilch3 - 1500) / throttlegain;
}
else
{
- roll_out = (float)MainV2.cs.hilch1 / rollgain;
- pitch_out = (float)MainV2.cs.hilch2 / pitchgain;
- throttle_out = ((float)MainV2.cs.hilch3) / throttlegain;
- rudder_out = (float)MainV2.cs.hilch4 / ruddergain;
+ roll_out = (float)MainV2.comPort.MAV.cs.hilch1 / rollgain;
+ pitch_out = (float)MainV2.comPort.MAV.cs.hilch2 / pitchgain;
+ throttle_out = ((float)MainV2.comPort.MAV.cs.hilch3) / throttlegain;
+ rudder_out = (float)MainV2.comPort.MAV.cs.hilch4 / ruddergain;
if (RAD_aerosimrc.Checked && CHK_quad.Checked)
{
- throttle_out = ((float)MainV2.cs.hilch7 / 2 + 5000) / throttlegain;
- //throttle_out = (float)(MainV2.cs.hilch7 - 1100) / throttlegain;
+ throttle_out = ((float)MainV2.comPort.MAV.cs.hilch7 / 2 + 5000) / throttlegain;
+ //throttle_out = (float)(MainV2.comPort.MAV.cs.hilch7 - 1100) / throttlegain;
}
}
@@ -1292,10 +1292,10 @@ namespace ArdupilotMega.GCSViews
if (CHK_quad.Checked)
{
- //MainV2.cs.ch1out = 1100;
- //MainV2.cs.ch2out = 1100;
- //MainV2.cs.ch3out = 1100;
- //MainV2.cs.ch4out = 1100;
+ //MainV2.comPort.MAV.cs.ch1out = 1100;
+ //MainV2.comPort.MAV.cs.ch2out = 1100;
+ //MainV2.comPort.MAV.cs.ch3out = 1100;
+ //MainV2.comPort.MAV.cs.ch4out = 1100;
//ac
// 3 front
@@ -1303,10 +1303,10 @@ namespace ArdupilotMega.GCSViews
// 4 back
// 2 left
- Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch3out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 0, 8); // motor 1 = front
- Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch1out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 8, 8); // motor 2 = right
- Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch4out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 16, 8);// motor 3 = back
- Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch2out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 24, 8);// motor 4 = left
+ Array.Copy(BitConverter.GetBytes((double)((MainV2.comPort.MAV.cs.ch3out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 0, 8); // motor 1 = front
+ Array.Copy(BitConverter.GetBytes((double)((MainV2.comPort.MAV.cs.ch1out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 8, 8); // motor 2 = right
+ Array.Copy(BitConverter.GetBytes((double)((MainV2.comPort.MAV.cs.ch4out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 16, 8);// motor 3 = back
+ Array.Copy(BitConverter.GetBytes((double)((MainV2.comPort.MAV.cs.ch2out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 24, 8);// motor 4 = left
}
else
diff --git a/Tools/ArdupilotMegaPlanner/HIL/XPlane.cs b/Tools/ArdupilotMegaPlanner/HIL/XPlane.cs
index 84c4b51bf8..245dc8a54c 100644
--- a/Tools/ArdupilotMegaPlanner/HIL/XPlane.cs
+++ b/Tools/ArdupilotMegaPlanner/HIL/XPlane.cs
@@ -155,10 +155,10 @@ namespace ArdupilotMega.HIL
}
public override void SendToSim()
{
- roll_out = (float)MainV2.cs.hilch1 / rollgain;
- pitch_out = (float)MainV2.cs.hilch2 / pitchgain;
- throttle_out = ((float)MainV2.cs.hilch3) / throttlegain;
- rudder_out = (float)MainV2.cs.hilch4 / ruddergain;
+ roll_out = (float)MainV2.comPort.MAV.cs.hilch1 / rollgain;
+ pitch_out = (float)MainV2.comPort.MAV.cs.hilch2 / pitchgain;
+ throttle_out = ((float)MainV2.comPort.MAV.cs.hilch3) / throttlegain;
+ rudder_out = (float)MainV2.comPort.MAV.cs.hilch4 / ruddergain;
// Limit min and max
roll_out = Constrain(roll_out, -1, 1);
diff --git a/Tools/ArdupilotMegaPlanner/Joystick.cs b/Tools/ArdupilotMegaPlanner/Joystick.cs
index c32136330a..ba01e6d278 100644
--- a/Tools/ArdupilotMegaPlanner/Joystick.cs
+++ b/Tools/ArdupilotMegaPlanner/Joystick.cs
@@ -304,30 +304,30 @@ namespace ArdupilotMega
ushort pitch = pickchannel(2, JoyChannels[2].axis, false, JoyChannels[2].expo);
if (getJoystickAxis(1) != Joystick.joystickaxis.None)
- MainV2.cs.rcoverridech1 = (ushort)(BOOL_TO_SIGN(JoyChannels[1].reverse) * ((int)(pitch - 1500) - (int)(roll - 1500)) / 2 + 1500);
+ MainV2.comPort.MAV.cs.rcoverridech1 = (ushort)(BOOL_TO_SIGN(JoyChannels[1].reverse) * ((int)(pitch - 1500) - (int)(roll - 1500)) / 2 + 1500);
if (getJoystickAxis(2) != Joystick.joystickaxis.None)
- MainV2.cs.rcoverridech2 = (ushort)(BOOL_TO_SIGN(JoyChannels[2].reverse) * ((int)(pitch - 1500) + (int)(roll - 1500)) / 2 + 1500);
+ MainV2.comPort.MAV.cs.rcoverridech2 = (ushort)(BOOL_TO_SIGN(JoyChannels[2].reverse) * ((int)(pitch - 1500) + (int)(roll - 1500)) / 2 + 1500);
}
else
{
if (getJoystickAxis(1) != Joystick.joystickaxis.None)
- MainV2.cs.rcoverridech1 = pickchannel(1, JoyChannels[1].axis, JoyChannels[1].reverse, JoyChannels[1].expo);//(ushort)(((int)state.Rz / 65.535) + 1000);
+ MainV2.comPort.MAV.cs.rcoverridech1 = pickchannel(1, JoyChannels[1].axis, JoyChannels[1].reverse, JoyChannels[1].expo);//(ushort)(((int)state.Rz / 65.535) + 1000);
if (getJoystickAxis(2) != Joystick.joystickaxis.None)
- MainV2.cs.rcoverridech2 = pickchannel(2, JoyChannels[2].axis, JoyChannels[2].reverse, JoyChannels[2].expo);//(ushort)(((int)state.Y / 65.535) + 1000);
+ MainV2.comPort.MAV.cs.rcoverridech2 = pickchannel(2, JoyChannels[2].axis, JoyChannels[2].reverse, JoyChannels[2].expo);//(ushort)(((int)state.Y / 65.535) + 1000);
}
if (getJoystickAxis(3) != Joystick.joystickaxis.None)
- MainV2.cs.rcoverridech3 = pickchannel(3, JoyChannels[3].axis, JoyChannels[3].reverse, JoyChannels[3].expo);//(ushort)(1000 - ((int)slider[0] / 65.535) + 1000);
+ MainV2.comPort.MAV.cs.rcoverridech3 = pickchannel(3, JoyChannels[3].axis, JoyChannels[3].reverse, JoyChannels[3].expo);//(ushort)(1000 - ((int)slider[0] / 65.535) + 1000);
if (getJoystickAxis(4) != Joystick.joystickaxis.None)
- MainV2.cs.rcoverridech4 = pickchannel(4, JoyChannels[4].axis, JoyChannels[4].reverse, JoyChannels[4].expo);//(ushort)(((int)state.X / 65.535) + 1000);
+ MainV2.comPort.MAV.cs.rcoverridech4 = pickchannel(4, JoyChannels[4].axis, JoyChannels[4].reverse, JoyChannels[4].expo);//(ushort)(((int)state.X / 65.535) + 1000);
if (getJoystickAxis(5) != Joystick.joystickaxis.None)
- MainV2.cs.rcoverridech5 = pickchannel(5, JoyChannels[5].axis, JoyChannels[5].reverse, JoyChannels[5].expo);
+ MainV2.comPort.MAV.cs.rcoverridech5 = pickchannel(5, JoyChannels[5].axis, JoyChannels[5].reverse, JoyChannels[5].expo);
if (getJoystickAxis(6) != Joystick.joystickaxis.None)
- MainV2.cs.rcoverridech6 = pickchannel(6, JoyChannels[6].axis, JoyChannels[6].reverse, JoyChannels[6].expo);
+ MainV2.comPort.MAV.cs.rcoverridech6 = pickchannel(6, JoyChannels[6].axis, JoyChannels[6].reverse, JoyChannels[6].expo);
if (getJoystickAxis(7) != Joystick.joystickaxis.None)
- MainV2.cs.rcoverridech7 = pickchannel(7, JoyChannels[7].axis, JoyChannels[7].reverse, JoyChannels[7].expo);
+ MainV2.comPort.MAV.cs.rcoverridech7 = pickchannel(7, JoyChannels[7].axis, JoyChannels[7].reverse, JoyChannels[7].expo);
if (getJoystickAxis(8) != Joystick.joystickaxis.None)
- MainV2.cs.rcoverridech8 = pickchannel(8, JoyChannels[8].axis, JoyChannels[8].reverse, JoyChannels[8].expo);
+ MainV2.comPort.MAV.cs.rcoverridech8 = pickchannel(8, JoyChannels[8].axis, JoyChannels[8].reverse, JoyChannels[8].expo);
foreach (JoyButton but in JoyButtons)
{
@@ -346,7 +346,7 @@ namespace ArdupilotMega
}
}
- //Console.WriteLine("{0} {1} {2} {3}", MainV2.cs.rcoverridech1, MainV2.cs.rcoverridech2, MainV2.cs.rcoverridech3, MainV2.cs.rcoverridech4);
+ //Console.WriteLine("{0} {1} {2} {3}", MainV2.comPort.MAV.cs.rcoverridech1, MainV2.comPort.MAV.cs.rcoverridech2, MainV2.comPort.MAV.cs.rcoverridech3, MainV2.comPort.MAV.cs.rcoverridech4);
}
catch (Exception ex) { log.Info("Joystick thread error "+ex.ToString()); } // so we cant fall out
}
@@ -503,13 +503,13 @@ namespace ArdupilotMega
{
int min, max, trim = 0;
- if (MainV2.comPort.param.Count > 0)
+ if (MainV2.comPort.MAV.param.Count > 0)
{
try
{
- min = (int)(float)(MainV2.comPort.param["RC" + chan + "_MIN"]);
- max = (int)(float)(MainV2.comPort.param["RC" + chan + "_MAX"]);
- trim = (int)(float)(MainV2.comPort.param["RC" + chan + "_TRIM"]);
+ min = (int)(float)(MainV2.comPort.MAV.param["RC" + chan + "_MIN"]);
+ max = (int)(float)(MainV2.comPort.MAV.param["RC" + chan + "_MAX"]);
+ trim = (int)(float)(MainV2.comPort.MAV.param["RC" + chan + "_TRIM"]);
}
catch {
min = 1000;
diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
index c750515d5c..2370e36706 100644
--- a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
+++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
@@ -151,8 +151,8 @@ namespace ArdupilotMega
{
MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
- rc.target_component = MainV2.comPort.compid;
- rc.target_system = MainV2.comPort.sysid;
+ rc.target_component = MainV2.comPort.MAV.compid;
+ rc.target_system = MainV2.comPort.MAV.sysid;
rc.chan1_raw = 0;
rc.chan2_raw = 0;
@@ -264,28 +264,28 @@ namespace ArdupilotMega
MainV2.joystick.elevons = CHK_elevons.Checked;
- MainV2.cs.rcoverridech1 = joy.getValueForChannel(1, CMB_joysticks.Text);
- MainV2.cs.rcoverridech2 = joy.getValueForChannel(2, CMB_joysticks.Text);
- MainV2.cs.rcoverridech3 = joy.getValueForChannel(3, CMB_joysticks.Text);
- MainV2.cs.rcoverridech4 = joy.getValueForChannel(4, CMB_joysticks.Text);
- MainV2.cs.rcoverridech5 = joy.getValueForChannel(5, CMB_joysticks.Text);
- MainV2.cs.rcoverridech6 = joy.getValueForChannel(6, CMB_joysticks.Text);
- MainV2.cs.rcoverridech7 = joy.getValueForChannel(7, CMB_joysticks.Text);
- MainV2.cs.rcoverridech8 = joy.getValueForChannel(8, CMB_joysticks.Text);
+ MainV2.comPort.MAV.cs.rcoverridech1 = joy.getValueForChannel(1, CMB_joysticks.Text);
+ MainV2.comPort.MAV.cs.rcoverridech2 = joy.getValueForChannel(2, CMB_joysticks.Text);
+ MainV2.comPort.MAV.cs.rcoverridech3 = joy.getValueForChannel(3, CMB_joysticks.Text);
+ MainV2.comPort.MAV.cs.rcoverridech4 = joy.getValueForChannel(4, CMB_joysticks.Text);
+ MainV2.comPort.MAV.cs.rcoverridech5 = joy.getValueForChannel(5, CMB_joysticks.Text);
+ MainV2.comPort.MAV.cs.rcoverridech6 = joy.getValueForChannel(6, CMB_joysticks.Text);
+ MainV2.comPort.MAV.cs.rcoverridech7 = joy.getValueForChannel(7, CMB_joysticks.Text);
+ MainV2.comPort.MAV.cs.rcoverridech8 = joy.getValueForChannel(8, CMB_joysticks.Text);
//Console.WriteLine(DateTime.Now.Millisecond + " end ");
}
}
catch { }
- progressBar1.Value = MainV2.cs.rcoverridech1;
- progressBar2.Value = MainV2.cs.rcoverridech2;
- progressBar3.Value = MainV2.cs.rcoverridech3;
- progressBar4.Value = MainV2.cs.rcoverridech4;
- horizontalProgressBar1.Value = MainV2.cs.rcoverridech5;
- horizontalProgressBar2.Value = MainV2.cs.rcoverridech6;
- horizontalProgressBar3.Value = MainV2.cs.rcoverridech7;
- horizontalProgressBar4.Value = MainV2.cs.rcoverridech8;
+ progressBar1.Value = MainV2.comPort.MAV.cs.rcoverridech1;
+ progressBar2.Value = MainV2.comPort.MAV.cs.rcoverridech2;
+ progressBar3.Value = MainV2.comPort.MAV.cs.rcoverridech3;
+ progressBar4.Value = MainV2.comPort.MAV.cs.rcoverridech4;
+ horizontalProgressBar1.Value = MainV2.comPort.MAV.cs.rcoverridech5;
+ horizontalProgressBar2.Value = MainV2.comPort.MAV.cs.rcoverridech6;
+ horizontalProgressBar3.Value = MainV2.comPort.MAV.cs.rcoverridech7;
+ horizontalProgressBar4.Value = MainV2.comPort.MAV.cs.rcoverridech8;
try
{
diff --git a/Tools/ArdupilotMegaPlanner/Log.cs b/Tools/ArdupilotMegaPlanner/Log.cs
index 1a83223b41..4dd6f59767 100644
--- a/Tools/ArdupilotMegaPlanner/Log.cs
+++ b/Tools/ArdupilotMegaPlanner/Log.cs
@@ -388,9 +388,14 @@ namespace ArdupilotMega
}
if (items[0].Contains("GPS") && items[2] == "1" && items[4] != "0" && items[4] != "-1" && lastline != line) // check gps line and fixed status
{
+ MainV2.comPort.MAV.cs.firmware = MainV2.Firmwares.ArduPlane;
+
if (position[positionindex] == null)
position[positionindex] = new List();
+ if (double.Parse(items[4], new System.Globalization.CultureInfo("en-US")) == 0)
+ return;
+
double alt = double.Parse(items[6], new System.Globalization.CultureInfo("en-US"));
if (items.Length == 11 && items[6] == "0.0000")
@@ -404,11 +409,16 @@ namespace ArdupilotMega
lastpos = (position[positionindex][position[positionindex].Count - 1]);
lastline = line;
}
- if (items[0].Contains("GPS") && items[4] != "0" && items[4] != "-1" && items.Length <= 9)
+ if (items[0].Contains("GPS") && items[4] != "0" && items[4] != "-1" && items.Length <= 9) // AC
{
+ MainV2.comPort.MAV.cs.firmware = MainV2.Firmwares.ArduCopter2;
+
if (position[positionindex] == null)
position[positionindex] = new List();
+ if (double.Parse(items[4], new System.Globalization.CultureInfo("en-US")) == 0)
+ return;
+
double alt = double.Parse(items[5], new System.Globalization.CultureInfo("en-US"));
position[positionindex].Add(new Point3D(double.Parse(items[4], new System.Globalization.CultureInfo("en-US")), double.Parse(items[3], new System.Globalization.CultureInfo("en-US")), alt));
@@ -522,7 +532,7 @@ namespace ArdupilotMega
AltitudeMode altmode = AltitudeMode.absolute;
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
altmode = AltitudeMode.relativeToGround; // because of sonar, this is both right and wrong. right for sonar, wrong in terms of gps as the land slopes off.
}
diff --git a/Tools/ArdupilotMegaPlanner/LogBrowse.cs b/Tools/ArdupilotMegaPlanner/LogBrowse.cs
index 219e33e8b0..b734eaa8d3 100644
--- a/Tools/ArdupilotMegaPlanner/LogBrowse.cs
+++ b/Tools/ArdupilotMegaPlanner/LogBrowse.cs
@@ -160,11 +160,11 @@ namespace ArdupilotMega
{
reader.Read();
reader.ReadStartElement("LOGFORMAT");
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
reader.ReadToFollowing("APM");
}
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduRover)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover)
{
reader.ReadToFollowing("APRover");
}
diff --git a/Tools/ArdupilotMegaPlanner/MagCalib.cs b/Tools/ArdupilotMegaPlanner/MagCalib.cs
index ecbfd980e4..3c5b9c8fbd 100644
--- a/Tools/ArdupilotMegaPlanner/MagCalib.cs
+++ b/Tools/ArdupilotMegaPlanner/MagCalib.cs
@@ -91,7 +91,7 @@ namespace ArdupilotMega
mine.logreadmode = true;
- mine.packets.Initialize(); // clear
+ mine.MAV.packets.Initialize(); // clear
// gather data
while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
@@ -249,7 +249,7 @@ namespace ArdupilotMega
/// offsets
public static void SaveOffsets(double[] ofs)
{
- if (MainV2.comPort.param.ContainsKey("COMPASS_OFS_X") && MainV2.comPort.BaseStream.IsOpen)
+ if (MainV2.comPort.MAV.param.ContainsKey("COMPASS_OFS_X") && MainV2.comPort.BaseStream.IsOpen)
{
try
{
diff --git a/Tools/ArdupilotMegaPlanner/MainV2.Designer.cs b/Tools/ArdupilotMegaPlanner/MainV2.Designer.cs
index 66bb8d5f76..95b9573a43 100644
--- a/Tools/ArdupilotMegaPlanner/MainV2.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/MainV2.Designer.cs
@@ -28,6 +28,7 @@
///
private void InitializeComponent()
{
+ this.components = new System.ComponentModel.Container();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2));
this.MyView = new ArdupilotMega.Controls.MainSwitcher();
this.MainMenu = new System.Windows.Forms.MenuStrip();
@@ -42,8 +43,11 @@
this.toolStripConnectionControl = new ArdupilotMega.Controls.ToolStripConnectionControl();
this.menu = new ArdupilotMega.Controls.MyButton();
this.panel1 = new System.Windows.Forms.Panel();
+ this.CTX_mainmenu = new System.Windows.Forms.ContextMenuStrip(this.components);
+ this.autoHideToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.MainMenu.SuspendLayout();
this.panel1.SuspendLayout();
+ this.CTX_mainmenu.SuspendLayout();
this.SuspendLayout();
//
// MyView
@@ -58,6 +62,7 @@
// MainMenu
//
this.MainMenu.BackgroundImage = ((System.Drawing.Image)(resources.GetObject("MainMenu.BackgroundImage")));
+ this.MainMenu.ContextMenuStrip = this.CTX_mainmenu;
this.MainMenu.GripMargin = new System.Windows.Forms.Padding(0);
this.MainMenu.ImageScalingSize = new System.Drawing.Size(76, 76);
this.MainMenu.Items.AddRange(new System.Windows.Forms.ToolStripItem[] {
@@ -231,6 +236,23 @@
this.panel1.Visible = false;
this.panel1.MouseLeave += new System.EventHandler(this.MainMenu_MouseLeave);
//
+ // CTX_mainmenu
+ //
+ this.CTX_mainmenu.Items.AddRange(new System.Windows.Forms.ToolStripItem[] {
+ this.autoHideToolStripMenuItem});
+ this.CTX_mainmenu.Name = "CTX_mainmenu";
+ this.CTX_mainmenu.Size = new System.Drawing.Size(153, 48);
+ //
+ // autoHideToolStripMenuItem
+ //
+ this.autoHideToolStripMenuItem.Checked = true;
+ this.autoHideToolStripMenuItem.CheckOnClick = true;
+ this.autoHideToolStripMenuItem.CheckState = System.Windows.Forms.CheckState.Checked;
+ this.autoHideToolStripMenuItem.Name = "autoHideToolStripMenuItem";
+ this.autoHideToolStripMenuItem.Size = new System.Drawing.Size(152, 22);
+ this.autoHideToolStripMenuItem.Text = "AutoHide";
+ this.autoHideToolStripMenuItem.Click += new System.EventHandler(this.autoHideToolStripMenuItem_Click);
+ //
// MainV2
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
@@ -254,6 +276,7 @@
this.MainMenu.PerformLayout();
this.panel1.ResumeLayout(false);
this.panel1.PerformLayout();
+ this.CTX_mainmenu.ResumeLayout(false);
this.ResumeLayout(false);
}
@@ -275,5 +298,7 @@
private Controls.ToolStripConnectionControl toolStripConnectionControl;
private Controls.MyButton menu;
private System.Windows.Forms.Panel panel1;
+ private System.Windows.Forms.ContextMenuStrip CTX_mainmenu;
+ private System.Windows.Forms.ToolStripMenuItem autoHideToolStripMenuItem;
}
}
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs
index 66cad5ffc9..d6e7ad24e8 100644
--- a/Tools/ArdupilotMegaPlanner/MainV2.cs
+++ b/Tools/ArdupilotMegaPlanner/MainV2.cs
@@ -83,10 +83,6 @@ namespace ArdupilotMega
///
public static WebCamService.Capture cam = null;
///
- /// the static global state of the currently connected MAV
- ///
- public static CurrentState cs = new CurrentState();
- ///
/// controls the main serial reader thread
///
bool serialThread = false;
@@ -153,7 +149,6 @@ namespace ArdupilotMega
log.Info("Mainv2 ctor");
Form splash = Program.Splash;
- splash.Show();
string strVersion = System.Reflection.Assembly.GetExecutingAssembly().GetName().Version.ToString();
@@ -303,49 +298,48 @@ namespace ArdupilotMega
this.Width = int.Parse(config["MainWidth"].ToString());
if (config["CMB_rateattitude"] != null)
- MainV2.cs.rateattitude = byte.Parse(config["CMB_rateattitude"].ToString());
+ MainV2.comPort.MAV.cs.rateattitude = byte.Parse(config["CMB_rateattitude"].ToString());
if (config["CMB_rateposition"] != null)
- MainV2.cs.rateposition = byte.Parse(config["CMB_rateposition"].ToString());
+ MainV2.comPort.MAV.cs.rateposition = byte.Parse(config["CMB_rateposition"].ToString());
if (config["CMB_ratestatus"] != null)
- MainV2.cs.ratestatus = byte.Parse(config["CMB_ratestatus"].ToString());
+ MainV2.comPort.MAV.cs.ratestatus = byte.Parse(config["CMB_ratestatus"].ToString());
if (config["CMB_raterc"] != null)
- MainV2.cs.raterc = byte.Parse(config["CMB_raterc"].ToString());
+ MainV2.comPort.MAV.cs.raterc = byte.Parse(config["CMB_raterc"].ToString());
if (config["CMB_ratesensors"] != null)
- MainV2.cs.ratesensors = byte.Parse(config["CMB_ratesensors"].ToString());
+ MainV2.comPort.MAV.cs.ratesensors = byte.Parse(config["CMB_ratesensors"].ToString());
if (config["speechenable"] != null)
MainV2.speechEnable = bool.Parse(config["speechenable"].ToString());
//int fixme;
/*
- MainV2.cs.rateattitude = 50;
- MainV2.cs.rateposition = 50;
- MainV2.cs.ratestatus = 50;
- MainV2.cs.raterc = 50;
- MainV2.cs.ratesensors = 50;
+ MainV2.comPort.MAV.cs.rateattitude = 50;
+ MainV2.comPort.MAV.cs.rateposition = 50;
+ MainV2.comPort.MAV.cs.ratestatus = 50;
+ MainV2.comPort.MAV.cs.raterc = 50;
+ MainV2.comPort.MAV.cs.ratesensors = 50;
*/
try
{
if (config["TXT_homelat"] != null)
- cs.HomeLocation.Lat = double.Parse(config["TXT_homelat"].ToString());
+ MainV2.comPort.MAV.cs.HomeLocation.Lat = double.Parse(config["TXT_homelat"].ToString());
if (config["TXT_homelng"] != null)
- cs.HomeLocation.Lng = double.Parse(config["TXT_homelng"].ToString());
+ MainV2.comPort.MAV.cs.HomeLocation.Lng = double.Parse(config["TXT_homelng"].ToString());
if (config["TXT_homealt"] != null)
- cs.HomeLocation.Alt = double.Parse(config["TXT_homealt"].ToString());
+ MainV2.comPort.MAV.cs.HomeLocation.Alt = double.Parse(config["TXT_homealt"].ToString());
}
catch { }
}
catch { }
- if (cs.rateattitude == 0) // initilised to 10, configured above from save
+ if (MainV2.comPort.MAV.cs.rateattitude == 0) // initilised to 10, configured above from save
{
CustomMessageBox.Show("NOTE: your attitude rate is 0, the hud will not work\nChange in Configuration > Planner > Telemetry Rates");
}
-
//System.Threading.Thread.Sleep(2000);
// make sure new enough .net framework is installed
@@ -484,7 +478,7 @@ namespace ArdupilotMega
giveComport = false;
// sanity check
- if (comPort.BaseStream.IsOpen && cs.groundspeed > 4)
+ if (comPort.BaseStream.IsOpen && MainV2.comPort.MAV.cs.groundspeed > 4)
{
if (DialogResult.No == CustomMessageBox.Show("Your model is still moving are you sure you want to disconnect?", "Disconnect", MessageBoxButtons.YesNo))
{
@@ -601,17 +595,17 @@ namespace ArdupilotMega
comPort.Open(true);
// detect firmware we are conected to.
- if (comPort.param["SYSID_SW_TYPE"] != null)
+ if (comPort.MAV.param["SYSID_SW_TYPE"] != null)
{
- if (float.Parse(comPort.param["SYSID_SW_TYPE"].ToString()) == 10)
+ if (float.Parse(comPort.MAV.param["SYSID_SW_TYPE"].ToString()) == 10)
{
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduCopter2);
}
- else if (float.Parse(comPort.param["SYSID_SW_TYPE"].ToString()) == 20)
+ else if (float.Parse(comPort.MAV.param["SYSID_SW_TYPE"].ToString()) == 20)
{
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduRover);
}
- else if (float.Parse(comPort.param["SYSID_SW_TYPE"].ToString()) == 0)
+ else if (float.Parse(comPort.MAV.param["SYSID_SW_TYPE"].ToString()) == 0)
{
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduPlane);
}
@@ -779,7 +773,7 @@ namespace ArdupilotMega
xmlwriter.WriteElementString("baudrate", _connectionControl.CMB_baudrate.Text);
- xmlwriter.WriteElementString("APMFirmware", MainV2.cs.firmware.ToString());
+ xmlwriter.WriteElementString("APMFirmware", MainV2.comPort.MAV.cs.firmware.ToString());
foreach (string key in config.Keys)
{
@@ -839,7 +833,7 @@ namespace ArdupilotMega
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.FindStringExact(temp3);
if (_connectionControl.TOOL_APMFirmware.SelectedIndex == -1)
_connectionControl.TOOL_APMFirmware.SelectedIndex = 0;
- MainV2.cs.firmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), _connectionControl.TOOL_APMFirmware.Text);
+ MainV2.comPort.MAV.cs.firmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), _connectionControl.TOOL_APMFirmware.Text);
break;
case "Config":
break;
@@ -907,40 +901,40 @@ namespace ArdupilotMega
{
MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
- rc.target_component = comPort.compid;
- rc.target_system = comPort.sysid;
+ rc.target_component = comPort.MAV.compid;
+ rc.target_system = comPort.MAV.sysid;
if (joystick.getJoystickAxis(1) != Joystick.joystickaxis.None)
- rc.chan1_raw = cs.rcoverridech1;//(ushort)(((int)state.Rz / 65.535) + 1000);
+ rc.chan1_raw = MainV2.comPort.MAV.cs.rcoverridech1;//(ushort)(((int)state.Rz / 65.535) + 1000);
if (joystick.getJoystickAxis(2) != Joystick.joystickaxis.None)
- rc.chan2_raw = cs.rcoverridech2;//(ushort)(((int)state.Y / 65.535) + 1000);
+ rc.chan2_raw = MainV2.comPort.MAV.cs.rcoverridech2;//(ushort)(((int)state.Y / 65.535) + 1000);
if (joystick.getJoystickAxis(3) != Joystick.joystickaxis.None)
- rc.chan3_raw = cs.rcoverridech3;//(ushort)(1000 - ((int)slider[0] / 65.535 ) + 1000);
+ rc.chan3_raw = MainV2.comPort.MAV.cs.rcoverridech3;//(ushort)(1000 - ((int)slider[0] / 65.535 ) + 1000);
if (joystick.getJoystickAxis(4) != Joystick.joystickaxis.None)
- rc.chan4_raw = cs.rcoverridech4;//(ushort)(((int)state.X / 65.535) + 1000);
+ rc.chan4_raw = MainV2.comPort.MAV.cs.rcoverridech4;//(ushort)(((int)state.X / 65.535) + 1000);
if (joystick.getJoystickAxis(5) != Joystick.joystickaxis.None)
- rc.chan5_raw = cs.rcoverridech5;
+ rc.chan5_raw = MainV2.comPort.MAV.cs.rcoverridech5;
if (joystick.getJoystickAxis(6) != Joystick.joystickaxis.None)
- rc.chan6_raw = cs.rcoverridech6;
+ rc.chan6_raw = MainV2.comPort.MAV.cs.rcoverridech6;
if (joystick.getJoystickAxis(7) != Joystick.joystickaxis.None)
- rc.chan7_raw = cs.rcoverridech7;
+ rc.chan7_raw = MainV2.comPort.MAV.cs.rcoverridech7;
if (joystick.getJoystickAxis(8) != Joystick.joystickaxis.None)
- rc.chan8_raw = cs.rcoverridech8;
+ rc.chan8_raw = MainV2.comPort.MAV.cs.rcoverridech8;
if (lastjoystick.AddMilliseconds(rate) < DateTime.Now)
{
/*
- if (cs.rssi > 0 && cs.remrssi > 0)
+ if (MainV2.comPort.MAV.cs.rssi > 0 && MainV2.comPort.MAV.cs.remrssi > 0)
{
if (lastratechange.Second != DateTime.Now.Second)
{
- if (cs.txbuffer > 90)
+ if (MainV2.comPort.MAV.cs.txbuffer > 90)
{
if (rate < 20)
rate = 21;
rate--;
- if (cs.linkqualitygcs < 70)
+ if (MainV2.comPort.MAV.cs.linkqualitygcs < 70)
rate = 50;
}
else
@@ -1052,13 +1046,13 @@ namespace ArdupilotMega
UpdateConnectIcon();
// 30 seconds interval speech options
- if (speechEnable && speechEngine != null && (DateTime.Now - speechcustomtime).TotalSeconds > 30 && MainV2.cs.lat != 0 && (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
+ if (speechEnable && speechEngine != null && (DateTime.Now - speechcustomtime).TotalSeconds > 30 && MainV2.comPort.MAV.cs.lat != 0 && (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
{
//speechbatteryvolt
float warnvolt = 0;
float.TryParse(MainV2.getConfig("speechbatteryvolt"), out warnvolt);
- if (MainV2.getConfig("speechbatteryenabled") == "True" && MainV2.cs.battery_voltage <= warnvolt)
+ if (MainV2.getConfig("speechbatteryenabled") == "True" && MainV2.comPort.MAV.cs.battery_voltage <= warnvolt)
{
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechbattery")));
}
@@ -1078,7 +1072,7 @@ namespace ArdupilotMega
float.TryParse(MainV2.getConfig("speechaltheight"), out warnalt);
try
{
- if (MainV2.getConfig("speechaltenabled") == "True" && (MainV2.cs.alt - (int)double.Parse(MainV2.getConfig("TXT_homealt"))) <= warnalt)
+ if (MainV2.getConfig("speechaltenabled") == "True" && (MainV2.comPort.MAV.cs.alt - (int)double.Parse(MainV2.getConfig("TXT_homealt"))) <= warnalt)
{
if (MainV2.speechEngine.State == SynthesizerState.Ready)
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechalt")));
@@ -1097,7 +1091,7 @@ namespace ArdupilotMega
// make sure we attenuate the link quality if we dont see any valid packets
if ((DateTime.Now - comPort.lastvalidpacket).TotalSeconds > 10)
{
- MainV2.cs.linkqualitygcs = 0;
+ MainV2.comPort.MAV.cs.linkqualitygcs = 0;
}
// attenuate the link qualty over time
@@ -1105,7 +1099,7 @@ namespace ArdupilotMega
{
if (linkqualitytime.Second != DateTime.Now.Second)
{
- MainV2.cs.linkqualitygcs = (ushort)(MainV2.cs.linkqualitygcs * 0.8f);
+ MainV2.comPort.MAV.cs.linkqualitygcs = (ushort)(MainV2.comPort.MAV.cs.linkqualitygcs * 0.8f);
linkqualitytime = DateTime.Now;
GCSViews.FlightData.myhud.Invalidate();
@@ -1196,7 +1190,7 @@ namespace ArdupilotMega
}
using (Pen pen = new Pen(Color.Black))
{
- //e.Graphics.DrawRectangle(pen, bounds.X, bounds.Y, bounds.Width - 1, bounds.Height - 1);
+ //e.GraphiMainV2.comPort.MAV.cs.DrawRectangle(pen, bounds.X, bounds.Y, bounds.Width - 1, bounds.Height - 1);
}
}
}
@@ -1209,6 +1203,18 @@ namespace ArdupilotMega
private void MainV2_Load(object sender, EventArgs e)
{
+ // check if its defined, and force to show it if not known about
+ if (config["menu_autohide"] == null)
+ {
+ config["menu_autohide"] = "false";
+ }
+
+ try
+ {
+ AutoHideMenu(bool.Parse(config["menu_autohide"].ToString()));
+ }
+ catch { }
+
MyView.AddScreen(new MainSwitcher.Screen("FlightData", FlightData, true));
MyView.AddScreen(new MainSwitcher.Screen("FlightPlanner", FlightPlanner, true));
MyView.AddScreen(new MainSwitcher.Screen("Config", new GCSViews.ConfigurationView.Setup(), false));
@@ -1221,6 +1227,7 @@ namespace ArdupilotMega
//int fixme;
MenuFlightData_Click(sender, e);
+
// for long running tasks using own threads.
// for short use threadpool
@@ -1384,7 +1391,7 @@ namespace ArdupilotMega
byte[] packet = new byte[256];
- string sendme = cs.roll + "," + cs.pitch + "," + cs.yaw;
+ string sendme = MainV2.comPort.MAV.cs.roll + "," + MainV2.comPort.MAV.cs.pitch + "," + MainV2.comPort.MAV.cs.yaw;
packet[0] = 0x81; // fin - binary
packet[1] = (byte)sendme.Length;
@@ -1427,17 +1434,17 @@ namespace ArdupilotMega
pmplane.Visibility = true;
SharpKml.Dom.Location loc = new SharpKml.Dom.Location();
- loc.Latitude = cs.lat;
- loc.Longitude = cs.lng;
- loc.Altitude = cs.alt;
+ loc.Latitude = MainV2.comPort.MAV.cs.lat;
+ loc.Longitude = MainV2.comPort.MAV.cs.lng;
+ loc.Altitude = MainV2.comPort.MAV.cs.alt;
if (loc.Altitude < 0)
loc.Altitude = 0.01;
SharpKml.Dom.Orientation ori = new SharpKml.Dom.Orientation();
- ori.Heading = cs.yaw;
- ori.Roll = -cs.roll;
- ori.Tilt = -cs.pitch;
+ ori.Heading = MainV2.comPort.MAV.cs.yaw;
+ ori.Roll = -MainV2.comPort.MAV.cs.roll;
+ ori.Tilt = -MainV2.comPort.MAV.cs.pitch;
SharpKml.Dom.Scale sca = new SharpKml.Dom.Scale();
@@ -1464,7 +1471,7 @@ namespace ArdupilotMega
Latitude = loc.Latitude.Value,
Longitude = loc.Longitude.Value,
Tilt = 80,
- Heading = cs.yaw,
+ Heading = MainV2.comPort.MAV.cs.yaw,
AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute,
Range = 50
};
@@ -1475,7 +1482,7 @@ namespace ArdupilotMega
SharpKml.Dom.CoordinateCollection coords = new SharpKml.Dom.CoordinateCollection();
- foreach (var point in MainV2.comPort.wps.Values)
+ foreach (var point in MainV2.comPort.MAV.wps.Values)
{
coords.Add(new SharpKml.Base.Vector(point.x, point.y, point.z));
}
@@ -1635,7 +1642,7 @@ namespace ArdupilotMega
private void TOOL_APMFirmware_SelectedIndexChanged(object sender, EventArgs e)
{
- MainV2.cs.firmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), _connectionControl.TOOL_APMFirmware.Text);
+ MainV2.comPort.MAV.cs.firmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), _connectionControl.TOOL_APMFirmware.Text);
}
private void MainV2_Resize(object sender, EventArgs e)
@@ -2257,19 +2264,19 @@ namespace ArdupilotMega
switch ((Common.distances)Enum.Parse(typeof(Common.distances), MainV2.config["distunits"].ToString()))
{
case Common.distances.Meters:
- MainV2.cs.multiplierdist = 1;
- MainV2.cs.DistanceUnit = "Meters";
+ MainV2.comPort.MAV.cs.multiplierdist = 1;
+ MainV2.comPort.MAV.cs.DistanceUnit = "Meters";
break;
case Common.distances.Feet:
- MainV2.cs.multiplierdist = 3.2808399f;
- MainV2.cs.DistanceUnit = "Feet";
+ MainV2.comPort.MAV.cs.multiplierdist = 3.2808399f;
+ MainV2.comPort.MAV.cs.DistanceUnit = "Feet";
break;
}
}
else
{
- MainV2.cs.multiplierdist = 1;
- MainV2.cs.DistanceUnit = "Meters";
+ MainV2.comPort.MAV.cs.multiplierdist = 1;
+ MainV2.comPort.MAV.cs.DistanceUnit = "Meters";
}
// speed
@@ -2278,31 +2285,31 @@ namespace ArdupilotMega
switch ((Common.speeds)Enum.Parse(typeof(Common.speeds), MainV2.config["speedunits"].ToString()))
{
case Common.speeds.ms:
- MainV2.cs.multiplierspeed = 1;
- MainV2.cs.SpeedUnit = "m/s";
+ MainV2.comPort.MAV.cs.multiplierspeed = 1;
+ MainV2.comPort.MAV.cs.SpeedUnit = "m/s";
break;
case Common.speeds.fps:
- MainV2.cs.multiplierdist = 3.2808399f;
- MainV2.cs.SpeedUnit = "fps";
+ MainV2.comPort.MAV.cs.multiplierdist = 3.2808399f;
+ MainV2.comPort.MAV.cs.SpeedUnit = "fps";
break;
case Common.speeds.kph:
- MainV2.cs.multiplierspeed = 3.6f;
- MainV2.cs.SpeedUnit = "kph";
+ MainV2.comPort.MAV.cs.multiplierspeed = 3.6f;
+ MainV2.comPort.MAV.cs.SpeedUnit = "kph";
break;
case Common.speeds.mph:
- MainV2.cs.multiplierspeed = 2.23693629f;
- MainV2.cs.SpeedUnit = "mph";
+ MainV2.comPort.MAV.cs.multiplierspeed = 2.23693629f;
+ MainV2.comPort.MAV.cs.SpeedUnit = "mph";
break;
case Common.speeds.knots:
- MainV2.cs.multiplierspeed = 1.94384449f;
- MainV2.cs.SpeedUnit = "knots";
+ MainV2.comPort.MAV.cs.multiplierspeed = 1.94384449f;
+ MainV2.comPort.MAV.cs.SpeedUnit = "knots";
break;
}
}
else
{
- MainV2.cs.multiplierspeed = 1;
- MainV2.cs.SpeedUnit = "m/s";
+ MainV2.comPort.MAV.cs.multiplierspeed = 1;
+ MainV2.comPort.MAV.cs.SpeedUnit = "m/s";
}
}
catch { }
@@ -2359,5 +2366,42 @@ namespace ArdupilotMega
panel1.Visible = true;
this.ResumeLayout();
}
+
+ private void autoHideToolStripMenuItem_Click(object sender, EventArgs e)
+ {
+ AutoHideMenu(autoHideToolStripMenuItem.Checked);
+
+ config["menu_autohide"] = autoHideToolStripMenuItem.Checked.ToString();
+ }
+
+ void AutoHideMenu(bool hide)
+ {
+ autoHideToolStripMenuItem.Checked = hide;
+
+ if (!hide)
+ {
+ this.SuspendLayout();
+ panel1.Dock = DockStyle.Top;
+ panel1.SendToBack();
+ panel1.Visible = true;
+ menu.Visible = false;
+ MainMenu.MouseLeave -= MainMenu_MouseLeave;
+ panel1.MouseLeave -= MainMenu_MouseLeave;
+ toolStripConnectionControl.MouseLeave -= MainMenu_MouseLeave;
+ this.ResumeLayout();
+ }
+ else
+ {
+ this.SuspendLayout();
+ panel1.Dock = DockStyle.None;
+ panel1.Visible = false;
+ MainMenu.MouseLeave += MainMenu_MouseLeave;
+ panel1.MouseLeave += MainMenu_MouseLeave;
+ toolStripConnectionControl.MouseLeave += MainMenu_MouseLeave;
+ menu.Visible = true;
+ menu.SendToBack();
+ this.ResumeLayout();
+ }
+ }
}
}
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/MainV2.resx b/Tools/ArdupilotMegaPlanner/MainV2.resx
index c0e0c546ed..e80ecac7fb 100644
--- a/Tools/ArdupilotMegaPlanner/MainV2.resx
+++ b/Tools/ArdupilotMegaPlanner/MainV2.resx
@@ -178,6 +178,9 @@
F7RNPD7QJqsL9YCOnc3vfuwBNe17h7wL9uHpUD//2Q==
+
+ 127, 17
+
46
diff --git a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs
index 29f909b045..cf036b67f6 100644
--- a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs
+++ b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs
@@ -25,6 +25,90 @@ namespace ArdupilotMega
public ICommsSerial BaseStream { get; set; }
public event EventHandler ParamListChanged;
+ ///
+ /// mavlink remote sysid
+ ///
+ public byte sysid { get { return MAV.sysid; } set { MAV.sysid = value; } }
+ ///
+ /// mavlink remove compid
+ ///
+ public byte compid { get { return MAV.compid; } set { MAV.compid = value; } }
+ ///
+ /// storage for whole paramater list
+ ///
+ public Hashtable param { get { return MAV.param; } set { MAV.param = value; } }
+ ///
+ /// storage of a previous packet recevied of a specific type
+ ///
+ public byte[][] packets { get { return MAV.packets; } set { MAV.packets = value; } }
+ ///
+ /// mavlink ap type
+ ///
+ public MAV_TYPE aptype { get { return MAV.aptype; } set { MAV.aptype = value; } }
+ public MAV_AUTOPILOT apname { get { return MAV.apname; } set { MAV.apname = value; } }
+ ///
+ /// used as a snapshot of what is loaded on the ap atm. - derived from the stream
+ ///
+ public Dictionary wps { get { return MAV.wps; } set { MAV.wps = value; } }
+ ///
+ /// Store the guided mode wp location
+ ///
+ public mavlink_mission_item_t GuidedMode { get { return MAV.GuidedMode; } set { MAV.GuidedMode = value; } }
+
+ internal int recvpacketcount { get { return MAV.recvpacketcount; } set { MAV.recvpacketcount = value; } }
+
+ public MAVState MAV = new MAVState();
+
+ public class MAVState
+ {
+ public MAVState()
+ {
+ this.sysid = 0;
+ this.compid = 0;
+ this.param = new Hashtable();
+ this.packets = new byte[0x100][];
+ this.aptype = 0;
+ this.apname = 0;
+ this.recvpacketcount = 0;
+ }
+
+ ///
+ /// the static global state of the currently connected MAV
+ ///
+ public CurrentState cs = new CurrentState();
+ ///
+ /// mavlink remote sysid
+ ///
+ public byte sysid { get; set; }
+ ///
+ /// mavlink remove compid
+ ///
+ public byte compid { get; set; }
+ ///
+ /// storage for whole paramater list
+ ///
+ public Hashtable param { get; set; }
+ ///
+ /// storage of a previous packet recevied of a specific type
+ ///
+ public byte[][] packets { get; set; }
+ ///
+ /// mavlink ap type
+ ///
+ public MAV_TYPE aptype { get; set; }
+ public MAV_AUTOPILOT apname { get; set; }
+ ///
+ /// used as a snapshot of what is loaded on the ap atm. - derived from the stream
+ ///
+ public Dictionary wps = new Dictionary();
+ ///
+ /// Store the guided mode wp location
+ ///
+ public mavlink_mission_item_t GuidedMode = new mavlink_mission_item_t();
+
+ internal int recvpacketcount = 0;
+ }
+
private const double CONNECT_TIMEOUT_SECONDS = 30;
///
@@ -36,22 +120,7 @@ namespace ArdupilotMega
/// used for outbound packet sending
///
byte packetcount = 0;
- ///
- /// mavlink remote sysid
- ///
- public byte sysid { get; set; }
- ///
- /// mavlink remove compid
- ///
- public byte compid { get; set; }
- ///
- /// storage for whole paramater list
- ///
- public Hashtable param { get; set; }
- ///
- /// storage of a previous packet recevied of a specific type
- ///
- public byte[][] packets { get; set; }
+
///
/// used to calc packets per second on any single message type - used for stream rate comparaison
///
@@ -105,19 +174,7 @@ namespace ArdupilotMega
/// mavlink version
///
byte mavlinkversion = 0;
- ///
- /// mavlink ap type
- ///
- public MAV_TYPE aptype { get; set; }
- public MAV_AUTOPILOT apname { get; set; }
- ///
- /// used as a snapshot of what is loaded on the ap atm. - derived from the stream
- ///
- public Dictionary wps = new Dictionary();
- ///
- /// Store the guided mode wp location
- ///
- public mavlink_mission_item_t GuidedMode = new mavlink_mission_item_t();
+
///
/// turns on console packet display
///
@@ -135,7 +192,6 @@ namespace ArdupilotMega
int bps2 = 0;
public int bps { get; set; }
public DateTime bpstime { get; set; }
- int recvpacketcount = 0;
float synclost;
float packetslost = 0;
@@ -147,10 +203,7 @@ namespace ArdupilotMega
// init fields
this.BaseStream = new SerialPort();
this.packetcount = 0;
- this.sysid = 0;
- this.compid = 0;
- this.param = new Hashtable();
- this.packets = new byte[0x100][];
+
this.packetspersecond = new double[0x100];
this.packetspersecondbuild = new DateTime[0x100];
this._bytesReceivedSubj = new Subject();
@@ -161,8 +214,7 @@ namespace ArdupilotMega
this.lastvalidpacket = DateTime.Now;
this.oldlogformat = false;
this.mavlinkversion = 0;
- this.aptype = 0;
- this.apname = 0;
+
this.debugmavlink = false;
this.logreadmode = false;
this.lastlogread = DateTime.MinValue;
@@ -173,7 +225,7 @@ namespace ArdupilotMega
this.bps2 = 0;
this.bps = 0;
this.bpstime = DateTime.Now;
- this.recvpacketcount = 0;
+
this.packetslost = 0f;
this.packetsnotlost = 0f;
this.packetlosttimer = DateTime.Now;
@@ -1600,7 +1652,7 @@ namespace ArdupilotMega
loc.lat = ((wp.x));
loc.lng = ((wp.y));
/*
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane)
{
switch (loc.id)
{ // Switch to map APM command fields inot MAVLink command fields
@@ -2239,7 +2291,7 @@ namespace ArdupilotMega
}
else
{
- MainV2.cs.datetime = DateTime.Now;
+ MainV2.comPort.MAV.cs.datetime = DateTime.Now;
DateTime to = DateTime.Now.AddMilliseconds(BaseStream.ReadTimeout);
@@ -2386,7 +2438,7 @@ namespace ArdupilotMega
packetsnotlost = (packetsnotlost * 0.8f);
}
- MainV2.cs.linkqualitygcs = (ushort)((packetsnotlost / (packetsnotlost + packetslost)) * 100.0);
+ MainV2.comPort.MAV.cs.linkqualitygcs = (ushort)((packetsnotlost / (packetsnotlost + packetslost)) * 100.0);
if (bpstime.Second != DateTime.Now.Second && !logreadmode)
{
@@ -2758,7 +2810,7 @@ namespace ArdupilotMega
}
catch { }
- MainV2.cs.datetime = lastlogread;
+ MainV2.comPort.MAV.cs.datetime = lastlogread;
int length = 5;
int a = 0;
@@ -2795,7 +2847,7 @@ namespace ArdupilotMega
public bool translateMode(string modein, ref MAVLink.mavlink_set_mode_t mode)
{
//MAVLink09.mavlink_set_mode_t mode = new MAVLink09.mavlink_set_mode_t();
- mode.target_system = MainV2.comPort.sysid;
+ mode.target_system = MainV2.comPort.MAV.sysid;
try
{
@@ -2855,13 +2907,13 @@ namespace ArdupilotMega
switch (aptype)
{
case MAVLink.MAV_TYPE.FIXED_WING:
- MainV2.cs.firmware = MainV2.Firmwares.ArduPlane;
+ MainV2.comPort.MAV.cs.firmware = MainV2.Firmwares.ArduPlane;
break;
case MAVLink.MAV_TYPE.QUADROTOR:
- MainV2.cs.firmware = MainV2.Firmwares.ArduCopter2;
+ MainV2.comPort.MAV.cs.firmware = MainV2.Firmwares.ArduCopter2;
break;
case MAVLink.MAV_TYPE.GROUND_ROVER:
- MainV2.cs.firmware = MainV2.Firmwares.ArduRover;
+ MainV2.comPort.MAV.cs.firmware = MainV2.Firmwares.ArduRover;
break;
default:
break;
diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
index 854d08ce99..af82d9a427 100644
--- a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
+++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
@@ -59,11 +59,11 @@ namespace ArdupilotMega
{
SharpKml.Dom.AltitudeMode altmode = SharpKml.Dom.AltitudeMode.Absolute;
- if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane || MainV2.cs.firmware == MainV2.Firmwares.ArduRover)
+ if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduPlane || MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduRover)
{
altmode = SharpKml.Dom.AltitudeMode.Absolute;
}
- else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ else if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
altmode = SharpKml.Dom.AltitudeMode.RelativeToGround;
}
@@ -392,7 +392,7 @@ namespace ArdupilotMega
catch (Exception ex) { log.Debug(ex.ToString()); CustomMessageBox.Show("Log Can not be opened. Are you still connected?"); return; }
mine.logreadmode = true;
- mine.packets.Initialize(); // clear
+ mine.MAV.packets.Initialize(); // clear
CurrentState cs = new CurrentState();
@@ -561,7 +561,7 @@ namespace ArdupilotMega
mine.logreadmode = true;
- mine.packets.Initialize(); // clear
+ mine.MAV.packets.Initialize(); // clear
StreamWriter sw = new StreamWriter(Path.GetDirectoryName(logfile)+ Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(logfile) + ".txt");
@@ -676,7 +676,7 @@ namespace ArdupilotMega
catch (Exception ex) { log.Debug(ex.ToString()); CustomMessageBox.Show("Log Can not be opened. Are you still connected?"); return options; }
MavlinkInterface.logreadmode = true;
- MavlinkInterface.packets.Initialize(); // clear
+ MavlinkInterface.MAV.packets.Initialize(); // clear
CurrentState cs = new CurrentState();
@@ -1235,7 +1235,7 @@ namespace ArdupilotMega
catch (Exception ex) { log.Debug(ex.ToString()); CustomMessageBox.Show("Log Can not be opened. Are you still connected?"); return; }
mine.logreadmode = true;
- mine.packets.Initialize(); // clear
+ mine.MAV.packets.Initialize(); // clear
StreamWriter sw = new StreamWriter(Path.GetDirectoryName(logfile) + Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(logfile) + ".csv");
@@ -1300,7 +1300,7 @@ namespace ArdupilotMega
mine.logreadmode = true;
- mine.packets.Initialize(); // clear
+ mine.MAV.packets.Initialize(); // clear
StreamWriter sw = new StreamWriter(Path.GetDirectoryName(logfile) + Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(logfile) + ".param");
@@ -1312,9 +1312,9 @@ namespace ArdupilotMega
mine.getParamList();
- foreach (string item in mine.param.Keys)
+ foreach (string item in mine.MAV.param.Keys)
{
- sw.WriteLine(item + "\t" + mine.param[item]);
+ sw.WriteLine(item + "\t" + mine.MAV.param[item]);
}
sw.Close();
@@ -1367,7 +1367,7 @@ namespace ArdupilotMega
mine.logreadmode = true;
- mine.packets.Initialize(); // clear
+ mine.MAV.packets.Initialize(); // clear
while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
{
@@ -1407,7 +1407,7 @@ namespace ArdupilotMega
sw.Write("\t" + wp.p4.ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write("\t" + wp.lat.ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write("\t" + wp.lng.ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
- sw.Write("\t" + (wp.alt / MainV2.cs.multiplierdist).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
+ sw.Write("\t" + (wp.alt / MainV2.comPort.MAV.cs.multiplierdist).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
sw.Write("\t" + 1);
sw.WriteLine("");
}
diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
index 530a0154d7..11009f7b2e 100644
--- a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
+++ b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
@@ -2,14 +2,14 @@
-
+
-
-
+
+
@@ -31,7 +31,7 @@
-
+
@@ -45,215 +45,223 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
+
+
+
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
-
-
-
-
-
+
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
-
-
-
-
-
-
-
+
+
+
+
+
+
+
-
-
-
+
+
+
-
-
-
-
+
+
+
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
+
+
+
+
+
+
@@ -311,26 +319,27 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
@@ -350,7 +359,7 @@
-
+
INS Lat Vel
INS Lon Vel
+
+ Time
+ Lat
+ Lon
+ Alt
+ Roll
+ Pitch
+ Yaw
+
Err
P
diff --git a/Tools/ArdupilotMegaPlanner/georefimage.cs b/Tools/ArdupilotMegaPlanner/georefimage.cs
index 37d125f812..4c9c044fe4 100644
--- a/Tools/ArdupilotMegaPlanner/georefimage.cs
+++ b/Tools/ArdupilotMegaPlanner/georefimage.cs
@@ -133,7 +133,7 @@ namespace ArdupilotMega
mine.logplaybackfile = new BinaryReader(File.Open(fn, FileMode.Open, FileAccess.Read, FileShare.Read));
mine.logreadmode = true;
- mine.packets.Initialize(); // clear
+ mine.MAV.packets.Initialize(); // clear
CurrentState cs = new CurrentState();