diff --git a/Tools/ArdupilotMegaPlanner/Antenna/DegreeTracker.cs b/Tools/ArdupilotMegaPlanner/Antenna/DegreeTracker.cs
new file mode 100644
index 0000000000..f138560967
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Antenna/DegreeTracker.cs
@@ -0,0 +1,130 @@
+using System;
+using System.Collections.Generic;
+using System.Linq;
+using System.Text;
+
+namespace ArdupilotMega.Antenna
+{
+ class DegreeTracker : ITrackerOutput
+ {
+ public Comms.SerialPort ComPort { get; set; }
+ ///
+ /// 0-360
+ ///
+ public double TrimPan { get; set; }
+ ///
+ /// -90 - 90
+ ///
+ public double TrimTilt { get; set; }
+
+ public int PanStartRange { get; set; }
+ public int TiltStartRange { get; set; }
+ public int PanEndRange { get; set; }
+ public int TiltEndRange { get; set; }
+ public int PanPWMRange { get; set; }
+ public int TiltPWMRange { get; set; }
+
+ public bool PanReverse { get { return _panreverse == 1; } set { _panreverse = value == true ? -1 : 1; } }
+ public bool TiltReverse { get { return _tiltreverse == 1; } set { _tiltreverse = value == true ? -1 : 1; } }
+
+ int _panreverse = 1;
+ int _tiltreverse = 1;
+
+ int currentpan = 1500;
+ int currenttilt = 1500;
+
+ public bool Init()
+ {
+
+/* if ((PanStartRange - PanEndRange) == 0)
+ {
+ System.Windows.Forms.CustomMessageBox.Show("Invalid Pan Range", "Error");
+ return false;
+ }
+
+ if ((TiltStartRange - TiltEndRange) == 0)
+ {
+ System.Windows.Forms.CustomMessageBox.Show("Invalid Tilt Range", "Error");
+ return false;
+ }
+*/
+ try
+ {
+ ComPort.Open();
+ }
+ catch (Exception ex) { System.Windows.Forms.CustomMessageBox.Show("Connect failed " + ex.Message, "Error"); return false; }
+
+ return true;
+ }
+ public bool Setup()
+ {
+
+
+ return true;
+ }
+
+ double wrap_180(double input)
+ {
+ if (input > 180)
+ return input - 360;
+ if (input < -180)
+ return input + 360;
+ return input;
+ }
+
+ double wrap_range(double input, double range)
+ {
+ if (input > range)
+ return input - 360;
+ if (input < -range)
+ return input + 360;
+ return input;
+ }
+
+ public bool Pan(double Angle)
+ {
+ currentpan = (int)(Angle*10);
+ return false;
+ }
+
+ public bool Tilt(double Angle)
+ {
+ currenttilt = (int)(Angle * 10);
+ return false;
+ }
+
+ public bool PanAndTilt(double pan, double tilt)
+ {
+ Tilt(tilt);
+ Pan(pan);
+
+ string command = string.Format("!!!PAN:{0:0000},TLT:{1:0000}\n", currentpan, currenttilt);
+
+ Console.Write(command);
+
+ ComPort.Write(command);
+
+ return false;
+ }
+
+ public bool Close()
+ {
+ try
+ {
+ ComPort.Close();
+ }
+ catch { }
+ return true;
+ }
+
+ short Constrain(double input, double min, double max)
+ {
+ if (input < min)
+ return (short)min;
+ if (input > max)
+ return (short)max;
+ return (short)input;
+ }
+
+ }
+}
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
index 8287d79f6a..3da8420be4 100644
--- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
+++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
@@ -21,7 +21,8 @@ namespace ArdupilotMega.Antenna
enum interfaces
{
Maestro,
- ArduTracker
+ ArduTracker,
+ DegreeTracker
}
public Tracker()
@@ -110,6 +111,8 @@ namespace ArdupilotMega.Antenna
tracker = new ArdupilotMega.Antenna.Maestro();
if (CMB_interface.Text == "ArduTracker")
tracker = new ArdupilotMega.Antenna.ArduTracker();
+ if (CMB_interface.Text == "DegreeTracker")
+ tracker = new ArdupilotMega.Antenna.DegreeTracker();
try
{
diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
index c75e804ae8..c60c66b4a6 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
@@ -232,6 +232,7 @@
+
diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs
index 62fffc9874..16b0c01977 100644
--- a/Tools/ArdupilotMegaPlanner/Common.cs
+++ b/Tools/ArdupilotMegaPlanner/Common.cs
@@ -818,6 +818,8 @@ namespace ArdupilotMega
form.Dispose();
+ form = null;
+
return dialogResult;
}
@@ -834,9 +836,11 @@ namespace ArdupilotMega
TextBox textBox = new TextBox();
ArdupilotMega.Controls.MyButton buttonOk = new ArdupilotMega.Controls.MyButton();
ArdupilotMega.Controls.MyButton buttonCancel = new ArdupilotMega.Controls.MyButton();
+ System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2));
+ form.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
form.TopMost = true;
- form.TopLevel = true;
+ //form.TopLevel = true;
form.Text = title;
label.Text = promptText;
@@ -861,7 +865,7 @@ namespace ArdupilotMega
form.Controls.AddRange(new Control[] { label, textBox, buttonOk, buttonCancel });
form.ClientSize = new Size(Math.Max(300, label.Right + 10), form.ClientSize.Height);
form.FormBorderStyle = FormBorderStyle.FixedDialog;
- form.StartPosition = FormStartPosition.CenterScreen;
+ form.StartPosition = FormStartPosition.CenterParent;
form.MinimizeBox = false;
form.MaximizeBox = false;
form.AcceptButton = buttonOk;
@@ -871,7 +875,9 @@ namespace ArdupilotMega
DialogResult dialogResult = DialogResult.Cancel;
- dialogResult = form.ShowDialog();
+ form.ShowDialog();
+
+ dialogResult = form.DialogResult;
if (dialogResult == DialogResult.OK)
{
@@ -879,6 +885,8 @@ namespace ArdupilotMega
}
form.Dispose();
+
+ form = null;
return dialogResult;
}
diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs
index 2514a96868..c5f1d1dbe4 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs
@@ -33,6 +33,8 @@ namespace ArdupilotMega.Controls.BackstageView
public List Pages { get { return _items.OfType().ToList(); } }
+ private BackstageViewPage popoutPage = null;
+
public BackstageView()
{
InitializeComponent();
@@ -247,6 +249,8 @@ namespace ArdupilotMega.Controls.BackstageView
popoutForm.Text = associatedPage.LinkText;
+ popoutPage = associatedPage;
+
popoutForm.BackColor = this.BackColor;
popoutForm.ForeColor = this.ForeColor;
@@ -263,6 +267,7 @@ namespace ArdupilotMega.Controls.BackstageView
// clear the controls, so we dont dispose the good control when it closes
((Form)sender).Controls.Clear();
+ popoutPage = null;
}
private void ButtonClick(object sender, EventArgs e)
@@ -314,6 +319,9 @@ namespace ArdupilotMega.Controls.BackstageView
{
foreach (var page in _items)
{
+ if (popoutPage != null && popoutPage == page)
+ continue;
+
if (((BackstageViewPage)page).Page is IDeactivate)
{
((IDeactivate)((BackstageViewPage)(page)).Page).Deactivate();
diff --git a/Tools/ArdupilotMegaPlanner/Controls/ConnectionStats.cs b/Tools/ArdupilotMegaPlanner/Controls/ConnectionStats.cs
index 5705d01048..07cd92560e 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/ConnectionStats.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/ConnectionStats.cs
@@ -39,6 +39,10 @@ namespace ArdupilotMega.Controls
.Buffer(TimeSpan.FromSeconds(1))
.Select(bytes => bytes.Sum());
+ var bytesSentEverySecond = _mavlink.BytesSent
+ .Buffer(TimeSpan.FromSeconds(1))
+ .Select(bytes => bytes.Sum());
+
var subscriptions = new List
{
// Total number of packets received
@@ -94,7 +98,7 @@ namespace ArdupilotMega.Controls
.Select(ToHumanReadableByteCount)
.SubscribeForTextUpdates(txt_BytesSent),
- _mavlink.BytesSent
+ bytesSentEverySecond
.Buffer(TimeSpan.FromSeconds(5), TimeSpan.FromSeconds(1))
.Select(xs => xs.Any() ? xs.Average() : 0)
.Select(x => ToHumanReadableByteCount((int) x))
diff --git a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
index ec35999fb3..90d0e8febd 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
@@ -104,20 +104,20 @@ namespace System.Windows.Forms
Console.WriteLine("CustomMessageBox 1");
- if (System.Windows.Forms.Application.OpenForms.Count > 0)
+ /* if (System.Windows.Forms.Application.OpenForms.Count > 0)
{
msgBoxFrm.StartPosition = FormStartPosition.Manual;
Form parentForm = System.Windows.Forms.Application.OpenForms[0];
// center of first form
msgBoxFrm.Location = new Point(parentForm.Location.X + parentForm.Width / 2 - msgBoxFrm.Width / 2,
parentForm.Location.Y + parentForm.Height / 2 - msgBoxFrm.Height / 2);
- Console.WriteLine("CustomMessageBox 2a");
- DialogResult test = msgBoxFrm.ShowDialog(null);
+ Console.WriteLine("CustomMessageBox 2a " + parentForm.Name);
+ DialogResult test = msgBoxFrm.ShowDialog();
}
- else
+ else*/
{
Console.WriteLine("CustomMessageBox 2b");
- DialogResult test = msgBoxFrm.ShowDialog(null);
+ DialogResult test = msgBoxFrm.ShowDialog();
}
Console.WriteLine("CustomMessageBox 3");
diff --git a/Tools/ArdupilotMegaPlanner/Controls/HUD.cs b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs
index f553075732..fc1494ae16 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/HUD.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs
@@ -184,7 +184,7 @@ namespace ArdupilotMega.Controls
{
if (!ThisReallyVisible())
{
- return;
+ // return;
}
//base.Refresh();
@@ -198,7 +198,7 @@ namespace ArdupilotMega.Controls
{
if (!ThisReallyVisible())
{
- return;
+ // return;
}
base.Invalidate();
diff --git a/Tools/ArdupilotMegaPlanner/Controls/MainSwitcher.cs b/Tools/ArdupilotMegaPlanner/Controls/MainSwitcher.cs
index 8fa9f8b47d..f298cb9e82 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/MainSwitcher.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/MainSwitcher.cs
@@ -41,14 +41,14 @@ namespace ArdupilotMega.Controls
// remove reference
this.Controls.Remove(current.Control);
+ if (current.Control is IDeactivate)
+ {
+ ((IDeactivate)(current.Control)).Deactivate();
+ }
+
// check if we need to remove the current control
if (!current.Persistent)
{
- if (current.Control is IDeactivate)
- {
- ((IDeactivate)(current.Control)).Deactivate();
- }
-
// cleanup
current.Control.Close();
diff --git a/Tools/ArdupilotMegaPlanner/Controls/MavlinkCheckBox.cs b/Tools/ArdupilotMegaPlanner/Controls/MavlinkCheckBox.cs
index 2e13736f3e..920c5fbb01 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/MavlinkCheckBox.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/MavlinkCheckBox.cs
@@ -9,6 +9,8 @@ namespace ArdupilotMega.Controls
{
public class MavlinkCheckBox : CheckBox
{
+ public new event EventHandler CheckedChanged;
+
[System.ComponentModel.Browsable(true)]
public float OnValue { get; set; }
@@ -77,6 +79,9 @@ namespace ArdupilotMega.Controls
void MavlinkCheckBox_CheckedChanged(object sender, EventArgs e)
{
+ if (this.CheckedChanged != null)
+ this.CheckedChanged(sender, e);
+
if (this.Checked)
{
enableControl(true);
diff --git a/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs b/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs
index e6a2dec884..fc7aa6e667 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs
@@ -2,6 +2,8 @@
using System.ComponentModel;
using System.Threading;
using System.Windows.Forms;
+using System.Reflection;
+using log4net;
namespace ArdupilotMega.Controls
{
@@ -14,6 +16,8 @@ namespace ArdupilotMega.Controls
///
public partial class ProgressReporterDialogue : Form
{
+ private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
+
private Exception workerException;
public ProgressWorkerEventArgs doWorkArgs;
@@ -43,6 +47,8 @@ namespace ArdupilotMega.Controls
private void RunBackgroundOperation(object o)
{
+ log.Info("RunBackgroundOperation");
+
try
{
Thread.CurrentThread.Name = "ProgressReporterDialogue Background thread";
@@ -51,7 +57,11 @@ namespace ArdupilotMega.Controls
// mono fix - ensure the dialog is running
while (this.IsHandleCreated == false)
- System.Threading.Thread.Sleep(1);
+ {
+ System.Threading.Thread.Sleep(100);
+ }
+
+ log.Info("Focus ctl");
this.Invoke((MethodInvoker)delegate
{
@@ -62,7 +72,9 @@ namespace ArdupilotMega.Controls
try
{
+ log.Info("DoWork");
if (this.DoWork != null) this.DoWork(this, doWorkArgs);
+ log.Info("DoWork Done");
}
catch(Exception e)
{
@@ -241,6 +253,11 @@ namespace ArdupilotMega.Controls
}
}
+ private void ProgressReporterDialogue_Load(object sender, EventArgs e)
+ {
+ this.Focus();
+ }
+
}
public class ProgressWorkerEventArgs : EventArgs
diff --git a/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.designer.cs b/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.designer.cs
index 15e1bdaff6..b1bd159e62 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.designer.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.designer.cs
@@ -131,6 +131,7 @@ namespace ArdupilotMega.Controls
this.StartPosition = System.Windows.Forms.FormStartPosition.CenterParent;
this.Text = "Progress";
this.TopMost = true;
+ this.Load += new System.EventHandler(this.ProgressReporterDialogue_Load);
((System.ComponentModel.ISupportInitialize)(this.imgWarning)).EndInit();
this.ResumeLayout(false);
this.PerformLayout();
diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs
index 442cd0d880..7c38f54a3a 100644
--- a/Tools/ArdupilotMegaPlanner/CurrentState.cs
+++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs
@@ -325,6 +325,7 @@ namespace ArdupilotMega
public DateTime datetime { get; set; }
private object locker = new object();
+ bool useLocation = false;
public CurrentState()
{
@@ -721,8 +722,11 @@ namespace ArdupilotMega
{
var gps = bytearray.ByteArrayToStructure(6);
- lat = gps.lat * 1.0e-7f;
- lng = gps.lon * 1.0e-7f;
+ if (!useLocation)
+ {
+ lat = gps.lat * 1.0e-7f;
+ lng = gps.lon * 1.0e-7f;
+ }
// alt = gps.alt; // using vfr as includes baro calc
gpsstatus = gps.fix_type;
@@ -785,6 +789,8 @@ namespace ArdupilotMega
{
var loc = bytearray.ByteArrayToStructure(6);
+ useLocation = true;
+
//alt = loc.alt / 1000.0f;
lat = loc.lat / 10000000.0f;
lng = loc.lon / 10000000.0f;
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.Designer.cs
index 21b189ccbe..7ed6e03606 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.Designer.cs
@@ -30,24 +30,24 @@
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigAP_Limits));
this.LNK_wiki = new System.Windows.Forms.LinkLabel();
- this.LIM_ENABLED = new ArdupilotMega.Controls.MavlinkCheckBox();
+ this.LIM_ENABLED = new System.Windows.Forms.CheckBox();
this.groupBox1 = new System.Windows.Forms.GroupBox();
this.textBox1 = new System.Windows.Forms.TextBox();
this.groupBox5 = new System.Windows.Forms.GroupBox();
- this.LIM_GPSLCK_REQ = new ArdupilotMega.Controls.MavlinkCheckBox();
- this.LIM_FNC_REQ = new ArdupilotMega.Controls.MavlinkCheckBox();
- this.LIM_ALT_REQ = new ArdupilotMega.Controls.MavlinkCheckBox();
+ this.LIM_GPSLCK_REQ = new System.Windows.Forms.CheckBox();
+ this.LIM_FNC_REQ = new System.Windows.Forms.CheckBox();
+ this.LIM_ALT_REQ = new System.Windows.Forms.CheckBox();
this.groupBox4 = new System.Windows.Forms.GroupBox();
- this.LIM_REQUIRED = new ArdupilotMega.Controls.MavlinkCheckBox();
+ this.LIM_REQUIRED = new System.Windows.Forms.CheckBox();
this.myLabel4 = new ArdupilotMega.Controls.MyLabel();
this.LIM_CHANNEL = new System.Windows.Forms.NumericUpDown();
this.myLabel3 = new ArdupilotMega.Controls.MyLabel();
this.LIM_FNC_RAD = new System.Windows.Forms.NumericUpDown();
- this.LIM_FNC_SMPL = new ArdupilotMega.Controls.MavlinkCheckBox();
+ this.LIM_FNC_SMPL = new System.Windows.Forms.CheckBox();
this.groupBox3 = new System.Windows.Forms.GroupBox();
- this.LIM_GPSLCK_ON = new ArdupilotMega.Controls.MavlinkCheckBox();
+ this.LIM_GPSLCK_ON = new System.Windows.Forms.CheckBox();
this.groupBox2 = new System.Windows.Forms.GroupBox();
- this.LIM_ALT_ON = new ArdupilotMega.Controls.MavlinkCheckBox();
+ this.LIM_ALT_ON = new System.Windows.Forms.CheckBox();
this.myLabel1 = new ArdupilotMega.Controls.MyLabel();
this.LIM_ALT_MAX = new System.Windows.Forms.NumericUpDown();
this.myLabel2 = new ArdupilotMega.Controls.MyLabel();
@@ -281,28 +281,28 @@
#endregion
private System.Windows.Forms.LinkLabel LNK_wiki;
- private ArdupilotMega.Controls.MavlinkCheckBox LIM_ENABLED;
+ private System.Windows.Forms.CheckBox LIM_ENABLED;
private System.Windows.Forms.GroupBox groupBox1;
private Controls.MyLabel myLabel2;
private Controls.MyLabel myLabel1;
private System.Windows.Forms.NumericUpDown LIM_ALT_MAX;
private System.Windows.Forms.NumericUpDown LIM_ALT_MIN;
private System.Windows.Forms.GroupBox groupBox2;
- private ArdupilotMega.Controls.MavlinkCheckBox LIM_ALT_ON;
+ private System.Windows.Forms.CheckBox LIM_ALT_ON;
private System.Windows.Forms.GroupBox groupBox3;
- private ArdupilotMega.Controls.MavlinkCheckBox LIM_GPSLCK_ON;
+ private System.Windows.Forms.CheckBox LIM_GPSLCK_ON;
private System.Windows.Forms.GroupBox groupBox4;
private Controls.MyLabel myLabel3;
private System.Windows.Forms.NumericUpDown LIM_FNC_RAD;
- private ArdupilotMega.Controls.MavlinkCheckBox LIM_FNC_SMPL;
+ private System.Windows.Forms.CheckBox LIM_FNC_SMPL;
private Controls.MyLabel myLabel4;
private System.Windows.Forms.NumericUpDown LIM_CHANNEL;
- private ArdupilotMega.Controls.MavlinkCheckBox LIM_REQUIRED;
+ private System.Windows.Forms.CheckBox LIM_REQUIRED;
private System.Windows.Forms.GroupBox groupBox5;
- private ArdupilotMega.Controls.MavlinkCheckBox LIM_FNC_REQ;
- private ArdupilotMega.Controls.MavlinkCheckBox LIM_ALT_REQ;
+ private System.Windows.Forms.CheckBox LIM_FNC_REQ;
+ private System.Windows.Forms.CheckBox LIM_ALT_REQ;
private System.Windows.Forms.TextBox textBox1;
- private ArdupilotMega.Controls.MavlinkCheckBox LIM_GPSLCK_REQ;
+ private System.Windows.Forms.CheckBox LIM_GPSLCK_REQ;
}
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.cs
index 090de0a367..4254c0ac8b 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.cs
@@ -93,11 +93,13 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
Console.WriteLine(chk.Name + " "+ copy[key]);
chk.Checked = (float)copy[key] == 1 ? true: false;
+ chk.Enabled = true;
}
else if (ctls[0].GetType() == typeof(NumericUpDown))
{
NumericUpDown nud = ((NumericUpDown)ctls[0]);
nud.Value = (decimal)(float)copy[key];
+ nud.Enabled = true;
}
}
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.resx
index e41b68c9ab..a93eb9f828 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAP_Limits.resx
@@ -149,6 +149,9 @@
True
+
+ False
+
247, 9
@@ -204,6 +207,9 @@
True
+
+ False
+
NoControl
@@ -235,6 +241,9 @@
True
+
+ False
+
NoControl
@@ -265,6 +274,9 @@
True
+
+ False
+
NoControl
@@ -322,6 +334,9 @@
True
+
+ False
+
NoControl
@@ -353,7 +368,7 @@
6, 95
- 60, 23
+ 65, 23
10
@@ -365,7 +380,7 @@
myLabel4
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4579.36338, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4597.13822, Culture=neutral, PublicKeyToken=null
groupBox4
@@ -410,7 +425,7 @@
myLabel3
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4579.36338, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4597.13822, Culture=neutral, PublicKeyToken=null
groupBox4
@@ -442,6 +457,9 @@
True
+
+ False
+
NoControl
@@ -496,6 +514,9 @@
True
+
+ False
+
NoControl
@@ -550,6 +571,9 @@
True
+
+ False
+
69, 19
@@ -590,7 +614,7 @@
myLabel1
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4579.36338, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4597.13822, Culture=neutral, PublicKeyToken=null
groupBox2
@@ -635,7 +659,7 @@
myLabel2
- ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4579.36338, Culture=neutral, PublicKeyToken=null
+ ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4597.13822, Culture=neutral, PublicKeyToken=null
groupBox2
@@ -725,6 +749,6 @@
ConfigAP_Limits
- ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner10, Version=1.1.4579.36338, Culture=neutral, PublicKeyToken=null
+ System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs
index c5d6a4e534..08a2285590 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigMount.cs
@@ -105,13 +105,32 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
updateYaw();
}
+ void ensureDisabled(ComboBox cmb, int number)
+ {
+ foreach (string item in cmb.Items)
+ {
+ if (MainV2.comPort.param.ContainsKey(item+"_FUNCTION")) {
+ float ans = (float)MainV2.comPort.param[item+"_FUNCTION"];
+
+ if (ans == number)
+ {
+ MainV2.comPort.setParam(item + "_FUNCTION",0);
+ }
+ }
+ }
+ }
+
void updatePitch()
{
// pitch
if (mavlinkComboBoxTilt.Text != "Disable")
{
- MainV2.comPort.setParam(mavlinkComboBoxTilt.Text + "_FUNCTION",7);
- MainV2.comPort.setParam("MNT_STAB_PITCH",1);
+ MainV2.comPort.setParam(mavlinkComboBoxTilt.Text + "_FUNCTION", 7);
+ MainV2.comPort.setParam("MNT_STAB_PITCH", 1);
+ }
+ else
+ {
+ ensureDisabled(mavlinkComboBoxTilt,7);
}
mavlinkNumericUpDownTSM.setup(800, 2200, 1, 1, mavlinkComboBoxTilt.Text +"_MIN", MainV2.comPort.param);
@@ -129,6 +148,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
MainV2.comPort.setParam(mavlinkComboBoxRoll.Text + "_FUNCTION", 8);
MainV2.comPort.setParam("MNT_STAB_ROLL", 1);
}
+ else
+ {
+ ensureDisabled(mavlinkComboBoxRoll,8);
+ }
mavlinkNumericUpDownRSM.setup(800, 2200, 1, 1, mavlinkComboBoxRoll.Text +"_MIN", MainV2.comPort.param);
mavlinkNumericUpDownRSMX.setup(800, 2200, 1, 1, mavlinkComboBoxRoll.Text + "_MAX", MainV2.comPort.param);
@@ -145,6 +168,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
MainV2.comPort.setParam(mavlinkComboBoxPan.Text + "_FUNCTION", 6);
MainV2.comPort.setParam("MNT_STAB_YAW", 1);
}
+ else
+ {
+ ensureDisabled(mavlinkComboBoxPan,6);
+ }
mavlinkNumericUpDownPSM.setup(800, 2200, 1, 1, mavlinkComboBoxPan.Text + "_MIN", MainV2.comPort.param);
mavlinkNumericUpDownPSMX.setup(800, 2200, 1, 1, mavlinkComboBoxPan.Text + "_MAX", MainV2.comPort.param);
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
index e76e14a6b1..b5c57f9975 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
@@ -13,9 +13,13 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
public partial class Setup : MyUserControl
{
+ // remeber the last page accessed
+ static string lastpagename = "";
+
public Setup()
{
InitializeComponent();
+ ThemeManager.ApplyThemeTo(this);
}
@@ -34,7 +38,17 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
//backstageView.AddSpacer(15);
AddBackstageViewPage(new ConfigPlanner(), "Planner");
- this.backstageView.ActivatePage(backstageView.Pages[0]);
+ // remeber last page accessed
+ foreach (BackstageView.BackstageViewPage page in backstageView.Pages) {
+ if (page.LinkText == lastpagename)
+ {
+ this.backstageView.ActivatePage(page);
+ break;
+ }
+ }
+
+
+ //this.backstageView.ActivatePage(backstageView.Pages[0]);
ThemeManager.ApplyThemeTo(this);
@@ -115,6 +129,8 @@ If you are just setting up 3DR radios, you may continue without connecting.");
private void Setup_FormClosing(object sender, FormClosingEventArgs e)
{
+ lastpagename = backstageView.SelectedPage.LinkText;
+
backstageView.Close();
}
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
index 435f764970..034e311dd9 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
@@ -221,18 +221,22 @@ namespace ArdupilotMega.GCSViews
if (CB_tuning.Checked)
ZedGraphTimer.Start();
- hud1.Visible = true;
- hud1.Enabled = true;
- // SubMainLeft.Panel1.Controls.Clear();
- // SubMainLeft.Panel1.Controls.Add(hud1);
+ if (!hud1.Visible)
+ hud1.Visible = true;
+ if (!hud1.Enabled)
+ hud1.Enabled = true;
+
+ hud1.Dock = DockStyle.Fill;
}
public void Deactivate()
{
- //SubMainLeft.Panel1.Controls.Remove(hud1);
- hud1.Visible = false;
+ hud1.Dock = DockStyle.None;
+ hud1.Size = new System.Drawing.Size(5,5);
hud1.Enabled = false;
+ hud1.Visible = false;
+ // hud1.Location = new Point(-1000,-1000);
ZedGraphTimer.Stop();
}
@@ -517,12 +521,7 @@ namespace ArdupilotMega.GCSViews
if (waypoints.AddSeconds(10) < DateTime.Now)
{
//Console.WriteLine("Doing FD WP's");
- while (gMapControl1.inOnPaint == true)
- {
- System.Threading.Thread.Sleep(1);
- }
- polygons.Markers.Clear();
- routes.Markers.Clear();
+ updateMissionRoute();
if (MainV2.comPort.logreadmode && MainV2.comPort.logplaybackfile != null)
{
@@ -627,6 +626,17 @@ namespace ArdupilotMega.GCSViews
});
}
+ // to prevent cross thread calls while in a draw and exception
+ private void updateMissionRoute()
+ {
+ // not async
+ this.Invoke((System.Windows.Forms.MethodInvoker)delegate()
+ {
+ polygons.Markers.Clear();
+ routes.Markers.Clear();
+ });
+ }
+
private void updatePlayPauseButton(bool playing)
{
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
index 2944df0521..42389a0a30 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
@@ -28,7 +28,7 @@ using ArdupilotMega.Controls.BackstageView;
namespace ArdupilotMega.GCSViews
{
- partial class FlightPlanner : MyUserControl, IDeactivate
+ partial class FlightPlanner : MyUserControl, IDeactivate, IActivate
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
int selectedrow = 0;
@@ -3488,6 +3488,11 @@ namespace ArdupilotMega.GCSViews
//drawnpolygon.Points.Add(new PointLatLng(start.Lat, start.Lng));
}
+ public void Activate()
+ {
+ timer1.Start();
+ }
+
public void Deactivate()
{
timer1.Stop();
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
index 0744c65267..7048d226a5 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
@@ -636,7 +636,7 @@ namespace ArdupilotMega.GCSViews
if (hzcounttime.Second != DateTime.Now.Second)
{
- //Console.WriteLine("SIM hz {0}", hzcount);
+ Console.WriteLine("SIM hz {0}", hzcount);
hzcount = 0;
hzcounttime = DateTime.Now;
}
diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs
index 73468de937..7fefa08e44 100644
--- a/Tools/ArdupilotMegaPlanner/MainV2.cs
+++ b/Tools/ArdupilotMegaPlanner/MainV2.cs
@@ -24,6 +24,7 @@ using System.Security.Cryptography;
using ArdupilotMega.Comms;
using ArdupilotMega.Arduino;
using System.IO.Ports;
+using Transitions;
namespace ArdupilotMega
{
@@ -1194,6 +1195,7 @@ namespace ArdupilotMega
MyView.AddScreen(new MainSwitcher.Screen("Help", new GCSViews.Help(), false));
// init button depressed - ensures correct action
+ //int fixme;
MenuFlightData_Click(sender, e);
// for long running tasks using own threads.
diff --git a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs
index 1605e39633..c5950b4de8 100644
--- a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs
+++ b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs
@@ -231,6 +231,8 @@ namespace ArdupilotMega
{
frmProgressReporter.UpdateProgressAndStatus(-1, "Mavlink Connecting...");
+ MainV2.giveComport = true;
+
// allow settings to settle - previous dtr
System.Threading.Thread.Sleep(500);
@@ -242,8 +244,6 @@ namespace ArdupilotMega
try
{
- MainV2.giveComport = true;
-
BaseStream.ReadBufferSize = 4 * 1024;
lock (objlock) // so we dont have random traffic
diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
index 94011d4dd9..54f729d0af 100644
--- a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
+++ b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
@@ -2,14 +2,14 @@
-
+
-
-
+
+
@@ -31,222 +31,228 @@
-
+
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
+
+
+
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
-
-
-
-
-
+
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
-
-
-
-
-
-
-
+
+
+
+
+
+
+
-
-
-
+
+
+
-
-
-
+
+
+
-
-
-
+
+
+
-
-
-
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
-
-
-
+
+
+
+
+
+
+
-
-
-
+
+
+
-
-
-
-
+
+
+
+
-
-
-
+
+
+
-
-
-
+
+
+
-
-
-
+
+
+
@@ -290,26 +296,26 @@
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
-
-
-
+
+
+
-
-
-
-
+
+
+
+
+
@@ -330,7 +336,7 @@
-
+