mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
APM Planner 1.1.41
add NaN checking/error message add config page shortcuts - F5, ctl-s and ctl-o add +++ passthrough on terminal add longer delay to log download modify param receive process. modify connecting and param receive process - re Andrew
This commit is contained in:
parent
48cad8bc25
commit
58bca7d4a4
@ -257,6 +257,7 @@ namespace ArdupilotMega
|
||||
|
||||
return sync();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Upload data at preset address
|
||||
/// </summary>
|
||||
|
@ -225,6 +225,18 @@
|
||||
</Reference>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<Compile Include="Controls\ProgressReporterDialogue.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\ProgressReporterDialogue.designer.cs">
|
||||
<DependentUpon>ProgressReporterDialogue.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Radio\3DRradio.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Radio\3DRradio.Designer.cs">
|
||||
<DependentUpon>3DRradio.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Controls\AGauge.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
@ -252,18 +264,13 @@
|
||||
<Compile Include="Controls\myGMAP.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\ProgressReporter.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\ProgressReporter.designer.cs">
|
||||
<DependentUpon>ProgressReporter.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Controls\XorPlus.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\XorPlus.Designer.cs">
|
||||
<DependentUpon>XorPlus.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Radio\IHex.cs" />
|
||||
<Compile Include="Mavlink\MavlinkCRC.cs" />
|
||||
<Compile Include="Mavlink\MavlinkUtil.cs" />
|
||||
<Compile Include="SerialInput.cs">
|
||||
@ -437,6 +444,13 @@
|
||||
<Compile Include="temp.Designer.cs">
|
||||
<DependentUpon>temp.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Radio\Uploader.cs" />
|
||||
<EmbeddedResource Include="Controls\ProgressReporterDialogue.resx">
|
||||
<DependentUpon>ProgressReporterDialogue.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Radio\3DRradio.resx">
|
||||
<DependentUpon>3DRradio.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Controls\AGauge.resx">
|
||||
<DependentUpon>AGauge.cs</DependentUpon>
|
||||
<SubType>Designer</SubType>
|
||||
@ -447,9 +461,6 @@
|
||||
<EmbeddedResource Include="Controls\ImageLabel.resx">
|
||||
<DependentUpon>ImageLabel.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Controls\ProgressReporter.resx">
|
||||
<DependentUpon>ProgressReporter.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Controls\XorPlus.resx">
|
||||
<DependentUpon>XorPlus.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -830,6 +841,7 @@
|
||||
<Content Include="mavcmd.xml">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</Content>
|
||||
<None Include="Resources\y6.png" />
|
||||
<None Include="Resources\new frames-13.png" />
|
||||
<None Include="Resources\new frames-12.png" />
|
||||
<None Include="Resources\new frames-11.png" />
|
||||
|
@ -118,13 +118,19 @@ namespace ArdupilotMega
|
||||
g.TranslateTransform(LocalPosition.X, LocalPosition.Y);
|
||||
|
||||
int length = 500;
|
||||
|
||||
g.DrawLine(new Pen(Color.Red, 2), 0.0f, 0.0f, (float)Math.Cos((heading - 90) * deg2rad) * length, (float)Math.Sin((heading - 90) * deg2rad) * length);
|
||||
// anti NaN
|
||||
try
|
||||
{
|
||||
g.DrawLine(new Pen(Color.Red, 2), 0.0f, 0.0f, (float)Math.Cos((heading - 90) * deg2rad) * length, (float)Math.Sin((heading - 90) * deg2rad) * length);
|
||||
}
|
||||
catch { }
|
||||
g.DrawLine(new Pen(Color.Green, 2), 0.0f, 0.0f, (float)Math.Cos((nav_bearing - 90) * deg2rad) * length, (float)Math.Sin((nav_bearing - 90) * deg2rad) * length);
|
||||
g.DrawLine(new Pen(Color.Black, 2), 0.0f, 0.0f, (float)Math.Cos((cog - 90) * deg2rad) * length, (float)Math.Sin((cog - 90) * deg2rad) * length);
|
||||
g.DrawLine(new Pen(Color.Orange, 2), 0.0f, 0.0f, (float)Math.Cos((target - 90) * deg2rad) * length, (float)Math.Sin((target - 90) * deg2rad) * length);
|
||||
|
||||
// anti NaN
|
||||
try {
|
||||
g.RotateTransform(heading);
|
||||
} catch{}
|
||||
g.DrawImageUnscaled(global::ArdupilotMega.Properties.Resources.planeicon, global::ArdupilotMega.Properties.Resources.planeicon.Width / -2, global::ArdupilotMega.Properties.Resources.planeicon.Height / -2);
|
||||
|
||||
g.Transform = temp;
|
||||
@ -157,14 +163,21 @@ namespace ArdupilotMega
|
||||
g.TranslateTransform(LocalPosition.X, LocalPosition.Y);
|
||||
|
||||
int length = 500;
|
||||
|
||||
g.DrawLine(new Pen(Color.Red, 2), 0.0f, 0.0f, (float)Math.Cos((heading - 90) * deg2rad) * length, (float)Math.Sin((heading - 90) * deg2rad) * length);
|
||||
// anti NaN
|
||||
try
|
||||
{
|
||||
g.DrawLine(new Pen(Color.Red, 2), 0.0f, 0.0f, (float)Math.Cos((heading - 90) * deg2rad) * length, (float)Math.Sin((heading - 90) * deg2rad) * length);
|
||||
}
|
||||
catch { }
|
||||
//g.DrawLine(new Pen(Color.Green, 2), 0.0f, 0.0f, (float)Math.Cos((nav_bearing - 90) * deg2rad) * length, (float)Math.Sin((nav_bearing - 90) * deg2rad) * length);
|
||||
g.DrawLine(new Pen(Color.Black, 2), 0.0f, 0.0f, (float)Math.Cos((cog - 90) * deg2rad) * length, (float)Math.Sin((cog - 90) * deg2rad) * length);
|
||||
g.DrawLine(new Pen(Color.Orange, 2), 0.0f, 0.0f, (float)Math.Cos((target - 90) * deg2rad) * length, (float)Math.Sin((target - 90) * deg2rad) * length);
|
||||
|
||||
|
||||
g.RotateTransform(heading);
|
||||
// anti NaN
|
||||
try
|
||||
{
|
||||
g.RotateTransform(heading);
|
||||
}
|
||||
catch { }
|
||||
g.DrawImageUnscaled(global::ArdupilotMega.Properties.Resources.quadicon, global::ArdupilotMega.Properties.Resources.quadicon.Width / -2 + 2, global::ArdupilotMega.Properties.Resources.quadicon.Height / -2);
|
||||
|
||||
g.Transform = temp;
|
||||
@ -490,7 +503,7 @@ namespace ArdupilotMega
|
||||
WebResponse response = request.GetResponse();
|
||||
// Display the status.
|
||||
Console.WriteLine(((HttpWebResponse)response).StatusDescription);
|
||||
if (((HttpWebResponse)response).StatusDescription != "200")
|
||||
if (((HttpWebResponse)response).StatusCode != HttpStatusCode.OK)
|
||||
return false;
|
||||
// Get the stream containing content returned by the server.
|
||||
Stream dataStream = response.GetResponseStream();
|
||||
@ -500,7 +513,7 @@ namespace ArdupilotMega
|
||||
|
||||
byte[] buf1 = new byte[1024];
|
||||
|
||||
FileStream fs = new FileStream(saveto+".new", FileMode.Create);
|
||||
FileStream fs = new FileStream(saveto + ".new", FileMode.Create);
|
||||
|
||||
DateTime dt = DateTime.Now;
|
||||
|
||||
|
214
Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs
Normal file
214
Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs
Normal file
@ -0,0 +1,214 @@
|
||||
using System;
|
||||
using System.ComponentModel;
|
||||
using System.Threading;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArdupilotMega.Controls
|
||||
{
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// Form that is shown to the user during a background operation
|
||||
/// </summary>
|
||||
/// <remarks>
|
||||
/// Performs operation excplicitely on a threadpool thread due to
|
||||
/// Mono not playing nice with the BackgroundWorker
|
||||
/// </remarks>
|
||||
public partial class ProgressReporterDialogue : Form
|
||||
{
|
||||
private Exception workerException;
|
||||
public ProgressWorkerEventArgs doWorkArgs;
|
||||
|
||||
public delegate void DoWorkEventHandler(object sender, ProgressWorkerEventArgs e);
|
||||
|
||||
// This is the event that will be raised on the BG thread
|
||||
public event DoWorkEventHandler DoWork;
|
||||
|
||||
public ProgressReporterDialogue()
|
||||
{
|
||||
InitializeComponent();
|
||||
doWorkArgs = new ProgressWorkerEventArgs();
|
||||
this.btnClose.Visible = false;
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Called at setup - will kick off the background process on a thread pool thread
|
||||
/// </summary>
|
||||
public void RunBackgroundOperationAsync()
|
||||
{
|
||||
ThreadPool.QueueUserWorkItem(RunBackgroundOperation);
|
||||
this.ShowDialog();
|
||||
}
|
||||
|
||||
private void RunBackgroundOperation(object o)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (this.DoWork != null) this.DoWork(this, doWorkArgs);
|
||||
}
|
||||
catch(Exception e)
|
||||
{
|
||||
// The background operation thew an exception.
|
||||
// Examine the work args, if there is an error, then display that and the exception details
|
||||
// Otherwise display 'Unexpected error' and exception details
|
||||
ShowDoneWithError(e, doWorkArgs.ErrorMessage);
|
||||
return;
|
||||
}
|
||||
|
||||
if (doWorkArgs.CancelRequested && doWorkArgs.CancelAcknowledged)
|
||||
{
|
||||
ShowDoneCancelled();
|
||||
return;
|
||||
}
|
||||
|
||||
if (!string.IsNullOrEmpty(doWorkArgs.ErrorMessage))
|
||||
{
|
||||
ShowDoneWithError(null, doWorkArgs.ErrorMessage);
|
||||
return;
|
||||
}
|
||||
|
||||
if (doWorkArgs.CancelRequested)
|
||||
{
|
||||
ShowDoneWithError(null, "Operation could not cancel");
|
||||
return;
|
||||
}
|
||||
|
||||
ShowDone();
|
||||
}
|
||||
|
||||
// Called as a possible last operation of the bg thread that was cancelled
|
||||
// - Hide progress bar
|
||||
// - Set label text
|
||||
private void ShowDoneCancelled()
|
||||
{
|
||||
this.Invoke((MethodInvoker)delegate
|
||||
{
|
||||
this.progressBar1.Visible = false;
|
||||
this.lblProgressMessage.Text = "Cancelled";
|
||||
this.btnClose.Visible = true;
|
||||
});
|
||||
}
|
||||
|
||||
// Called as a possible last operation of the bg thread
|
||||
// - Set progress bar to 100%
|
||||
// - Wait a little bit to allow the Aero progress animatiom to catch up
|
||||
// - Signal that we can close
|
||||
private void ShowDone()
|
||||
{
|
||||
this.Invoke((MethodInvoker) delegate
|
||||
{
|
||||
this.progressBar1.Style = ProgressBarStyle.Continuous;
|
||||
this.progressBar1.Value = 100;
|
||||
this.btnCancel.Visible = false;
|
||||
this.btnClose.Visible = false;
|
||||
});
|
||||
|
||||
Thread.Sleep(1000);
|
||||
|
||||
this.BeginInvoke((MethodInvoker) this.Close);
|
||||
}
|
||||
|
||||
// Called as a possible last operation of the bg thread
|
||||
// There was an exception on the worker event, so:
|
||||
// - Show the error message supplied by the worker, or a default message
|
||||
// - Make visible the error icon
|
||||
// - Make the progress bar invisible to make room for:
|
||||
// - Add the exception details and stack trace in an expansion panel
|
||||
// - Change the Cancel button to 'Close', so that the user can look at the exception message a bit
|
||||
private void ShowDoneWithError(Exception exception, string doWorkArgs)
|
||||
{
|
||||
var errMessage = doWorkArgs ?? "There was an unexpected error";
|
||||
|
||||
if (this.InvokeRequired)
|
||||
{
|
||||
this.Invoke((MethodInvoker) delegate
|
||||
{
|
||||
this.Text = "Error";
|
||||
this.lblProgressMessage.Left = 65;
|
||||
this.lblProgressMessage.Text = errMessage;
|
||||
this.imgWarning.Visible = true;
|
||||
this.progressBar1.Visible = false;
|
||||
this.btnCancel.Visible = false;
|
||||
this.btnClose.Visible = true;
|
||||
this.linkLabel1.Visible = exception != null;
|
||||
this.workerException = exception;
|
||||
});
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
private void btnCancel_Click(object sender, EventArgs e)
|
||||
{
|
||||
// User wants to cancel -
|
||||
// * Set the text of the Cancel button to 'Close'
|
||||
// * Set the cancel button to disabled, will enable it and let the user dismiss the dialogue
|
||||
// when the async operation is complete
|
||||
// * Set the status text to 'Cancelling...'
|
||||
// * Set the progress bar to marquee, we don't know how long the worker will take to cancel
|
||||
// * Signal the worker.
|
||||
this.btnCancel.Visible = false;
|
||||
this.lblProgressMessage.Text = "Cancelling...";
|
||||
this.progressBar1.Style = ProgressBarStyle.Marquee;
|
||||
|
||||
doWorkArgs.CancelRequested = true;
|
||||
}
|
||||
|
||||
|
||||
private void btn_Close_Click(object sender, EventArgs e)
|
||||
{
|
||||
// we have already cancelled, and this now a 'close' button
|
||||
this.Close();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Called from the BG thread
|
||||
/// </summary>
|
||||
/// <param name="progress">progress in %, -1 means inderteminate</param>
|
||||
/// <param name="status"></param>
|
||||
public void UpdateProgressAndStatus(int progress, string status)
|
||||
{
|
||||
// we don't let the worker update progress when a cancel has been
|
||||
// requested, unless the cancel has been acknowleged, so we know that
|
||||
// this progress update pertains to the cancellation cleanup
|
||||
if (doWorkArgs.CancelRequested && !doWorkArgs.CancelAcknowledged)
|
||||
return;
|
||||
|
||||
if (this.InvokeRequired)
|
||||
{
|
||||
|
||||
this.Invoke((MethodInvoker) delegate
|
||||
{
|
||||
|
||||
lblProgressMessage.Text = status;
|
||||
if (progress == -1)
|
||||
{
|
||||
this.progressBar1.Style = ProgressBarStyle.Marquee;
|
||||
}
|
||||
else
|
||||
{
|
||||
this.progressBar1.Style = ProgressBarStyle.Continuous;
|
||||
this.progressBar1.Value = progress;
|
||||
}
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
private void linkLabel1_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e)
|
||||
{
|
||||
var message = this.workerException.Message
|
||||
+ Environment.NewLine + Environment.NewLine
|
||||
+ this.workerException.StackTrace;
|
||||
|
||||
MessageBox.Show(message,"Exception Details",MessageBoxButtons.OK,MessageBoxIcon.Information);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
public class ProgressWorkerEventArgs : EventArgs
|
||||
{
|
||||
public string ErrorMessage;
|
||||
public volatile bool CancelRequested;
|
||||
public volatile bool CancelAcknowledged;
|
||||
}
|
||||
}
|
141
Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.designer.cs
generated
Normal file
141
Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.designer.cs
generated
Normal file
@ -0,0 +1,141 @@
|
||||
using System;
|
||||
using System.ComponentModel;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArdupilotMega.Controls
|
||||
{
|
||||
partial class ProgressReporterDialogue
|
||||
{
|
||||
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Windows Form Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.progressBar1 = new System.Windows.Forms.ProgressBar();
|
||||
this.lblProgressMessage = new System.Windows.Forms.Label();
|
||||
this.btnCancel = new System.Windows.Forms.Button();
|
||||
this.imgWarning = new System.Windows.Forms.PictureBox();
|
||||
this.linkLabel1 = new System.Windows.Forms.LinkLabel();
|
||||
this.btnClose = new System.Windows.Forms.Button();
|
||||
((System.ComponentModel.ISupportInitialize)(this.imgWarning)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// progressBar1
|
||||
//
|
||||
this.progressBar1.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left)
|
||||
| System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.progressBar1.Location = new System.Drawing.Point(11, 90);
|
||||
this.progressBar1.Name = "progressBar1";
|
||||
this.progressBar1.Size = new System.Drawing.Size(277, 13);
|
||||
this.progressBar1.TabIndex = 0;
|
||||
//
|
||||
// lblProgressMessage
|
||||
//
|
||||
this.lblProgressMessage.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom)
|
||||
| System.Windows.Forms.AnchorStyles.Left)
|
||||
| System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.lblProgressMessage.Location = new System.Drawing.Point(13, 13);
|
||||
this.lblProgressMessage.Name = "lblProgressMessage";
|
||||
this.lblProgressMessage.Size = new System.Drawing.Size(275, 74);
|
||||
this.lblProgressMessage.TabIndex = 1;
|
||||
this.lblProgressMessage.TextAlign = System.Drawing.ContentAlignment.MiddleLeft;
|
||||
//
|
||||
// btnCancel
|
||||
//
|
||||
this.btnCancel.Location = new System.Drawing.Point(213, 109);
|
||||
this.btnCancel.Name = "btnCancel";
|
||||
this.btnCancel.Size = new System.Drawing.Size(75, 23);
|
||||
this.btnCancel.TabIndex = 2;
|
||||
this.btnCancel.Text = "Cancel";
|
||||
this.btnCancel.UseVisualStyleBackColor = true;
|
||||
this.btnCancel.Click += new System.EventHandler(this.btnCancel_Click);
|
||||
//
|
||||
// imgWarning
|
||||
//
|
||||
this.imgWarning.Image = global::ArdupilotMega.Properties.Resources.iconWarning48;
|
||||
this.imgWarning.Location = new System.Drawing.Point(13, 22);
|
||||
this.imgWarning.Name = "imgWarning";
|
||||
this.imgWarning.Size = new System.Drawing.Size(48, 48);
|
||||
this.imgWarning.TabIndex = 3;
|
||||
this.imgWarning.TabStop = false;
|
||||
this.imgWarning.Visible = false;
|
||||
//
|
||||
// linkLabel1
|
||||
//
|
||||
this.linkLabel1.AutoSize = true;
|
||||
this.linkLabel1.Location = new System.Drawing.Point(240, 90);
|
||||
this.linkLabel1.Name = "linkLabel1";
|
||||
this.linkLabel1.Size = new System.Drawing.Size(48, 13);
|
||||
this.linkLabel1.TabIndex = 4;
|
||||
this.linkLabel1.TabStop = true;
|
||||
this.linkLabel1.Text = "Details...";
|
||||
this.linkLabel1.Visible = false;
|
||||
this.linkLabel1.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.linkLabel1_LinkClicked);
|
||||
//
|
||||
// btn_Close
|
||||
//
|
||||
this.btnClose.Location = new System.Drawing.Point(213, 109);
|
||||
this.btnClose.Name = "btnClose";
|
||||
this.btnClose.Size = new System.Drawing.Size(75, 23);
|
||||
this.btnClose.TabIndex = 5;
|
||||
this.btnClose.Text = "Close";
|
||||
this.btnClose.UseVisualStyleBackColor = true;
|
||||
this.btnClose.Click += new System.EventHandler(this.btn_Close_Click);
|
||||
//
|
||||
// ProgressReporterDialogue
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.ClientSize = new System.Drawing.Size(306, 144);
|
||||
this.ControlBox = false;
|
||||
this.Controls.Add(this.btnClose);
|
||||
this.Controls.Add(this.linkLabel1);
|
||||
this.Controls.Add(this.imgWarning);
|
||||
this.Controls.Add(this.btnCancel);
|
||||
this.Controls.Add(this.lblProgressMessage);
|
||||
this.Controls.Add(this.progressBar1);
|
||||
this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.FixedToolWindow;
|
||||
this.MaximizeBox = false;
|
||||
this.MinimizeBox = false;
|
||||
this.Name = "ProgressReporterDialogue";
|
||||
this.SizeGripStyle = System.Windows.Forms.SizeGripStyle.Hide;
|
||||
this.StartPosition = System.Windows.Forms.FormStartPosition.CenterParent;
|
||||
this.Text = "Progress";
|
||||
((System.ComponentModel.ISupportInitialize)(this.imgWarning)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private ProgressBar progressBar1;
|
||||
private System.Windows.Forms.Label lblProgressMessage;
|
||||
private Button btnCancel;
|
||||
private PictureBox imgWarning;
|
||||
private LinkLabel linkLabel1;
|
||||
private Button btnClose;
|
||||
}
|
||||
}
|
@ -0,0 +1,120 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
</root>
|
File diff suppressed because it is too large
Load Diff
@ -1154,5 +1154,25 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
|
||||
{
|
||||
if (keyData == Keys.F5)
|
||||
{
|
||||
BUT_rerequestparams_Click(BUT_rerequestparams, null);
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.S))
|
||||
{
|
||||
BUT_writePIDS_Click(BUT_writePIDS, null);
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.O))
|
||||
{
|
||||
BUT_load_Click(BUT_load, null);
|
||||
return true;
|
||||
}
|
||||
return base.ProcessCmdKey(ref msg, keyData);
|
||||
}
|
||||
}
|
||||
}
|
File diff suppressed because it is too large
Load Diff
@ -127,7 +127,6 @@
|
||||
//
|
||||
resources.ApplyResources(this.CHKREV_roll, "CHKREV_roll");
|
||||
this.CHKREV_roll.Name = "CHKREV_roll";
|
||||
this.toolTip1.SetToolTip(this.CHKREV_roll, resources.GetString("CHKREV_roll.ToolTip"));
|
||||
this.CHKREV_roll.UseVisualStyleBackColor = true;
|
||||
this.CHKREV_roll.CheckedChanged += new System.EventHandler(this.CHKREV_roll_CheckedChanged);
|
||||
//
|
||||
@ -135,7 +134,6 @@
|
||||
//
|
||||
resources.ApplyResources(this.CHKREV_pitch, "CHKREV_pitch");
|
||||
this.CHKREV_pitch.Name = "CHKREV_pitch";
|
||||
this.toolTip1.SetToolTip(this.CHKREV_pitch, resources.GetString("CHKREV_pitch.ToolTip"));
|
||||
this.CHKREV_pitch.UseVisualStyleBackColor = true;
|
||||
this.CHKREV_pitch.CheckedChanged += new System.EventHandler(this.CHKREV_pitch_CheckedChanged);
|
||||
//
|
||||
@ -143,13 +141,11 @@
|
||||
//
|
||||
resources.ApplyResources(this.CHKREV_rudder, "CHKREV_rudder");
|
||||
this.CHKREV_rudder.Name = "CHKREV_rudder";
|
||||
this.toolTip1.SetToolTip(this.CHKREV_rudder, resources.GetString("CHKREV_rudder.ToolTip"));
|
||||
this.CHKREV_rudder.UseVisualStyleBackColor = true;
|
||||
this.CHKREV_rudder.CheckedChanged += new System.EventHandler(this.CHKREV_rudder_CheckedChanged);
|
||||
//
|
||||
// GPSrate
|
||||
//
|
||||
resources.ApplyResources(this.GPSrate, "GPSrate");
|
||||
this.GPSrate.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
|
||||
this.GPSrate.FormattingEnabled = true;
|
||||
this.GPSrate.Items.AddRange(new object[] {
|
||||
@ -161,8 +157,8 @@
|
||||
resources.GetString("GPSrate.Items5"),
|
||||
resources.GetString("GPSrate.Items6"),
|
||||
resources.GetString("GPSrate.Items7")});
|
||||
resources.ApplyResources(this.GPSrate, "GPSrate");
|
||||
this.GPSrate.Name = "GPSrate";
|
||||
this.toolTip1.SetToolTip(this.GPSrate, resources.GetString("GPSrate.ToolTip"));
|
||||
this.GPSrate.SelectedIndexChanged += new System.EventHandler(this.GPSrate_SelectedIndexChanged);
|
||||
this.GPSrate.KeyDown += new System.Windows.Forms.KeyEventHandler(this.GPSrate_KeyDown);
|
||||
this.GPSrate.Leave += new System.EventHandler(this.GPSrate_Leave);
|
||||
@ -171,7 +167,6 @@
|
||||
//
|
||||
resources.ApplyResources(this.ConnectComPort, "ConnectComPort");
|
||||
this.ConnectComPort.Name = "ConnectComPort";
|
||||
this.toolTip1.SetToolTip(this.ConnectComPort, resources.GetString("ConnectComPort.ToolTip"));
|
||||
this.ConnectComPort.UseVisualStyleBackColor = true;
|
||||
this.ConnectComPort.Click += new System.EventHandler(this.ConnectComPort_Click);
|
||||
//
|
||||
@ -179,7 +174,6 @@
|
||||
//
|
||||
resources.ApplyResources(this.OutputLog, "OutputLog");
|
||||
this.OutputLog.Name = "OutputLog";
|
||||
this.toolTip1.SetToolTip(this.OutputLog, resources.GetString("OutputLog.ToolTip"));
|
||||
this.OutputLog.TextChanged += new System.EventHandler(this.OutputLog_TextChanged);
|
||||
//
|
||||
// TXT_roll
|
||||
@ -187,28 +181,24 @@
|
||||
resources.ApplyResources(this.TXT_roll, "TXT_roll");
|
||||
this.TXT_roll.Name = "TXT_roll";
|
||||
this.TXT_roll.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_roll, resources.GetString("TXT_roll.ToolTip"));
|
||||
//
|
||||
// TXT_pitch
|
||||
//
|
||||
resources.ApplyResources(this.TXT_pitch, "TXT_pitch");
|
||||
this.TXT_pitch.Name = "TXT_pitch";
|
||||
this.TXT_pitch.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_pitch, resources.GetString("TXT_pitch.ToolTip"));
|
||||
//
|
||||
// TXT_heading
|
||||
//
|
||||
resources.ApplyResources(this.TXT_heading, "TXT_heading");
|
||||
this.TXT_heading.Name = "TXT_heading";
|
||||
this.TXT_heading.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_heading, resources.GetString("TXT_heading.ToolTip"));
|
||||
//
|
||||
// TXT_wpdist
|
||||
//
|
||||
resources.ApplyResources(this.TXT_wpdist, "TXT_wpdist");
|
||||
this.TXT_wpdist.Name = "TXT_wpdist";
|
||||
this.TXT_wpdist.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_wpdist, resources.GetString("TXT_wpdist.ToolTip"));
|
||||
//
|
||||
// currentStateBindingSource
|
||||
//
|
||||
@ -219,41 +209,35 @@
|
||||
resources.ApplyResources(this.TXT_bererror, "TXT_bererror");
|
||||
this.TXT_bererror.Name = "TXT_bererror";
|
||||
this.TXT_bererror.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_bererror, resources.GetString("TXT_bererror.ToolTip"));
|
||||
//
|
||||
// TXT_alterror
|
||||
//
|
||||
resources.ApplyResources(this.TXT_alterror, "TXT_alterror");
|
||||
this.TXT_alterror.Name = "TXT_alterror";
|
||||
this.TXT_alterror.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_alterror, resources.GetString("TXT_alterror.ToolTip"));
|
||||
//
|
||||
// TXT_lat
|
||||
//
|
||||
resources.ApplyResources(this.TXT_lat, "TXT_lat");
|
||||
this.TXT_lat.Name = "TXT_lat";
|
||||
this.TXT_lat.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_lat, resources.GetString("TXT_lat.ToolTip"));
|
||||
//
|
||||
// TXT_long
|
||||
//
|
||||
resources.ApplyResources(this.TXT_long, "TXT_long");
|
||||
this.TXT_long.Name = "TXT_long";
|
||||
this.TXT_long.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_long, resources.GetString("TXT_long.ToolTip"));
|
||||
//
|
||||
// TXT_alt
|
||||
//
|
||||
resources.ApplyResources(this.TXT_alt, "TXT_alt");
|
||||
this.TXT_alt.Name = "TXT_alt";
|
||||
this.TXT_alt.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_alt, resources.GetString("TXT_alt.ToolTip"));
|
||||
//
|
||||
// SaveSettings
|
||||
//
|
||||
resources.ApplyResources(this.SaveSettings, "SaveSettings");
|
||||
this.SaveSettings.Name = "SaveSettings";
|
||||
this.toolTip1.SetToolTip(this.SaveSettings, resources.GetString("SaveSettings.ToolTip"));
|
||||
this.SaveSettings.UseVisualStyleBackColor = true;
|
||||
this.SaveSettings.Click += new System.EventHandler(this.SaveSettings_Click);
|
||||
//
|
||||
@ -280,32 +264,27 @@
|
||||
resources.ApplyResources(this.TXT_servoroll, "TXT_servoroll");
|
||||
this.TXT_servoroll.Name = "TXT_servoroll";
|
||||
this.TXT_servoroll.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_servoroll, resources.GetString("TXT_servoroll.ToolTip"));
|
||||
//
|
||||
// TXT_servopitch
|
||||
//
|
||||
resources.ApplyResources(this.TXT_servopitch, "TXT_servopitch");
|
||||
this.TXT_servopitch.Name = "TXT_servopitch";
|
||||
this.TXT_servopitch.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_servopitch, resources.GetString("TXT_servopitch.ToolTip"));
|
||||
//
|
||||
// TXT_servorudder
|
||||
//
|
||||
resources.ApplyResources(this.TXT_servorudder, "TXT_servorudder");
|
||||
this.TXT_servorudder.Name = "TXT_servorudder";
|
||||
this.TXT_servorudder.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_servorudder, resources.GetString("TXT_servorudder.ToolTip"));
|
||||
//
|
||||
// TXT_servothrottle
|
||||
//
|
||||
resources.ApplyResources(this.TXT_servothrottle, "TXT_servothrottle");
|
||||
this.TXT_servothrottle.Name = "TXT_servothrottle";
|
||||
this.TXT_servothrottle.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_servothrottle, resources.GetString("TXT_servothrottle.ToolTip"));
|
||||
//
|
||||
// panel1
|
||||
//
|
||||
resources.ApplyResources(this.panel1, "panel1");
|
||||
this.panel1.Controls.Add(this.label4);
|
||||
this.panel1.Controls.Add(this.label3);
|
||||
this.panel1.Controls.Add(this.label2);
|
||||
@ -313,40 +292,35 @@
|
||||
this.panel1.Controls.Add(this.TXT_lat);
|
||||
this.panel1.Controls.Add(this.TXT_long);
|
||||
this.panel1.Controls.Add(this.TXT_alt);
|
||||
resources.ApplyResources(this.panel1, "panel1");
|
||||
this.panel1.Name = "panel1";
|
||||
this.toolTip1.SetToolTip(this.panel1, resources.GetString("panel1.ToolTip"));
|
||||
//
|
||||
// label4
|
||||
//
|
||||
resources.ApplyResources(this.label4, "label4");
|
||||
this.label4.Name = "label4";
|
||||
this.label4.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label4, resources.GetString("label4.ToolTip"));
|
||||
//
|
||||
// label3
|
||||
//
|
||||
resources.ApplyResources(this.label3, "label3");
|
||||
this.label3.Name = "label3";
|
||||
this.label3.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label3, resources.GetString("label3.ToolTip"));
|
||||
//
|
||||
// label2
|
||||
//
|
||||
resources.ApplyResources(this.label2, "label2");
|
||||
this.label2.Name = "label2";
|
||||
this.label2.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label2, resources.GetString("label2.ToolTip"));
|
||||
//
|
||||
// label1
|
||||
//
|
||||
resources.ApplyResources(this.label1, "label1");
|
||||
this.label1.Name = "label1";
|
||||
this.label1.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label1, resources.GetString("label1.ToolTip"));
|
||||
//
|
||||
// panel2
|
||||
//
|
||||
resources.ApplyResources(this.panel2, "panel2");
|
||||
this.panel2.Controls.Add(this.label30);
|
||||
this.panel2.Controls.Add(this.TXT_yaw);
|
||||
this.panel2.Controls.Add(this.label11);
|
||||
@ -356,75 +330,65 @@
|
||||
this.panel2.Controls.Add(this.TXT_roll);
|
||||
this.panel2.Controls.Add(this.TXT_pitch);
|
||||
this.panel2.Controls.Add(this.TXT_heading);
|
||||
resources.ApplyResources(this.panel2, "panel2");
|
||||
this.panel2.Name = "panel2";
|
||||
this.toolTip1.SetToolTip(this.panel2, resources.GetString("panel2.ToolTip"));
|
||||
//
|
||||
// label30
|
||||
//
|
||||
resources.ApplyResources(this.label30, "label30");
|
||||
this.label30.Name = "label30";
|
||||
this.label30.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label30, resources.GetString("label30.ToolTip"));
|
||||
//
|
||||
// TXT_yaw
|
||||
//
|
||||
resources.ApplyResources(this.TXT_yaw, "TXT_yaw");
|
||||
this.TXT_yaw.Name = "TXT_yaw";
|
||||
this.TXT_yaw.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_yaw, resources.GetString("TXT_yaw.ToolTip"));
|
||||
//
|
||||
// label11
|
||||
//
|
||||
resources.ApplyResources(this.label11, "label11");
|
||||
this.label11.Name = "label11";
|
||||
this.label11.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label11, resources.GetString("label11.ToolTip"));
|
||||
//
|
||||
// label7
|
||||
//
|
||||
resources.ApplyResources(this.label7, "label7");
|
||||
this.label7.Name = "label7";
|
||||
this.label7.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label7, resources.GetString("label7.ToolTip"));
|
||||
//
|
||||
// label6
|
||||
//
|
||||
resources.ApplyResources(this.label6, "label6");
|
||||
this.label6.Name = "label6";
|
||||
this.label6.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label6, resources.GetString("label6.ToolTip"));
|
||||
//
|
||||
// label5
|
||||
//
|
||||
resources.ApplyResources(this.label5, "label5");
|
||||
this.label5.Name = "label5";
|
||||
this.label5.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label5, resources.GetString("label5.ToolTip"));
|
||||
//
|
||||
// label8
|
||||
//
|
||||
resources.ApplyResources(this.label8, "label8");
|
||||
this.label8.Name = "label8";
|
||||
this.label8.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label8, resources.GetString("label8.ToolTip"));
|
||||
//
|
||||
// label9
|
||||
//
|
||||
resources.ApplyResources(this.label9, "label9");
|
||||
this.label9.Name = "label9";
|
||||
this.label9.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label9, resources.GetString("label9.ToolTip"));
|
||||
//
|
||||
// label10
|
||||
//
|
||||
resources.ApplyResources(this.label10, "label10");
|
||||
this.label10.Name = "label10";
|
||||
this.label10.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label10, resources.GetString("label10.ToolTip"));
|
||||
//
|
||||
// panel3
|
||||
//
|
||||
resources.ApplyResources(this.panel3, "panel3");
|
||||
this.panel3.Controls.Add(this.label16);
|
||||
this.panel3.Controls.Add(this.label15);
|
||||
this.panel3.Controls.Add(this.label14);
|
||||
@ -434,47 +398,41 @@
|
||||
this.panel3.Controls.Add(this.TXT_servopitch);
|
||||
this.panel3.Controls.Add(this.TXT_servorudder);
|
||||
this.panel3.Controls.Add(this.TXT_servothrottle);
|
||||
resources.ApplyResources(this.panel3, "panel3");
|
||||
this.panel3.Name = "panel3";
|
||||
this.toolTip1.SetToolTip(this.panel3, resources.GetString("panel3.ToolTip"));
|
||||
//
|
||||
// label16
|
||||
//
|
||||
resources.ApplyResources(this.label16, "label16");
|
||||
this.label16.Name = "label16";
|
||||
this.label16.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label16, resources.GetString("label16.ToolTip"));
|
||||
//
|
||||
// label15
|
||||
//
|
||||
resources.ApplyResources(this.label15, "label15");
|
||||
this.label15.Name = "label15";
|
||||
this.label15.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label15, resources.GetString("label15.ToolTip"));
|
||||
//
|
||||
// label14
|
||||
//
|
||||
resources.ApplyResources(this.label14, "label14");
|
||||
this.label14.Name = "label14";
|
||||
this.label14.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label14, resources.GetString("label14.ToolTip"));
|
||||
//
|
||||
// label13
|
||||
//
|
||||
resources.ApplyResources(this.label13, "label13");
|
||||
this.label13.Name = "label13";
|
||||
this.label13.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label13, resources.GetString("label13.ToolTip"));
|
||||
//
|
||||
// label12
|
||||
//
|
||||
resources.ApplyResources(this.label12, "label12");
|
||||
this.label12.Name = "label12";
|
||||
this.label12.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label12, resources.GetString("label12.ToolTip"));
|
||||
//
|
||||
// panel4
|
||||
//
|
||||
resources.ApplyResources(this.panel4, "panel4");
|
||||
this.panel4.Controls.Add(this.label20);
|
||||
this.panel4.Controls.Add(this.label19);
|
||||
this.panel4.Controls.Add(this.TXT_control_mode);
|
||||
@ -486,57 +444,50 @@
|
||||
this.panel4.Controls.Add(this.TXT_wpdist);
|
||||
this.panel4.Controls.Add(this.TXT_bererror);
|
||||
this.panel4.Controls.Add(this.TXT_alterror);
|
||||
resources.ApplyResources(this.panel4, "panel4");
|
||||
this.panel4.Name = "panel4";
|
||||
this.toolTip1.SetToolTip(this.panel4, resources.GetString("panel4.ToolTip"));
|
||||
//
|
||||
// label20
|
||||
//
|
||||
resources.ApplyResources(this.label20, "label20");
|
||||
this.label20.Name = "label20";
|
||||
this.label20.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label20, resources.GetString("label20.ToolTip"));
|
||||
//
|
||||
// label19
|
||||
//
|
||||
resources.ApplyResources(this.label19, "label19");
|
||||
this.label19.Name = "label19";
|
||||
this.label19.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label19, resources.GetString("label19.ToolTip"));
|
||||
//
|
||||
// TXT_control_mode
|
||||
//
|
||||
resources.ApplyResources(this.TXT_control_mode, "TXT_control_mode");
|
||||
this.TXT_control_mode.Name = "TXT_control_mode";
|
||||
this.TXT_control_mode.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_control_mode, resources.GetString("TXT_control_mode.ToolTip"));
|
||||
//
|
||||
// TXT_WP
|
||||
//
|
||||
resources.ApplyResources(this.TXT_WP, "TXT_WP");
|
||||
this.TXT_WP.Name = "TXT_WP";
|
||||
this.TXT_WP.resize = false;
|
||||
this.toolTip1.SetToolTip(this.TXT_WP, resources.GetString("TXT_WP.ToolTip"));
|
||||
//
|
||||
// label18
|
||||
//
|
||||
resources.ApplyResources(this.label18, "label18");
|
||||
this.label18.Name = "label18";
|
||||
this.label18.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label18, resources.GetString("label18.ToolTip"));
|
||||
//
|
||||
// label17
|
||||
//
|
||||
resources.ApplyResources(this.label17, "label17");
|
||||
this.label17.Name = "label17";
|
||||
this.label17.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label17, resources.GetString("label17.ToolTip"));
|
||||
//
|
||||
// panel5
|
||||
//
|
||||
resources.ApplyResources(this.panel5, "panel5");
|
||||
this.panel5.Controls.Add(this.ConnectComPort);
|
||||
resources.ApplyResources(this.panel5, "panel5");
|
||||
this.panel5.Name = "panel5";
|
||||
this.toolTip1.SetToolTip(this.panel5, resources.GetString("panel5.ToolTip"));
|
||||
//
|
||||
// zg1
|
||||
//
|
||||
@ -549,7 +500,6 @@
|
||||
this.zg1.ScrollMinX = 0D;
|
||||
this.zg1.ScrollMinY = 0D;
|
||||
this.zg1.ScrollMinY2 = 0D;
|
||||
this.toolTip1.SetToolTip(this.zg1, resources.GetString("zg1.ToolTip"));
|
||||
//
|
||||
// timer_servo_graph
|
||||
//
|
||||
@ -557,7 +507,6 @@
|
||||
//
|
||||
// panel6
|
||||
//
|
||||
resources.ApplyResources(this.panel6, "panel6");
|
||||
this.panel6.Controls.Add(this.label28);
|
||||
this.panel6.Controls.Add(this.label29);
|
||||
this.panel6.Controls.Add(this.label27);
|
||||
@ -570,42 +519,37 @@
|
||||
this.panel6.Controls.Add(this.TXT_ruddergain);
|
||||
this.panel6.Controls.Add(this.TXT_pitchgain);
|
||||
this.panel6.Controls.Add(this.TXT_rollgain);
|
||||
resources.ApplyResources(this.panel6, "panel6");
|
||||
this.panel6.Name = "panel6";
|
||||
this.toolTip1.SetToolTip(this.panel6, resources.GetString("panel6.ToolTip"));
|
||||
//
|
||||
// label28
|
||||
//
|
||||
resources.ApplyResources(this.label28, "label28");
|
||||
this.label28.Name = "label28";
|
||||
this.label28.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label28, resources.GetString("label28.ToolTip"));
|
||||
//
|
||||
// label29
|
||||
//
|
||||
resources.ApplyResources(this.label29, "label29");
|
||||
this.label29.Name = "label29";
|
||||
this.label29.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label29, resources.GetString("label29.ToolTip"));
|
||||
//
|
||||
// label27
|
||||
//
|
||||
resources.ApplyResources(this.label27, "label27");
|
||||
this.label27.Name = "label27";
|
||||
this.label27.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label27, resources.GetString("label27.ToolTip"));
|
||||
//
|
||||
// label25
|
||||
//
|
||||
resources.ApplyResources(this.label25, "label25");
|
||||
this.label25.Name = "label25";
|
||||
this.label25.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label25, resources.GetString("label25.ToolTip"));
|
||||
//
|
||||
// TXT_throttlegain
|
||||
//
|
||||
resources.ApplyResources(this.TXT_throttlegain, "TXT_throttlegain");
|
||||
this.TXT_throttlegain.Name = "TXT_throttlegain";
|
||||
this.toolTip1.SetToolTip(this.TXT_throttlegain, resources.GetString("TXT_throttlegain.ToolTip"));
|
||||
this.TXT_throttlegain.TextChanged += new System.EventHandler(this.TXT_throttlegain_TextChanged);
|
||||
//
|
||||
// label24
|
||||
@ -613,48 +557,41 @@
|
||||
resources.ApplyResources(this.label24, "label24");
|
||||
this.label24.Name = "label24";
|
||||
this.label24.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label24, resources.GetString("label24.ToolTip"));
|
||||
//
|
||||
// label23
|
||||
//
|
||||
resources.ApplyResources(this.label23, "label23");
|
||||
this.label23.Name = "label23";
|
||||
this.label23.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label23, resources.GetString("label23.ToolTip"));
|
||||
//
|
||||
// label22
|
||||
//
|
||||
resources.ApplyResources(this.label22, "label22");
|
||||
this.label22.Name = "label22";
|
||||
this.label22.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label22, resources.GetString("label22.ToolTip"));
|
||||
//
|
||||
// label21
|
||||
//
|
||||
resources.ApplyResources(this.label21, "label21");
|
||||
this.label21.Name = "label21";
|
||||
this.label21.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label21, resources.GetString("label21.ToolTip"));
|
||||
//
|
||||
// TXT_ruddergain
|
||||
//
|
||||
resources.ApplyResources(this.TXT_ruddergain, "TXT_ruddergain");
|
||||
this.TXT_ruddergain.Name = "TXT_ruddergain";
|
||||
this.toolTip1.SetToolTip(this.TXT_ruddergain, resources.GetString("TXT_ruddergain.ToolTip"));
|
||||
this.TXT_ruddergain.TextChanged += new System.EventHandler(this.TXT_ruddergain_TextChanged);
|
||||
//
|
||||
// TXT_pitchgain
|
||||
//
|
||||
resources.ApplyResources(this.TXT_pitchgain, "TXT_pitchgain");
|
||||
this.TXT_pitchgain.Name = "TXT_pitchgain";
|
||||
this.toolTip1.SetToolTip(this.TXT_pitchgain, resources.GetString("TXT_pitchgain.ToolTip"));
|
||||
this.TXT_pitchgain.TextChanged += new System.EventHandler(this.TXT_pitchgain_TextChanged);
|
||||
//
|
||||
// TXT_rollgain
|
||||
//
|
||||
resources.ApplyResources(this.TXT_rollgain, "TXT_rollgain");
|
||||
this.TXT_rollgain.Name = "TXT_rollgain";
|
||||
this.toolTip1.SetToolTip(this.TXT_rollgain, resources.GetString("TXT_rollgain.ToolTip"));
|
||||
this.TXT_rollgain.TextChanged += new System.EventHandler(this.TXT_rollgain_TextChanged);
|
||||
//
|
||||
// label26
|
||||
@ -662,13 +599,11 @@
|
||||
resources.ApplyResources(this.label26, "label26");
|
||||
this.label26.Name = "label26";
|
||||
this.label26.resize = false;
|
||||
this.toolTip1.SetToolTip(this.label26, resources.GetString("label26.ToolTip"));
|
||||
//
|
||||
// CHKdisplayall
|
||||
//
|
||||
resources.ApplyResources(this.CHKdisplayall, "CHKdisplayall");
|
||||
this.CHKdisplayall.Name = "CHKdisplayall";
|
||||
this.toolTip1.SetToolTip(this.CHKdisplayall, resources.GetString("CHKdisplayall.ToolTip"));
|
||||
this.CHKdisplayall.UseVisualStyleBackColor = true;
|
||||
this.CHKdisplayall.CheckedChanged += new System.EventHandler(this.CHKdisplayall_CheckedChanged);
|
||||
//
|
||||
@ -678,7 +613,6 @@
|
||||
this.CHKgraphroll.Checked = true;
|
||||
this.CHKgraphroll.CheckState = System.Windows.Forms.CheckState.Checked;
|
||||
this.CHKgraphroll.Name = "CHKgraphroll";
|
||||
this.toolTip1.SetToolTip(this.CHKgraphroll, resources.GetString("CHKgraphroll.ToolTip"));
|
||||
this.CHKgraphroll.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// CHKgraphpitch
|
||||
@ -687,7 +621,6 @@
|
||||
this.CHKgraphpitch.Checked = true;
|
||||
this.CHKgraphpitch.CheckState = System.Windows.Forms.CheckState.Checked;
|
||||
this.CHKgraphpitch.Name = "CHKgraphpitch";
|
||||
this.toolTip1.SetToolTip(this.CHKgraphpitch, resources.GetString("CHKgraphpitch.ToolTip"));
|
||||
this.CHKgraphpitch.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// CHKgraphrudder
|
||||
@ -696,7 +629,6 @@
|
||||
this.CHKgraphrudder.Checked = true;
|
||||
this.CHKgraphrudder.CheckState = System.Windows.Forms.CheckState.Checked;
|
||||
this.CHKgraphrudder.Name = "CHKgraphrudder";
|
||||
this.toolTip1.SetToolTip(this.CHKgraphrudder, resources.GetString("CHKgraphrudder.ToolTip"));
|
||||
this.CHKgraphrudder.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// CHKgraphthrottle
|
||||
@ -705,14 +637,12 @@
|
||||
this.CHKgraphthrottle.Checked = true;
|
||||
this.CHKgraphthrottle.CheckState = System.Windows.Forms.CheckState.Checked;
|
||||
this.CHKgraphthrottle.Name = "CHKgraphthrottle";
|
||||
this.toolTip1.SetToolTip(this.CHKgraphthrottle, resources.GetString("CHKgraphthrottle.ToolTip"));
|
||||
this.CHKgraphthrottle.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// but_advsettings
|
||||
//
|
||||
resources.ApplyResources(this.but_advsettings, "but_advsettings");
|
||||
this.but_advsettings.Name = "but_advsettings";
|
||||
this.toolTip1.SetToolTip(this.but_advsettings, resources.GetString("but_advsettings.ToolTip"));
|
||||
this.but_advsettings.UseVisualStyleBackColor = true;
|
||||
this.but_advsettings.Click += new System.EventHandler(this.but_advsettings_Click);
|
||||
//
|
||||
@ -720,14 +650,12 @@
|
||||
//
|
||||
resources.ApplyResources(this.chkSensor, "chkSensor");
|
||||
this.chkSensor.Name = "chkSensor";
|
||||
this.toolTip1.SetToolTip(this.chkSensor, resources.GetString("chkSensor.ToolTip"));
|
||||
this.chkSensor.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// CHK_quad
|
||||
//
|
||||
resources.ApplyResources(this.CHK_quad, "CHK_quad");
|
||||
this.CHK_quad.Name = "CHK_quad";
|
||||
this.toolTip1.SetToolTip(this.CHK_quad, resources.GetString("CHK_quad.ToolTip"));
|
||||
this.CHK_quad.UseVisualStyleBackColor = true;
|
||||
this.CHK_quad.CheckedChanged += new System.EventHandler(this.CHK_quad_CheckedChanged);
|
||||
//
|
||||
@ -735,7 +663,6 @@
|
||||
//
|
||||
resources.ApplyResources(this.BUT_startfgquad, "BUT_startfgquad");
|
||||
this.BUT_startfgquad.Name = "BUT_startfgquad";
|
||||
this.toolTip1.SetToolTip(this.BUT_startfgquad, resources.GetString("BUT_startfgquad.ToolTip"));
|
||||
this.BUT_startfgquad.UseVisualStyleBackColor = true;
|
||||
this.BUT_startfgquad.Click += new System.EventHandler(this.BUT_startfgquad_Click);
|
||||
//
|
||||
@ -743,7 +670,6 @@
|
||||
//
|
||||
resources.ApplyResources(this.BUT_startfgplane, "BUT_startfgplane");
|
||||
this.BUT_startfgplane.Name = "BUT_startfgplane";
|
||||
this.toolTip1.SetToolTip(this.BUT_startfgplane, resources.GetString("BUT_startfgplane.ToolTip"));
|
||||
this.BUT_startfgplane.UseVisualStyleBackColor = true;
|
||||
this.BUT_startfgplane.Click += new System.EventHandler(this.BUT_startfgplane_Click);
|
||||
//
|
||||
@ -751,7 +677,6 @@
|
||||
//
|
||||
resources.ApplyResources(this.BUT_startxplane, "BUT_startxplane");
|
||||
this.BUT_startxplane.Name = "BUT_startxplane";
|
||||
this.toolTip1.SetToolTip(this.BUT_startxplane, resources.GetString("BUT_startxplane.ToolTip"));
|
||||
this.BUT_startxplane.UseVisualStyleBackColor = true;
|
||||
this.BUT_startxplane.Click += new System.EventHandler(this.BUT_startxplane_Click);
|
||||
//
|
||||
@ -759,7 +684,6 @@
|
||||
//
|
||||
resources.ApplyResources(this.CHK_heli, "CHK_heli");
|
||||
this.CHK_heli.Name = "CHK_heli";
|
||||
this.toolTip1.SetToolTip(this.CHK_heli, resources.GetString("CHK_heli.ToolTip"));
|
||||
this.CHK_heli.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// RAD_aerosimrc
|
||||
@ -780,7 +704,6 @@
|
||||
//
|
||||
resources.ApplyResources(this.CHK_xplane10, "CHK_xplane10");
|
||||
this.CHK_xplane10.Name = "CHK_xplane10";
|
||||
this.toolTip1.SetToolTip(this.CHK_xplane10, resources.GetString("CHK_xplane10.ToolTip"));
|
||||
this.CHK_xplane10.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// Simulation
|
||||
@ -820,7 +743,6 @@
|
||||
this.Controls.Add(this.CHKREV_pitch);
|
||||
this.Controls.Add(this.CHKREV_roll);
|
||||
this.Name = "Simulation";
|
||||
this.toolTip1.SetToolTip(this, resources.GetString("$this.ToolTip"));
|
||||
this.Load += new System.EventHandler(this.Simulation_Load);
|
||||
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
|
||||
this.panel1.ResumeLayout(false);
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -146,7 +146,11 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
}
|
||||
// do not change this \r is correct - no \n
|
||||
if (cmd == "+++")
|
||||
comPort.Write(Encoding.ASCII.GetBytes(cmd), 0, cmd.Length);
|
||||
else {
|
||||
comPort.Write(Encoding.ASCII.GetBytes(cmd + "\r"), 0, cmd.Length + 1);
|
||||
}
|
||||
}
|
||||
catch { MessageBox.Show("Error writing to com port"); }
|
||||
}
|
||||
|
@ -676,6 +676,7 @@ namespace hud
|
||||
|
||||
void doPaint(PaintEventArgs e)
|
||||
{
|
||||
bool isNaN = false;
|
||||
try
|
||||
{
|
||||
if (graphicsObjectGDIP == null || !opengl && (objBitmap.Width != this.Width || objBitmap.Height != this.Height))
|
||||
@ -709,9 +710,22 @@ namespace hud
|
||||
bgon = true;
|
||||
}
|
||||
|
||||
|
||||
if (float.IsNaN(_roll) || float.IsNaN(_pitch) || float.IsNaN(_heading))
|
||||
{
|
||||
isNaN = true;
|
||||
|
||||
_roll = 0;
|
||||
_pitch = 0;
|
||||
_heading = 0;
|
||||
}
|
||||
|
||||
graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2);
|
||||
|
||||
graphicsObject.RotateTransform(-_roll);
|
||||
|
||||
|
||||
graphicsObject.RotateTransform(-_roll);
|
||||
|
||||
|
||||
int fontsize = this.Height / 30; // = 10
|
||||
int fontoffset = fontsize - 10;
|
||||
@ -1272,6 +1286,11 @@ namespace hud
|
||||
|
||||
drawstring(graphicsObject, gps, font, fontsize + 2, whiteBrush, this.Width - 10 * fontsize, this.Height - 30 - fontoffset);
|
||||
|
||||
|
||||
if (isNaN)
|
||||
drawstring(graphicsObject, "NaN Error " + DateTime.Now, font, this.Height / 30 + 10, Brushes.Red, 50, 50);
|
||||
|
||||
|
||||
if (!opengl)
|
||||
{
|
||||
e.Graphics.DrawImageUnscaled(objBitmap, 0, 0);
|
||||
@ -1305,7 +1324,6 @@ namespace hud
|
||||
catch (Exception ex)
|
||||
{
|
||||
Console.WriteLine("hud error "+ex.ToString());
|
||||
//MessageBox.Show(ex.ToString());
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -83,7 +83,7 @@ namespace ArdupilotMega
|
||||
|
||||
threadrun = true;
|
||||
|
||||
System.Threading.Thread.Sleep(2000);
|
||||
System.Threading.Thread.Sleep(4000);
|
||||
|
||||
try
|
||||
{
|
||||
|
@ -9,6 +9,8 @@ using System.Reflection;
|
||||
using System.Reflection.Emit;
|
||||
using System.IO;
|
||||
using System.Drawing;
|
||||
using System.Threading;
|
||||
using ArdupilotMega.Controls;
|
||||
using ArdupilotMega.Mavlink;
|
||||
using System.ComponentModel;
|
||||
|
||||
@ -20,14 +22,10 @@ namespace ArdupilotMega
|
||||
|
||||
private const double CONNECT_TIMEOUT_SECONDS = 30;
|
||||
|
||||
/// <summary>
|
||||
/// Used for progress reporting on all internal functions
|
||||
/// </summary>
|
||||
public event ProgressEventHandler Progress;
|
||||
/// <summary>
|
||||
/// progress form to handle connect and param requests
|
||||
/// </summary>
|
||||
ProgressReporter frm;
|
||||
ProgressReporterDialogue frmProgressReporter;
|
||||
|
||||
/// <summary>
|
||||
/// used for outbound packet sending
|
||||
@ -131,22 +129,39 @@ namespace ArdupilotMega
|
||||
if (BaseStream.IsOpen)
|
||||
return;
|
||||
|
||||
//System.Windows.Forms.Form frm = Common.LoadingBox("Mavlink Connecting..", "Mavlink Connecting..");
|
||||
//frm.TopMost = true;
|
||||
frmProgressReporter = new ProgressReporterDialogue
|
||||
{
|
||||
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
|
||||
Text = "Connecting Mavlink"
|
||||
};
|
||||
|
||||
frm = new ProgressReporter();
|
||||
MainV2.fixtheme(frm);
|
||||
this.Progress += new ProgressEventHandler(MAVLink_Progress);
|
||||
//(progress, status) => { frm.updateProgressAndStatus(progress, status); };
|
||||
if (getparams)
|
||||
{
|
||||
frmProgressReporter.DoWork += FrmProgressReporterDoWorkAndParams;
|
||||
}
|
||||
else
|
||||
{
|
||||
frmProgressReporter.DoWork += FrmProgressReporterDoWorkNOParams;
|
||||
}
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Mavlink Connecting...");
|
||||
MainV2.fixtheme(frmProgressReporter);
|
||||
|
||||
frm.StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen;
|
||||
frmProgressReporter.RunBackgroundOperationAsync();
|
||||
}
|
||||
|
||||
frm.Show();
|
||||
void FrmProgressReporterDoWorkAndParams(object sender, ProgressWorkerEventArgs e)
|
||||
{
|
||||
OpenBg(true, e);
|
||||
}
|
||||
|
||||
frm.Focus();
|
||||
void FrmProgressReporterDoWorkNOParams(object sender, ProgressWorkerEventArgs e)
|
||||
{
|
||||
OpenBg(false, e);
|
||||
}
|
||||
|
||||
if (Progress != null)
|
||||
Progress(-1, "Mavlink Connecting...");
|
||||
private void OpenBg(bool getparams, ProgressWorkerEventArgs progressWorkerEventArgs)
|
||||
{
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Mavlink Connecting...");
|
||||
|
||||
// reset
|
||||
sysid = 0;
|
||||
@ -168,15 +183,7 @@ namespace ArdupilotMega
|
||||
|
||||
BaseStream.toggleDTR();
|
||||
|
||||
// allow 2560 connect timeout on usb
|
||||
for (int a = 0; a < 1000; a++ ) {
|
||||
System.Threading.Thread.Sleep(1);
|
||||
if (!MainV2.instance.InvokeRequired)
|
||||
{
|
||||
System.Windows.Forms.Application.DoEvents();
|
||||
}
|
||||
}
|
||||
|
||||
Thread.Sleep(1000);
|
||||
}
|
||||
|
||||
byte[] buffer;
|
||||
@ -189,8 +196,9 @@ namespace ArdupilotMega
|
||||
countDown.Elapsed += (sender, e) =>
|
||||
{
|
||||
int secondsRemaining = (deadline - e.SignalTime).Seconds;
|
||||
if (Progress != null)
|
||||
Progress(-1, string.Format("Trying to connect.\nTimeout in {0}", secondsRemaining));
|
||||
//if (Progress != null)
|
||||
// Progress(-1, string.Format("Trying to connect.\nTimeout in {0}", secondsRemaining));
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, string.Format("Trying to connect.\nTimeout in {0}", secondsRemaining));
|
||||
if (secondsRemaining > 0) countDown.Start();
|
||||
};
|
||||
countDown.Start();
|
||||
@ -199,31 +207,35 @@ namespace ArdupilotMega
|
||||
|
||||
while (true)
|
||||
{
|
||||
if (progressWorkerEventArgs.CancelRequested)
|
||||
{
|
||||
progressWorkerEventArgs.CancelAcknowledged = true;
|
||||
countDown.Stop();
|
||||
if (BaseStream.IsOpen)
|
||||
BaseStream.Close();
|
||||
MainV2.givecomport = false;
|
||||
return;
|
||||
}
|
||||
|
||||
// incase we are in setup mode
|
||||
BaseStream.WriteLine("planner\rgcs\r");
|
||||
|
||||
Console.WriteLine(DateTime.Now.Millisecond + " start ");
|
||||
|
||||
/*
|
||||
if (Progress != null)
|
||||
{
|
||||
int secondsRemaining = (start.AddSeconds(CONNECT_TIMEOUT_SECONDS) - DateTime.Now).Seconds;
|
||||
Progress(-1, string.Format("Trying to connect.\nTimeout in {0}", secondsRemaining));
|
||||
}
|
||||
*/
|
||||
|
||||
if (lastbad[0] == '!' && lastbad[1] == 'G' || lastbad[0] == 'G' && lastbad[1] == '!') // waiting for gps lock
|
||||
{
|
||||
if (Progress != null)
|
||||
Progress(-1, "Waiting for GPS detection..");
|
||||
start = start.AddSeconds(5); // each round is 1.1 seconds
|
||||
//if (Progress != null)
|
||||
// Progress(-1, "Waiting for GPS detection..");
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Waiting for GPS detection..");
|
||||
deadline = deadline.AddSeconds(5); // each round is 1.1 seconds
|
||||
}
|
||||
|
||||
if (DateTime.Now > deadline)
|
||||
{
|
||||
if (Progress != null)
|
||||
Progress(-1, "No Heatbeat Packets");
|
||||
//if (Progress != null)
|
||||
// Progress(-1, "No Heatbeat Packets");
|
||||
this.Close();
|
||||
progressWorkerEventArgs.ErrorMessage = "No Heatbeat Packets Received";
|
||||
throw new Exception("No Mavlink Heartbeat Packets where read from this port - Verify Baud Rate and setup\nIt might also be waiting for GPS Lock\nAPM Planner waits for 2 valid heartbeat packets before connecting");
|
||||
}
|
||||
|
||||
@ -267,11 +279,12 @@ namespace ArdupilotMega
|
||||
|
||||
countDown.Stop();
|
||||
|
||||
if (Progress != null)
|
||||
Progress(-1, "Getting Params.. (sysid " + sysid + " compid " + compid + ") ");
|
||||
// if (Progress != null)
|
||||
// Progress(-1, "Getting Params.. (sysid " + sysid + " compid " + compid + ") ");
|
||||
frmProgressReporter.UpdateProgressAndStatus(0, "Getting Params.. (sysid " + sysid + " compid " + compid + ") ");
|
||||
|
||||
if (getparams)
|
||||
getParamList();
|
||||
getParamListBG();
|
||||
}
|
||||
catch (Exception e)
|
||||
{
|
||||
@ -281,28 +294,19 @@ namespace ArdupilotMega
|
||||
}
|
||||
catch { }
|
||||
MainV2.givecomport = false;
|
||||
if (Progress != null)
|
||||
Progress(-1, "Connect Failed\n" + e.Message);
|
||||
throw e;
|
||||
// if (Progress != null)
|
||||
// Progress(-1, "Connect Failed\n" + e.Message);
|
||||
if (string.IsNullOrEmpty(progressWorkerEventArgs.ErrorMessage))
|
||||
progressWorkerEventArgs.ErrorMessage = "Connect Failed";
|
||||
throw;
|
||||
}
|
||||
frm.Close();
|
||||
//frmProgressReporter.Close();
|
||||
MainV2.givecomport = false;
|
||||
frmProgressReporter.UpdateProgressAndStatus(100, "Done.");
|
||||
Console.WriteLine("Done open " + sysid + " " + compid);
|
||||
packetslost = 0;
|
||||
}
|
||||
|
||||
void MAVLink_Progress(int progress, string status)
|
||||
{
|
||||
if (frm != null)
|
||||
{
|
||||
try
|
||||
{
|
||||
frm.updateProgressAndStatus(progress, status);
|
||||
}
|
||||
catch (Exception ex) { throw ex; }
|
||||
}
|
||||
}
|
||||
|
||||
byte[] getHeartBeat()
|
||||
{
|
||||
DateTime start = DateTime.Now;
|
||||
@ -556,19 +560,48 @@ namespace ArdupilotMega
|
||||
|
||||
}
|
||||
*/
|
||||
public void getParamList()
|
||||
{
|
||||
frmProgressReporter = new ProgressReporterDialogue
|
||||
{
|
||||
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
|
||||
Text = "Getting Params"
|
||||
};
|
||||
|
||||
frmProgressReporter.DoWork += FrmProgressReporterGetParams;
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Getting Params...");
|
||||
MainV2.fixtheme(frmProgressReporter);
|
||||
|
||||
frmProgressReporter.RunBackgroundOperationAsync();
|
||||
}
|
||||
|
||||
void FrmProgressReporterGetParams(object sender, ProgressWorkerEventArgs e)
|
||||
{
|
||||
Hashtable old = new Hashtable(param);
|
||||
getParamListBG();
|
||||
if (frmProgressReporter.doWorkArgs.CancelRequested)
|
||||
{
|
||||
param = old;
|
||||
}
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Get param list from apm
|
||||
/// </summary>
|
||||
/// <returns></returns>
|
||||
public Hashtable getParamList()
|
||||
private Hashtable getParamListBG()
|
||||
{
|
||||
MainV2.givecomport = true;
|
||||
List<int> missed = new List<int>();
|
||||
|
||||
// ryan - re start
|
||||
__mavlink_param_request_read_t rereq = new __mavlink_param_request_read_t();
|
||||
rereq.target_system = sysid;
|
||||
rereq.target_component = compid;
|
||||
// clear old
|
||||
param = new Hashtable();
|
||||
|
||||
int retrys = 3;
|
||||
int param_count = 0;
|
||||
int param_total = 5;
|
||||
|
||||
goagain:
|
||||
|
||||
__mavlink_param_request_list_t req = new __mavlink_param_request_list_t();
|
||||
req.target_system = sysid;
|
||||
@ -578,13 +611,18 @@ namespace ArdupilotMega
|
||||
|
||||
DateTime start = DateTime.Now;
|
||||
DateTime restart = DateTime.Now;
|
||||
|
||||
int retrys = 3;
|
||||
int nextid = 0;
|
||||
int param_count = 0;
|
||||
int param_total = 5;
|
||||
|
||||
while (param_count < param_total)
|
||||
{
|
||||
|
||||
if (frmProgressReporter.doWorkArgs.CancelRequested)
|
||||
{
|
||||
frmProgressReporter.doWorkArgs.CancelAcknowledged = true;
|
||||
MainV2.givecomport = false;
|
||||
frmProgressReporter.doWorkArgs.ErrorMessage = "User Canceled";
|
||||
return param;
|
||||
}
|
||||
|
||||
if (!(start.AddMilliseconds(5000) > DateTime.Now))
|
||||
{
|
||||
if (retrys > 0)
|
||||
@ -598,15 +636,7 @@ namespace ArdupilotMega
|
||||
MainV2.givecomport = false;
|
||||
throw new Exception("Timeout on read - getParamList");
|
||||
}
|
||||
if (!(restart.AddMilliseconds(1000) > DateTime.Now))
|
||||
{
|
||||
rereq.param_id = new byte[] { 0x0, 0x0 };
|
||||
rereq.param_index = (short)nextid;
|
||||
sendPacket(rereq);
|
||||
restart = DateTime.Now;
|
||||
}
|
||||
|
||||
System.Windows.Forms.Application.DoEvents();
|
||||
byte[] buffer = readPacket();
|
||||
if (buffer.Length > 5)
|
||||
{
|
||||
@ -619,9 +649,10 @@ namespace ArdupilotMega
|
||||
|
||||
__mavlink_param_value_t par = buffer.ByteArrayToStructure<__mavlink_param_value_t>(6);
|
||||
|
||||
// set new target
|
||||
param_total = (par.param_count);
|
||||
|
||||
|
||||
|
||||
string paramID = System.Text.ASCIIEncoding.ASCII.GetString(par.param_id);
|
||||
|
||||
int pos = paramID.IndexOf('\0');
|
||||
@ -629,47 +660,41 @@ namespace ArdupilotMega
|
||||
{
|
||||
paramID = paramID.Substring(0, pos);
|
||||
}
|
||||
Console.WriteLine(DateTime.Now.Millisecond + " got param " + (par.param_index) + " of " + (param_total - 1) + " name: " + paramID);
|
||||
|
||||
// for out of order udp packets
|
||||
if (BaseStream.GetType() != typeof(UdpSerial))
|
||||
{
|
||||
if (nextid == (par.param_index))
|
||||
{
|
||||
nextid++;
|
||||
if (Progress != null)
|
||||
Progress((par.param_index * 100) / param_total, "Got param " + paramID);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
if (retrys > 0)
|
||||
{
|
||||
generatePacket(MAVLINK_MSG_ID_PARAM_REQUEST_LIST, req);
|
||||
param_count = 0;
|
||||
nextid = 0;
|
||||
retrys--;
|
||||
continue;
|
||||
}
|
||||
Console.WriteLine("Out of order packet. Re-requesting list");
|
||||
missed.Add(nextid); // for later devel
|
||||
MainV2.givecomport = false;
|
||||
throw new Exception("Missed ID expecting " + nextid + " got " + (par.param_index) + "\nPlease try loading again");
|
||||
}
|
||||
// check if we already have it
|
||||
if (param.ContainsKey(paramID)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
Console.WriteLine(DateTime.Now.Millisecond + " got param " + (par.param_index) + " of " + (param_total - 1) + " name: " + paramID);
|
||||
|
||||
modifyParamForDisplay(true, paramID, ref par.param_value);
|
||||
param[paramID] = (par.param_value);
|
||||
param_count++;
|
||||
|
||||
// if (Progress != null)
|
||||
// Progress((param.Count * 100) / param_total, "Got param " + paramID);
|
||||
this.frmProgressReporter.UpdateProgressAndStatus((param.Count * 100) / param_total, "Got param " + paramID);
|
||||
}
|
||||
else
|
||||
{
|
||||
//Console.WriteLine(DateTime.Now + " PC paramlist " + buffer[5] + " " + this.BytesToRead);
|
||||
//Console.WriteLine(DateTime.Now + " PC paramlist " + buffer[5] + " want " + MAVLINK_MSG_ID_PARAM_VALUE + " btr " + BaseStream.BytesToRead);
|
||||
}
|
||||
//stopwatch.Stop();
|
||||
//Console.WriteLine("Time elapsed: {0}", stopwatch.Elapsed);
|
||||
}
|
||||
}
|
||||
|
||||
if (param.Count != param_total)
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
this.frmProgressReporter.UpdateProgressAndStatus((param.Count * 100) / param_total, "Getting missed params");
|
||||
retrys--;
|
||||
goto goagain;
|
||||
}
|
||||
throw new Exception("Missing Params");
|
||||
}
|
||||
MainV2.givecomport = false;
|
||||
return param;
|
||||
}
|
||||
@ -1923,10 +1948,10 @@ namespace ArdupilotMega
|
||||
throw new Exception("Timeout");
|
||||
}
|
||||
System.Threading.Thread.Sleep(1);
|
||||
if (!MainV2.instance.InvokeRequired)
|
||||
{
|
||||
System.Windows.Forms.Application.DoEvents(); // when connecting this is in the main thread
|
||||
}
|
||||
// if (!MainV2.instance.InvokeRequired)
|
||||
// {
|
||||
// System.Windows.Forms.Application.DoEvents(); // when connecting this is in the main thread
|
||||
// }
|
||||
to++;
|
||||
}
|
||||
if (BaseStream.IsOpen)
|
||||
|
@ -125,8 +125,8 @@ namespace ArdupilotMega
|
||||
CMB_serialport.Items.Add("UDP");
|
||||
if (CMB_serialport.Items.Count > 0)
|
||||
{
|
||||
CMB_serialport.SelectedIndex = 0;
|
||||
CMB_baudrate.SelectedIndex = 7;
|
||||
CMB_serialport.SelectedIndex = 0;
|
||||
}
|
||||
|
||||
splash.Refresh();
|
||||
@ -1945,6 +1945,13 @@ namespace ArdupilotMega
|
||||
frm.Show();
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.A)) // test
|
||||
{
|
||||
Form frm = new _3DRradio();
|
||||
fixtheme(frm);
|
||||
frm.Show();
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.T)) // for override connect
|
||||
{
|
||||
try
|
||||
|
@ -34,5 +34,5 @@ using System.Resources;
|
||||
// by using the '*' as shown below:
|
||||
// [assembly: AssemblyVersion("1.0.*")]
|
||||
[assembly: AssemblyVersion("1.0.0.0")]
|
||||
[assembly: AssemblyFileVersion("1.1.40")]
|
||||
[assembly: AssemblyFileVersion("1.1.41")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
@ -214,6 +214,20 @@ namespace ArdupilotMega.Properties {
|
||||
}
|
||||
}
|
||||
|
||||
public static System.Drawing.Bitmap iconWarning32 {
|
||||
get {
|
||||
object obj = ResourceManager.GetObject("iconWarning32", resourceCulture);
|
||||
return ((System.Drawing.Bitmap)(obj));
|
||||
}
|
||||
}
|
||||
|
||||
public static System.Drawing.Bitmap iconWarning48 {
|
||||
get {
|
||||
object obj = ResourceManager.GetObject("iconWarning48", resourceCulture);
|
||||
return ((System.Drawing.Bitmap)(obj));
|
||||
}
|
||||
}
|
||||
|
||||
public static System.Drawing.Bitmap octo {
|
||||
get {
|
||||
object obj = ResourceManager.GetObject("octo", resourceCulture);
|
||||
|
@ -181,9 +181,6 @@
|
||||
<data name="hexa" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\frames-07.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<data name="y6" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\frames-08.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<data name="planeicon" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\planetracker.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
@ -1201,7 +1198,6 @@
|
||||
<data name="opticalflow" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\BR-0016-01-3T.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="hil" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\new frames-10.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
@ -1220,4 +1216,14 @@
|
||||
<data name="octov" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\new frames-06.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<data name="iconWarning32" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\iconWarning32.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<data name="iconWarning48" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\iconWarning48.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="y6" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\y6.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
</root>
|
620
Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
generated
Normal file
620
Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
generated
Normal file
@ -0,0 +1,620 @@
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
partial class _3DRradio
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Windows Form Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.components = new System.ComponentModel.Container();
|
||||
this.Progressbar = new System.Windows.Forms.ProgressBar();
|
||||
this.S1 = new System.Windows.Forms.ComboBox();
|
||||
this.label1 = new System.Windows.Forms.Label();
|
||||
this.S0 = new System.Windows.Forms.TextBox();
|
||||
this.label2 = new System.Windows.Forms.Label();
|
||||
this.label3 = new System.Windows.Forms.Label();
|
||||
this.S2 = new System.Windows.Forms.ComboBox();
|
||||
this.label4 = new System.Windows.Forms.Label();
|
||||
this.S3 = new System.Windows.Forms.ComboBox();
|
||||
this.label5 = new System.Windows.Forms.Label();
|
||||
this.S4 = new System.Windows.Forms.ComboBox();
|
||||
this.label6 = new System.Windows.Forms.Label();
|
||||
this.S5 = new System.Windows.Forms.CheckBox();
|
||||
this.label7 = new System.Windows.Forms.Label();
|
||||
this.S6 = new System.Windows.Forms.CheckBox();
|
||||
this.label8 = new System.Windows.Forms.Label();
|
||||
this.S7 = new System.Windows.Forms.CheckBox();
|
||||
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
|
||||
this.RS7 = new System.Windows.Forms.CheckBox();
|
||||
this.RS6 = new System.Windows.Forms.CheckBox();
|
||||
this.RS5 = new System.Windows.Forms.CheckBox();
|
||||
this.RS4 = new System.Windows.Forms.ComboBox();
|
||||
this.RS3 = new System.Windows.Forms.ComboBox();
|
||||
this.RS2 = new System.Windows.Forms.ComboBox();
|
||||
this.RS1 = new System.Windows.Forms.ComboBox();
|
||||
this.RS0 = new System.Windows.Forms.TextBox();
|
||||
this.label9 = new System.Windows.Forms.Label();
|
||||
this.label10 = new System.Windows.Forms.Label();
|
||||
this.RTI = new System.Windows.Forms.TextBox();
|
||||
this.ATI = new System.Windows.Forms.TextBox();
|
||||
this.RSSI = new System.Windows.Forms.TextBox();
|
||||
this.label11 = new System.Windows.Forms.Label();
|
||||
this.label12 = new System.Windows.Forms.Label();
|
||||
this.BUT_savesettings = new ArdupilotMega.MyButton();
|
||||
this.BUT_getcurrent = new ArdupilotMega.MyButton();
|
||||
this.lbl_status = new ArdupilotMega.MyLabel();
|
||||
this.BUT_upload = new ArdupilotMega.MyButton();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// Progressbar
|
||||
//
|
||||
this.Progressbar.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left)
|
||||
| System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.Progressbar.Location = new System.Drawing.Point(12, 368);
|
||||
this.Progressbar.Name = "Progressbar";
|
||||
this.Progressbar.Size = new System.Drawing.Size(294, 36);
|
||||
this.Progressbar.TabIndex = 2;
|
||||
//
|
||||
// S1
|
||||
//
|
||||
this.S1.FormattingEnabled = true;
|
||||
this.S1.Items.AddRange(new object[] {
|
||||
"115",
|
||||
"111",
|
||||
"57",
|
||||
"38",
|
||||
"19",
|
||||
"9",
|
||||
"4",
|
||||
"2",
|
||||
"1"});
|
||||
this.S1.Location = new System.Drawing.Point(87, 103);
|
||||
this.S1.Name = "S1";
|
||||
this.S1.Size = new System.Drawing.Size(80, 21);
|
||||
this.S1.TabIndex = 4;
|
||||
this.toolTip1.SetToolTip(this.S1, "Serial Baud Rate 57 = 57600");
|
||||
//
|
||||
// label1
|
||||
//
|
||||
this.label1.AutoSize = true;
|
||||
this.label1.Location = new System.Drawing.Point(15, 111);
|
||||
this.label1.Name = "label1";
|
||||
this.label1.Size = new System.Drawing.Size(32, 13);
|
||||
this.label1.TabIndex = 5;
|
||||
this.label1.Text = "Baud";
|
||||
//
|
||||
// S0
|
||||
//
|
||||
this.S0.Location = new System.Drawing.Point(87, 77);
|
||||
this.S0.Name = "S0";
|
||||
this.S0.ReadOnly = true;
|
||||
this.S0.Size = new System.Drawing.Size(80, 20);
|
||||
this.S0.TabIndex = 7;
|
||||
//
|
||||
// label2
|
||||
//
|
||||
this.label2.AutoSize = true;
|
||||
this.label2.Location = new System.Drawing.Point(15, 84);
|
||||
this.label2.Name = "label2";
|
||||
this.label2.Size = new System.Drawing.Size(39, 13);
|
||||
this.label2.TabIndex = 8;
|
||||
this.label2.Text = "Format";
|
||||
//
|
||||
// label3
|
||||
//
|
||||
this.label3.AutoSize = true;
|
||||
this.label3.Location = new System.Drawing.Point(15, 138);
|
||||
this.label3.Name = "label3";
|
||||
this.label3.Size = new System.Drawing.Size(53, 13);
|
||||
this.label3.TabIndex = 10;
|
||||
this.label3.Text = "Air Speed";
|
||||
//
|
||||
// S2
|
||||
//
|
||||
this.S2.FormattingEnabled = true;
|
||||
this.S2.Items.AddRange(new object[] {
|
||||
"192",
|
||||
"160",
|
||||
"128",
|
||||
"96",
|
||||
"64",
|
||||
"32",
|
||||
"16"});
|
||||
this.S2.Location = new System.Drawing.Point(87, 130);
|
||||
this.S2.Name = "S2";
|
||||
this.S2.Size = new System.Drawing.Size(80, 21);
|
||||
this.S2.TabIndex = 9;
|
||||
this.toolTip1.SetToolTip(this.S2, "the inter-radio data rate in rounded kbps. So 128 means");
|
||||
//
|
||||
// label4
|
||||
//
|
||||
this.label4.AutoSize = true;
|
||||
this.label4.Location = new System.Drawing.Point(15, 165);
|
||||
this.label4.Name = "label4";
|
||||
this.label4.Size = new System.Drawing.Size(38, 13);
|
||||
this.label4.TabIndex = 12;
|
||||
this.label4.Text = "Net ID";
|
||||
//
|
||||
// S3
|
||||
//
|
||||
this.S3.FormattingEnabled = true;
|
||||
this.S3.Items.AddRange(new object[] {
|
||||
"1",
|
||||
"2",
|
||||
"3",
|
||||
"4",
|
||||
"5",
|
||||
"6",
|
||||
"7",
|
||||
"8",
|
||||
"9",
|
||||
"10",
|
||||
"11",
|
||||
"12",
|
||||
"13",
|
||||
"14",
|
||||
"15",
|
||||
"16",
|
||||
"17",
|
||||
"18",
|
||||
"19",
|
||||
"20",
|
||||
"21",
|
||||
"22",
|
||||
"23",
|
||||
"24",
|
||||
"25",
|
||||
"26",
|
||||
"27",
|
||||
"28",
|
||||
"29",
|
||||
"30"});
|
||||
this.S3.Location = new System.Drawing.Point(87, 157);
|
||||
this.S3.Name = "S3";
|
||||
this.S3.Size = new System.Drawing.Size(80, 21);
|
||||
this.S3.TabIndex = 11;
|
||||
this.toolTip1.SetToolTip(this.S3, "a 16 bit \'network ID\'. This is used to seed the frequency");
|
||||
//
|
||||
// label5
|
||||
//
|
||||
this.label5.AutoSize = true;
|
||||
this.label5.Location = new System.Drawing.Point(15, 192);
|
||||
this.label5.Name = "label5";
|
||||
this.label5.Size = new System.Drawing.Size(52, 13);
|
||||
this.label5.TabIndex = 14;
|
||||
this.label5.Text = "Tx Power";
|
||||
//
|
||||
// S4
|
||||
//
|
||||
this.S4.FormattingEnabled = true;
|
||||
this.S4.Items.AddRange(new object[] {
|
||||
"0",
|
||||
"1",
|
||||
"2",
|
||||
"3",
|
||||
"4",
|
||||
"5",
|
||||
"6",
|
||||
"7",
|
||||
"8",
|
||||
"9",
|
||||
"10",
|
||||
"11",
|
||||
"12",
|
||||
"13",
|
||||
"14",
|
||||
"15",
|
||||
"16",
|
||||
"17",
|
||||
"18",
|
||||
"19",
|
||||
"20"});
|
||||
this.S4.Location = new System.Drawing.Point(87, 184);
|
||||
this.S4.Name = "S4";
|
||||
this.S4.Size = new System.Drawing.Size(80, 21);
|
||||
this.S4.TabIndex = 13;
|
||||
this.toolTip1.SetToolTip(this.S4, "the transmit power in dBm. 20dBm is 100mW. It is useful to");
|
||||
//
|
||||
// label6
|
||||
//
|
||||
this.label6.AutoSize = true;
|
||||
this.label6.Location = new System.Drawing.Point(15, 219);
|
||||
this.label6.Name = "label6";
|
||||
this.label6.Size = new System.Drawing.Size(28, 13);
|
||||
this.label6.TabIndex = 16;
|
||||
this.label6.Text = "ECC";
|
||||
//
|
||||
// S5
|
||||
//
|
||||
this.S5.Location = new System.Drawing.Point(87, 211);
|
||||
this.S5.Name = "S5";
|
||||
this.S5.Size = new System.Drawing.Size(80, 21);
|
||||
this.S5.TabIndex = 15;
|
||||
this.toolTip1.SetToolTip(this.S5, "to enable/disable the golay error correcting code. It defaults");
|
||||
//
|
||||
// label7
|
||||
//
|
||||
this.label7.AutoSize = true;
|
||||
this.label7.Location = new System.Drawing.Point(15, 246);
|
||||
this.label7.Name = "label7";
|
||||
this.label7.Size = new System.Drawing.Size(44, 13);
|
||||
this.label7.TabIndex = 18;
|
||||
this.label7.Text = "Mavlink";
|
||||
//
|
||||
// S6
|
||||
//
|
||||
this.S6.Location = new System.Drawing.Point(87, 238);
|
||||
this.S6.Name = "S6";
|
||||
this.S6.Size = new System.Drawing.Size(80, 21);
|
||||
this.S6.TabIndex = 17;
|
||||
this.toolTip1.SetToolTip(this.S6, "enables/disables MAVLink packet framing. This tries to align");
|
||||
//
|
||||
// label8
|
||||
//
|
||||
this.label8.AutoSize = true;
|
||||
this.label8.Location = new System.Drawing.Point(15, 273);
|
||||
this.label8.Name = "label8";
|
||||
this.label8.Size = new System.Drawing.Size(68, 13);
|
||||
this.label8.TabIndex = 20;
|
||||
this.label8.Text = "Op Pre Send";
|
||||
//
|
||||
// S7
|
||||
//
|
||||
this.S7.Location = new System.Drawing.Point(87, 265);
|
||||
this.S7.Name = "S7";
|
||||
this.S7.Size = new System.Drawing.Size(80, 21);
|
||||
this.S7.TabIndex = 19;
|
||||
this.toolTip1.SetToolTip(this.S7, "enables/disables \"opportunistic resend\". When enabled the");
|
||||
//
|
||||
// RS7
|
||||
//
|
||||
this.RS7.Location = new System.Drawing.Point(201, 265);
|
||||
this.RS7.Name = "RS7";
|
||||
this.RS7.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS7.TabIndex = 29;
|
||||
this.toolTip1.SetToolTip(this.RS7, "enables/disables \"opportunistic resend\". When enabled the");
|
||||
//
|
||||
// RS6
|
||||
//
|
||||
this.RS6.Location = new System.Drawing.Point(201, 238);
|
||||
this.RS6.Name = "RS6";
|
||||
this.RS6.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS6.TabIndex = 28;
|
||||
this.toolTip1.SetToolTip(this.RS6, "enables/disables MAVLink packet framing. This tries to align");
|
||||
//
|
||||
// RS5
|
||||
//
|
||||
this.RS5.Location = new System.Drawing.Point(201, 211);
|
||||
this.RS5.Name = "RS5";
|
||||
this.RS5.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS5.TabIndex = 27;
|
||||
this.toolTip1.SetToolTip(this.RS5, "to enable/disable the golay error correcting code. It defaults");
|
||||
//
|
||||
// RS4
|
||||
//
|
||||
this.RS4.FormattingEnabled = true;
|
||||
this.RS4.Items.AddRange(new object[] {
|
||||
"0",
|
||||
"1",
|
||||
"2",
|
||||
"3",
|
||||
"4",
|
||||
"5",
|
||||
"6",
|
||||
"7",
|
||||
"8",
|
||||
"9",
|
||||
"10",
|
||||
"11",
|
||||
"12",
|
||||
"13",
|
||||
"14",
|
||||
"15",
|
||||
"16",
|
||||
"17",
|
||||
"18",
|
||||
"19",
|
||||
"20"});
|
||||
this.RS4.Location = new System.Drawing.Point(201, 184);
|
||||
this.RS4.Name = "RS4";
|
||||
this.RS4.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS4.TabIndex = 26;
|
||||
this.toolTip1.SetToolTip(this.RS4, "the transmit power in dBm. 20dBm is 100mW. It is useful to");
|
||||
//
|
||||
// RS3
|
||||
//
|
||||
this.RS3.FormattingEnabled = true;
|
||||
this.RS3.Items.AddRange(new object[] {
|
||||
"1",
|
||||
"2",
|
||||
"3",
|
||||
"4",
|
||||
"5",
|
||||
"6",
|
||||
"7",
|
||||
"8",
|
||||
"9",
|
||||
"10",
|
||||
"11",
|
||||
"12",
|
||||
"13",
|
||||
"14",
|
||||
"15",
|
||||
"16",
|
||||
"17",
|
||||
"18",
|
||||
"19",
|
||||
"20",
|
||||
"21",
|
||||
"22",
|
||||
"23",
|
||||
"24",
|
||||
"25",
|
||||
"26",
|
||||
"27",
|
||||
"28",
|
||||
"29",
|
||||
"30"});
|
||||
this.RS3.Location = new System.Drawing.Point(201, 157);
|
||||
this.RS3.Name = "RS3";
|
||||
this.RS3.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS3.TabIndex = 25;
|
||||
this.toolTip1.SetToolTip(this.RS3, "a 16 bit \'network ID\'. This is used to seed the frequency");
|
||||
//
|
||||
// RS2
|
||||
//
|
||||
this.RS2.FormattingEnabled = true;
|
||||
this.RS2.Items.AddRange(new object[] {
|
||||
"192",
|
||||
"160",
|
||||
"128",
|
||||
"96",
|
||||
"64",
|
||||
"32",
|
||||
"16"});
|
||||
this.RS2.Location = new System.Drawing.Point(201, 130);
|
||||
this.RS2.Name = "RS2";
|
||||
this.RS2.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS2.TabIndex = 24;
|
||||
this.toolTip1.SetToolTip(this.RS2, "the inter-radio data rate in rounded kbps. So 128 means");
|
||||
//
|
||||
// RS1
|
||||
//
|
||||
this.RS1.FormattingEnabled = true;
|
||||
this.RS1.Items.AddRange(new object[] {
|
||||
"115",
|
||||
"111",
|
||||
"57",
|
||||
"38",
|
||||
"19",
|
||||
"9",
|
||||
"4",
|
||||
"2",
|
||||
"1"});
|
||||
this.RS1.Location = new System.Drawing.Point(201, 103);
|
||||
this.RS1.Name = "RS1";
|
||||
this.RS1.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS1.TabIndex = 22;
|
||||
this.toolTip1.SetToolTip(this.RS1, "Serial Baud Rate 57 = 57600");
|
||||
//
|
||||
// RS0
|
||||
//
|
||||
this.RS0.Location = new System.Drawing.Point(201, 77);
|
||||
this.RS0.Name = "RS0";
|
||||
this.RS0.ReadOnly = true;
|
||||
this.RS0.Size = new System.Drawing.Size(80, 20);
|
||||
this.RS0.TabIndex = 23;
|
||||
//
|
||||
// label9
|
||||
//
|
||||
this.label9.AutoSize = true;
|
||||
this.label9.Location = new System.Drawing.Point(108, 9);
|
||||
this.label9.Name = "label9";
|
||||
this.label9.Size = new System.Drawing.Size(33, 13);
|
||||
this.label9.TabIndex = 30;
|
||||
this.label9.Text = "Local";
|
||||
//
|
||||
// label10
|
||||
//
|
||||
this.label10.AutoSize = true;
|
||||
this.label10.Location = new System.Drawing.Point(225, 9);
|
||||
this.label10.Name = "label10";
|
||||
this.label10.Size = new System.Drawing.Size(44, 13);
|
||||
this.label10.TabIndex = 31;
|
||||
this.label10.Text = "Remote";
|
||||
//
|
||||
// RTI
|
||||
//
|
||||
this.RTI.Location = new System.Drawing.Point(201, 25);
|
||||
this.RTI.Name = "RTI";
|
||||
this.RTI.ReadOnly = true;
|
||||
this.RTI.Size = new System.Drawing.Size(80, 20);
|
||||
this.RTI.TabIndex = 33;
|
||||
//
|
||||
// ATI
|
||||
//
|
||||
this.ATI.Location = new System.Drawing.Point(87, 25);
|
||||
this.ATI.Name = "ATI";
|
||||
this.ATI.ReadOnly = true;
|
||||
this.ATI.Size = new System.Drawing.Size(80, 20);
|
||||
this.ATI.TabIndex = 32;
|
||||
//
|
||||
// RSSI
|
||||
//
|
||||
this.RSSI.Location = new System.Drawing.Point(87, 51);
|
||||
this.RSSI.Name = "RSSI";
|
||||
this.RSSI.ReadOnly = true;
|
||||
this.RSSI.Size = new System.Drawing.Size(194, 20);
|
||||
this.RSSI.TabIndex = 34;
|
||||
//
|
||||
// label11
|
||||
//
|
||||
this.label11.AutoSize = true;
|
||||
this.label11.Location = new System.Drawing.Point(15, 32);
|
||||
this.label11.Name = "label11";
|
||||
this.label11.Size = new System.Drawing.Size(42, 13);
|
||||
this.label11.TabIndex = 36;
|
||||
this.label11.Text = "Version";
|
||||
//
|
||||
// label12
|
||||
//
|
||||
this.label12.AutoSize = true;
|
||||
this.label12.Location = new System.Drawing.Point(15, 58);
|
||||
this.label12.Name = "label12";
|
||||
this.label12.Size = new System.Drawing.Size(32, 13);
|
||||
this.label12.TabIndex = 37;
|
||||
this.label12.Text = "RSSI";
|
||||
//
|
||||
// BUT_savesettings
|
||||
//
|
||||
this.BUT_savesettings.Location = new System.Drawing.Point(99, 292);
|
||||
this.BUT_savesettings.Name = "BUT_savesettings";
|
||||
this.BUT_savesettings.Size = new System.Drawing.Size(75, 39);
|
||||
this.BUT_savesettings.TabIndex = 21;
|
||||
this.BUT_savesettings.Text = "Save Settings";
|
||||
this.BUT_savesettings.UseVisualStyleBackColor = true;
|
||||
this.BUT_savesettings.Click += new System.EventHandler(this.BUT_savesettings_Click);
|
||||
//
|
||||
// BUT_getcurrent
|
||||
//
|
||||
this.BUT_getcurrent.Location = new System.Drawing.Point(18, 292);
|
||||
this.BUT_getcurrent.Name = "BUT_getcurrent";
|
||||
this.BUT_getcurrent.Size = new System.Drawing.Size(75, 39);
|
||||
this.BUT_getcurrent.TabIndex = 6;
|
||||
this.BUT_getcurrent.Text = "Load Settings";
|
||||
this.BUT_getcurrent.UseVisualStyleBackColor = true;
|
||||
this.BUT_getcurrent.Click += new System.EventHandler(this.BUT_getcurrent_Click);
|
||||
//
|
||||
// lbl_status
|
||||
//
|
||||
this.lbl_status.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left)
|
||||
| System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.lbl_status.BackColor = System.Drawing.SystemColors.ActiveCaption;
|
||||
this.lbl_status.Location = new System.Drawing.Point(12, 340);
|
||||
this.lbl_status.Name = "lbl_status";
|
||||
this.lbl_status.resize = false;
|
||||
this.lbl_status.Size = new System.Drawing.Size(294, 22);
|
||||
this.lbl_status.TabIndex = 3;
|
||||
//
|
||||
// BUT_upload
|
||||
//
|
||||
this.BUT_upload.Location = new System.Drawing.Point(180, 292);
|
||||
this.BUT_upload.Name = "BUT_upload";
|
||||
this.BUT_upload.Size = new System.Drawing.Size(127, 39);
|
||||
this.BUT_upload.TabIndex = 0;
|
||||
this.BUT_upload.Text = "Upload Firmware (Local)";
|
||||
this.BUT_upload.UseVisualStyleBackColor = true;
|
||||
this.BUT_upload.Click += new System.EventHandler(this.BUT_upload_Click);
|
||||
//
|
||||
// _3DRradio
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.ClientSize = new System.Drawing.Size(318, 416);
|
||||
this.Controls.Add(this.label12);
|
||||
this.Controls.Add(this.label11);
|
||||
this.Controls.Add(this.RSSI);
|
||||
this.Controls.Add(this.RTI);
|
||||
this.Controls.Add(this.ATI);
|
||||
this.Controls.Add(this.label10);
|
||||
this.Controls.Add(this.label9);
|
||||
this.Controls.Add(this.RS7);
|
||||
this.Controls.Add(this.RS6);
|
||||
this.Controls.Add(this.RS5);
|
||||
this.Controls.Add(this.RS4);
|
||||
this.Controls.Add(this.RS3);
|
||||
this.Controls.Add(this.RS2);
|
||||
this.Controls.Add(this.RS0);
|
||||
this.Controls.Add(this.RS1);
|
||||
this.Controls.Add(this.BUT_savesettings);
|
||||
this.Controls.Add(this.label8);
|
||||
this.Controls.Add(this.S7);
|
||||
this.Controls.Add(this.label7);
|
||||
this.Controls.Add(this.S6);
|
||||
this.Controls.Add(this.label6);
|
||||
this.Controls.Add(this.S5);
|
||||
this.Controls.Add(this.label5);
|
||||
this.Controls.Add(this.S4);
|
||||
this.Controls.Add(this.label4);
|
||||
this.Controls.Add(this.S3);
|
||||
this.Controls.Add(this.label3);
|
||||
this.Controls.Add(this.S2);
|
||||
this.Controls.Add(this.label2);
|
||||
this.Controls.Add(this.S0);
|
||||
this.Controls.Add(this.BUT_getcurrent);
|
||||
this.Controls.Add(this.label1);
|
||||
this.Controls.Add(this.S1);
|
||||
this.Controls.Add(this.lbl_status);
|
||||
this.Controls.Add(this.Progressbar);
|
||||
this.Controls.Add(this.BUT_upload);
|
||||
this.MinimumSize = new System.Drawing.Size(334, 454);
|
||||
this.Name = "_3DRradio";
|
||||
this.Text = "3DRradio";
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private MyButton BUT_upload;
|
||||
private System.Windows.Forms.ProgressBar Progressbar;
|
||||
private MyLabel lbl_status;
|
||||
private System.Windows.Forms.ComboBox S1;
|
||||
private System.Windows.Forms.Label label1;
|
||||
private MyButton BUT_getcurrent;
|
||||
private System.Windows.Forms.TextBox S0;
|
||||
private System.Windows.Forms.Label label2;
|
||||
private System.Windows.Forms.Label label3;
|
||||
private System.Windows.Forms.ComboBox S2;
|
||||
private System.Windows.Forms.Label label4;
|
||||
private System.Windows.Forms.ComboBox S3;
|
||||
private System.Windows.Forms.Label label5;
|
||||
private System.Windows.Forms.ComboBox S4;
|
||||
private System.Windows.Forms.Label label6;
|
||||
private System.Windows.Forms.CheckBox S5;
|
||||
private System.Windows.Forms.Label label7;
|
||||
private System.Windows.Forms.CheckBox S6;
|
||||
private System.Windows.Forms.Label label8;
|
||||
private System.Windows.Forms.CheckBox S7;
|
||||
private MyButton BUT_savesettings;
|
||||
private System.Windows.Forms.ToolTip toolTip1;
|
||||
private System.Windows.Forms.CheckBox RS7;
|
||||
private System.Windows.Forms.CheckBox RS6;
|
||||
private System.Windows.Forms.CheckBox RS5;
|
||||
private System.Windows.Forms.ComboBox RS4;
|
||||
private System.Windows.Forms.ComboBox RS3;
|
||||
private System.Windows.Forms.ComboBox RS2;
|
||||
private System.Windows.Forms.TextBox RS0;
|
||||
private System.Windows.Forms.ComboBox RS1;
|
||||
private System.Windows.Forms.Label label9;
|
||||
private System.Windows.Forms.Label label10;
|
||||
private System.Windows.Forms.TextBox RTI;
|
||||
private System.Windows.Forms.TextBox ATI;
|
||||
private System.Windows.Forms.TextBox RSSI;
|
||||
private System.Windows.Forms.Label label11;
|
||||
private System.Windows.Forms.Label label12;
|
||||
}
|
||||
}
|
522
Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs
Normal file
522
Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs
Normal file
@ -0,0 +1,522 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Data;
|
||||
using System.Drawing;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using System.Net;
|
||||
using System.IO;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public partial class _3DRradio : Form
|
||||
{
|
||||
public delegate void LogEventHandler(string message, int level = 0);
|
||||
|
||||
public delegate void ProgressEventHandler(double completed);
|
||||
|
||||
string firmwarefile = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "radio.hm_trp.hex";
|
||||
|
||||
public _3DRradio()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
bool getFirmware()
|
||||
{
|
||||
//https://raw.github.com/tridge/SiK/master/Firmware/dst/radio.hm_trp.hex
|
||||
|
||||
return Common.getFilefromNet("https://raw.github.com/tridge/SiK/master/Firmware/dst/radio.hm_trp.hex", firmwarefile);
|
||||
}
|
||||
|
||||
void Sleep(int mstimeout)
|
||||
{
|
||||
DateTime endtime = DateTime.Now.AddMilliseconds(mstimeout);
|
||||
|
||||
while (DateTime.Now < endtime)
|
||||
{
|
||||
System.Threading.Thread.Sleep(1);
|
||||
Application.DoEvents();
|
||||
}
|
||||
}
|
||||
|
||||
private void BUT_upload_Click(object sender, EventArgs e)
|
||||
{
|
||||
ArduinoSTK comPort = new ArduinoSTK();
|
||||
|
||||
string version = "";
|
||||
|
||||
uploader.Uploader uploader = new uploader.Uploader();
|
||||
|
||||
comPort.PortName = MainV2.comPort.BaseStream.PortName;
|
||||
comPort.BaudRate = 115200;
|
||||
|
||||
comPort.Open();
|
||||
|
||||
bool bootloadermode = false;
|
||||
|
||||
try
|
||||
{
|
||||
uploader_ProgressEvent(0);
|
||||
uploader_LogEvent("Trying Bootloader Mode");
|
||||
uploader.port = comPort;
|
||||
uploader.connect_and_sync();
|
||||
uploader_LogEvent("In Bootloader Mode");
|
||||
bootloadermode = true;
|
||||
}
|
||||
catch { uploader_LogEvent("Trying Firmware Mode"); bootloadermode = false; }
|
||||
|
||||
uploader.ProgressEvent += new ProgressEventHandler(uploader_ProgressEvent);
|
||||
uploader.LogEvent += new LogEventHandler(uploader_LogEvent);
|
||||
|
||||
if (!bootloadermode)
|
||||
{
|
||||
comPort.BaudRate = 57600;
|
||||
// clear buffer
|
||||
comPort.DiscardInBuffer();
|
||||
// setup a known enviroment
|
||||
comPort.Write("\r\n");
|
||||
// wait
|
||||
Sleep(1000);
|
||||
// send config string
|
||||
comPort.Write("+++");
|
||||
// wait
|
||||
Sleep(1100);
|
||||
// check for config responce "OK"
|
||||
if (comPort.ReadExisting().Contains("OK"))
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
comPort.Write("\r\nATI\r\n");
|
||||
|
||||
Sleep(100);
|
||||
|
||||
version = comPort.ReadExisting();
|
||||
}
|
||||
|
||||
|
||||
if (version.Contains("on HM-TRP") || bootloadermode)
|
||||
{
|
||||
if (getFirmware())
|
||||
{
|
||||
uploader.IHex iHex = new uploader.IHex();
|
||||
|
||||
iHex.LogEvent += new LogEventHandler(iHex_LogEvent);
|
||||
|
||||
iHex.ProgressEvent += new ProgressEventHandler(iHex_ProgressEvent);
|
||||
|
||||
try
|
||||
{
|
||||
iHex.load(firmwarefile);
|
||||
}
|
||||
catch { MessageBox.Show("Bad Firmware File"); goto exit; }
|
||||
|
||||
if (!bootloadermode)
|
||||
{
|
||||
|
||||
comPort.Write("AT&UPDATE\r\n");
|
||||
string left = comPort.ReadExisting();
|
||||
Console.WriteLine(left);
|
||||
Sleep(700);
|
||||
comPort.BaudRate = 115200;
|
||||
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
uploader.upload(comPort, iHex);
|
||||
}
|
||||
catch (Exception ex) { MessageBox.Show("Upload Failed " + ex.Message); goto exit; }
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Failed to download new firmware");
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Failed to identify Radio");
|
||||
}
|
||||
|
||||
exit:
|
||||
if (comPort.IsOpen)
|
||||
comPort.Close();
|
||||
}
|
||||
|
||||
void iHex_ProgressEvent(double completed)
|
||||
{
|
||||
try
|
||||
{
|
||||
Progressbar.Value = (int)(completed * 100);
|
||||
Application.DoEvents();
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
void uploader_LogEvent(string message, int level = 0)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (level == 0)
|
||||
{
|
||||
Console.Write(message);
|
||||
lbl_status.Text = message;
|
||||
Application.DoEvents();
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
void iHex_LogEvent(string message, int level = 0)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (level == 0)
|
||||
{
|
||||
lbl_status.Text = message;
|
||||
Console.WriteLine(message);
|
||||
Application.DoEvents();
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
void uploader_ProgressEvent(double completed)
|
||||
{
|
||||
try
|
||||
{
|
||||
Progressbar.Value = (int)(completed * 100);
|
||||
Application.DoEvents();
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
private void BUT_getcurrent_Click(object sender, EventArgs e)
|
||||
{
|
||||
SerialPort comPort = new SerialPort();
|
||||
|
||||
comPort.PortName = MainV2.comPort.BaseStream.PortName;
|
||||
comPort.BaudRate = 57600;
|
||||
|
||||
comPort.ReadTimeout = 4000;
|
||||
|
||||
comPort.Open();
|
||||
|
||||
lbl_status.Text = "Connecting";
|
||||
|
||||
if (doConnect(comPort))
|
||||
{
|
||||
comPort.DiscardInBuffer();
|
||||
|
||||
lbl_status.Text = "Doing Command ATI & RTI";
|
||||
|
||||
ATI.Text = doCommand(comPort, "ATI1");
|
||||
|
||||
RTI.Text = doCommand(comPort, "RTI1");
|
||||
|
||||
RSSI.Text = doCommand(comPort, "ATI7");
|
||||
|
||||
lbl_status.Text = "Doing Command ATI5";
|
||||
|
||||
string answer = doCommand(comPort, "ATI5");
|
||||
|
||||
Console.Write("Local\n" + answer);
|
||||
|
||||
string[] items = answer.Split('\n');
|
||||
|
||||
foreach (string item in items)
|
||||
{
|
||||
if (item.StartsWith("S"))
|
||||
{
|
||||
string[] values = item.Split(':', '=');
|
||||
|
||||
if (values.Length == 3)
|
||||
{
|
||||
Control[] controls = this.Controls.Find(values[0].Trim(), false);
|
||||
|
||||
if (controls.Length > 0)
|
||||
{
|
||||
if (controls[0].GetType() == typeof(CheckBox))
|
||||
{
|
||||
((CheckBox)controls[0]).Checked = values[2].Trim() == "1";
|
||||
}
|
||||
else
|
||||
{
|
||||
controls[0].Text = values[2].Trim();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// remote
|
||||
|
||||
comPort.DiscardInBuffer();
|
||||
|
||||
lbl_status.Text = "Doing Command RTI5";
|
||||
|
||||
answer = doCommand(comPort, "RTI5");
|
||||
|
||||
Console.Write("Remote\n" + answer);
|
||||
|
||||
items = answer.Split('\n');
|
||||
|
||||
foreach (string item in items)
|
||||
{
|
||||
if (item.StartsWith("S"))
|
||||
{
|
||||
string[] values = item.Split(':', '=');
|
||||
|
||||
if (values.Length == 3)
|
||||
{
|
||||
Control[] controls = this.Controls.Find("R"+values[0].Trim(), false);
|
||||
|
||||
if (controls[0].GetType() == typeof(CheckBox))
|
||||
{
|
||||
((CheckBox)controls[0]).Checked = values[2].Trim() == "1";
|
||||
}
|
||||
else
|
||||
{
|
||||
controls[0].Text = values[2].Trim();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
lbl_status.Text = "Done";
|
||||
}
|
||||
else
|
||||
{
|
||||
lbl_status.Text = "Fail";
|
||||
MessageBox.Show("Failed to enter command mode");
|
||||
}
|
||||
|
||||
comPort.WriteLine("ATZ");
|
||||
|
||||
comPort.Close();
|
||||
|
||||
}
|
||||
|
||||
string doCommand(SerialPort comPort, string cmd)
|
||||
{
|
||||
Sleep(100);
|
||||
comPort.DiscardInBuffer();
|
||||
comPort.Write(cmd + "\r\n");
|
||||
string temp = comPort.ReadLine(); // echo
|
||||
Sleep(500);
|
||||
string ans = "";
|
||||
while (comPort.BytesToRead > 0)
|
||||
{
|
||||
ans = ans + comPort.ReadLine() + "\n";
|
||||
Sleep(50);
|
||||
|
||||
if (ans.Length > 500)
|
||||
return "";
|
||||
}
|
||||
|
||||
return ans;
|
||||
}
|
||||
|
||||
bool doConnect(SerialPort comPort)
|
||||
{
|
||||
// clear buffer
|
||||
comPort.DiscardOutBuffer();
|
||||
comPort.DiscardInBuffer();
|
||||
// setup a known enviroment
|
||||
comPort.Write("\r\n");
|
||||
// wait
|
||||
Sleep(1100);
|
||||
// send config string
|
||||
comPort.Write("+++");
|
||||
// wait
|
||||
Sleep(1100);
|
||||
// check for config responce "OK"
|
||||
if (comPort.ReadExisting().Contains("OK"))
|
||||
{
|
||||
//return true;
|
||||
}
|
||||
else
|
||||
{
|
||||
// cleanup incase we are already in cmd mode
|
||||
comPort.Write("\r\n");
|
||||
}
|
||||
|
||||
string version = doCommand(comPort, "ATI");
|
||||
|
||||
Console.Write("Connect Version: "+version);
|
||||
|
||||
if (version.Contains("on HM-TRP"))
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
private void BUT_savesettings_Click(object sender, EventArgs e)
|
||||
{
|
||||
SerialPort comPort = new SerialPort();
|
||||
|
||||
comPort.PortName = MainV2.comPort.BaseStream.PortName;
|
||||
comPort.BaudRate = 57600;
|
||||
|
||||
comPort.ReadTimeout = 4000;
|
||||
|
||||
comPort.Open();
|
||||
|
||||
lbl_status.Text = "Connecting";
|
||||
|
||||
if (doConnect(comPort))
|
||||
{
|
||||
comPort.DiscardInBuffer();
|
||||
|
||||
lbl_status.Text = "Doing Command";
|
||||
|
||||
// remote
|
||||
string answer = doCommand(comPort, "RTI5");
|
||||
|
||||
Console.Write("Remote\n"+answer);
|
||||
|
||||
string[] items = answer.Split('\n');
|
||||
|
||||
foreach (string item in items)
|
||||
{
|
||||
if (item.StartsWith("S"))
|
||||
{
|
||||
string[] values = item.Split(':', '=');
|
||||
|
||||
if (values.Length == 3)
|
||||
{
|
||||
Control[] controls = this.Controls.Find("R"+values[0].Trim(), false);
|
||||
|
||||
if (controls.Length > 0)
|
||||
{
|
||||
if (controls[0].GetType() == typeof(CheckBox))
|
||||
{
|
||||
string value = ((CheckBox)controls[0]).Checked ? "1" : "0";
|
||||
|
||||
if (value != values[2].Trim())
|
||||
{
|
||||
string cmdanswer = doCommand(comPort, "RT" + values[0].Trim() + "=" + value + "\r");
|
||||
|
||||
if (cmdanswer.Contains("OK"))
|
||||
{
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Set Command error");
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (controls[0].Text != values[2].Trim())
|
||||
{
|
||||
string cmdanswer = doCommand(comPort, "RT" + values[0].Trim() + "=" + controls[0].Text + "\r");
|
||||
|
||||
if (cmdanswer.Contains("OK"))
|
||||
{
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Set Command error");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// write it
|
||||
doCommand(comPort, "RT&W");
|
||||
|
||||
// return to normal mode
|
||||
comPort.WriteLine("RTZ");
|
||||
|
||||
comPort.Write("\r\n");
|
||||
|
||||
Sleep(100);
|
||||
|
||||
comPort.DiscardInBuffer();
|
||||
//local
|
||||
answer = doCommand(comPort, "ATI5");
|
||||
|
||||
Console.Write("Local\n" + answer);
|
||||
|
||||
items = answer.Split('\n');
|
||||
|
||||
foreach (string item in items)
|
||||
{
|
||||
if (item.StartsWith("S"))
|
||||
{
|
||||
string[] values = item.Split(':', '=');
|
||||
|
||||
if (values.Length == 3)
|
||||
{
|
||||
Control[] controls = this.Controls.Find(values[0].Trim(), false);
|
||||
|
||||
if (controls.Length > 0)
|
||||
{
|
||||
if (controls[0].GetType() == typeof(CheckBox))
|
||||
{
|
||||
string value = ((CheckBox)controls[0]).Checked ? "1" : "0";
|
||||
|
||||
if (value != values[2].Trim())
|
||||
{
|
||||
string cmdanswer = doCommand(comPort, "AT" + values[0].Trim() + "=" + value + "\r");
|
||||
|
||||
if (cmdanswer.Contains("OK"))
|
||||
{
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Set Command error");
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (controls[0].Text != values[2].Trim())
|
||||
{
|
||||
string cmdanswer = doCommand(comPort, "AT" + values[0].Trim() + "=" + controls[0].Text + "\r");
|
||||
|
||||
if (cmdanswer.Contains("OK"))
|
||||
{
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Set Command error");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// write it
|
||||
doCommand(comPort, "AT&W");
|
||||
|
||||
lbl_status.Text = "Done";
|
||||
}
|
||||
else
|
||||
{
|
||||
lbl_status.Text = "Fail";
|
||||
MessageBox.Show("Failed to enter command mode");
|
||||
}
|
||||
|
||||
// return to normal mode
|
||||
comPort.WriteLine("ATZ");
|
||||
|
||||
comPort.Close();
|
||||
}
|
||||
}
|
||||
}
|
123
Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx
Normal file
123
Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx
Normal file
@ -0,0 +1,123 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
</root>
|
147
Tools/ArdupilotMegaPlanner/Radio/IHex.cs
Normal file
147
Tools/ArdupilotMegaPlanner/Radio/IHex.cs
Normal file
@ -0,0 +1,147 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.IO;
|
||||
|
||||
namespace uploader
|
||||
{
|
||||
public class IHex : SortedList<UInt32, byte[]>
|
||||
{
|
||||
public event ArdupilotMega._3DRradio.LogEventHandler LogEvent;
|
||||
|
||||
public event ArdupilotMega._3DRradio.ProgressEventHandler ProgressEvent;
|
||||
|
||||
private SortedList<UInt32, UInt32> merge_index;
|
||||
|
||||
public IHex ()
|
||||
{
|
||||
merge_index = new SortedList<UInt32, UInt32> ();
|
||||
}
|
||||
|
||||
public void load (string fromPath)
|
||||
{
|
||||
StreamReader sr = new StreamReader (fromPath);
|
||||
UInt32 loadedSize = 0;
|
||||
|
||||
// discard anything we might previous have loaded
|
||||
Clear ();
|
||||
merge_index.Clear ();
|
||||
|
||||
log (string.Format ("reading from {0}\n", Path.GetFileName(fromPath)));
|
||||
|
||||
while (!sr.EndOfStream) {
|
||||
string line = sr.ReadLine ();
|
||||
|
||||
// every line must start with a :
|
||||
if (!line.StartsWith (":"))
|
||||
throw new Exception ("invalid IntelHex file");
|
||||
|
||||
if (ProgressEvent != null)
|
||||
ProgressEvent(sr.BaseStream.Position / (double)sr.BaseStream.Length);
|
||||
|
||||
// parse the record type and data length, assume ihex8
|
||||
// ignore the checksum
|
||||
byte length = Convert.ToByte (line.Substring (1, 2), 16);
|
||||
UInt32 address = Convert.ToUInt32 (line.Substring (3, 4), 16);
|
||||
byte rtype = Convert.ToByte (line.Substring (7, 2), 16);
|
||||
|
||||
// handle type zero (data) records
|
||||
if (rtype == 0) {
|
||||
byte[] b = new byte[length];
|
||||
string hexbytes = line.Substring (9, length * 2);
|
||||
|
||||
// convert hex bytes
|
||||
for (int i = 0; i < length; i++) {
|
||||
b [i] = Convert.ToByte (hexbytes.Substring (i * 2, 2), 16);
|
||||
}
|
||||
|
||||
log (string.Format ("ihex: 0x{0:X}: {1}\n", address, length), 1);
|
||||
loadedSize += length;
|
||||
|
||||
// and add to the list of ranges
|
||||
insert (address, b);
|
||||
}
|
||||
}
|
||||
if (Count < 1)
|
||||
throw new Exception ("no data in IntelHex file");
|
||||
log (string.Format ("read {0} bytes from {1}\n", loadedSize, fromPath));
|
||||
}
|
||||
|
||||
private void log (string message, int level = 0)
|
||||
{
|
||||
if (LogEvent != null)
|
||||
LogEvent (message, level);
|
||||
}
|
||||
|
||||
private void idx_record (UInt32 start, byte[] data)
|
||||
{
|
||||
UInt32 len = (UInt32)data.GetLength (0);
|
||||
|
||||
merge_index.Add (start + len, start);
|
||||
}
|
||||
|
||||
private void idx_remove (UInt32 start, byte[] data)
|
||||
{
|
||||
UInt32 len = (UInt32)data.GetLength (0);
|
||||
|
||||
merge_index.Remove (start + len);
|
||||
}
|
||||
|
||||
private bool idx_find (UInt32 start, out UInt32 other)
|
||||
{
|
||||
return merge_index.TryGetValue (start, out other);
|
||||
}
|
||||
|
||||
public void insert (UInt32 key, byte[] data)
|
||||
{
|
||||
UInt32 other;
|
||||
byte[] mergedata;
|
||||
|
||||
// value of the key that would come after this one
|
||||
other = key;
|
||||
other += (UInt32)data.GetLength (0);
|
||||
|
||||
// can we merge with the next block
|
||||
if (TryGetValue (other, out mergedata)) {
|
||||
int oldlen = data.GetLength (0);
|
||||
|
||||
// remove the next entry, we are going to merge with it
|
||||
Remove (other);
|
||||
|
||||
// remove its index entry as well
|
||||
idx_remove (other, mergedata);
|
||||
|
||||
log (string.Format ("ihex: merging {0:X}/{1} with next {2:X}/{3}\n",
|
||||
key, data.GetLength (0),
|
||||
other, mergedata.GetLength (0)), 1);
|
||||
|
||||
// resize the data array and append data from the next block
|
||||
Array.Resize (ref data, data.GetLength (0) + mergedata.GetLength (0));
|
||||
Array.Copy (mergedata, 0, data, oldlen, mergedata.GetLength (0));
|
||||
}
|
||||
|
||||
// look up a possible adjacent preceding block in the merge index
|
||||
if (idx_find (key, out other)) {
|
||||
|
||||
mergedata = this [other];
|
||||
int oldlen = mergedata.GetLength (0);
|
||||
Remove (other);
|
||||
idx_remove (other, mergedata);
|
||||
|
||||
log (string.Format ("ihex: merging {0:X}/{1} with prev {2:X}/{3}\n",
|
||||
key, data.GetLength (0),
|
||||
other, mergedata.GetLength (0)), 1);
|
||||
|
||||
Array.Resize (ref mergedata, data.GetLength (0) + mergedata.GetLength (0));
|
||||
Array.Copy (data, 0, mergedata, oldlen, data.GetLength (0));
|
||||
key = other;
|
||||
data = mergedata;
|
||||
}
|
||||
|
||||
// add the merged block
|
||||
Add (key, data);
|
||||
idx_record (key, data);
|
||||
log (string.Format ("ihex: adding {0:X}/{1}\n", key, data.GetLength (0)), 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
441
Tools/ArdupilotMegaPlanner/Radio/Uploader.cs
Normal file
441
Tools/ArdupilotMegaPlanner/Radio/Uploader.cs
Normal file
@ -0,0 +1,441 @@
|
||||
using System;
|
||||
using System.IO.Ports;
|
||||
using System.Collections.Generic;
|
||||
|
||||
namespace uploader
|
||||
{
|
||||
public class Uploader
|
||||
{
|
||||
public event ArdupilotMega._3DRradio.LogEventHandler LogEvent;
|
||||
public event ArdupilotMega._3DRradio.ProgressEventHandler ProgressEvent;
|
||||
|
||||
private int bytes_to_process;
|
||||
private int bytes_processed;
|
||||
public SerialPort port;
|
||||
|
||||
private enum Code : byte
|
||||
{
|
||||
// response codes
|
||||
OK = 0x10,
|
||||
FAILED = 0x11,
|
||||
INSYNC = 0x12,
|
||||
|
||||
// protocol commands
|
||||
EOC = 0x20,
|
||||
GET_SYNC = 0x21,
|
||||
GET_DEVICE = 0x22, // returns DEVICE_ID and FREQ bytes
|
||||
CHIP_ERASE = 0x23,
|
||||
LOAD_ADDRESS = 0x24,
|
||||
PROG_FLASH = 0x25,
|
||||
READ_FLASH = 0x26,
|
||||
PROG_MULTI = 0x27,
|
||||
READ_MULTI = 0x28,
|
||||
REBOOT = 0x30,
|
||||
|
||||
// protocol constants
|
||||
PROG_MULTI_MAX = 64, // maximum number of bytes in a PROG_MULTI command
|
||||
READ_MULTI_MAX = 255, // largest read that can be requested
|
||||
|
||||
// device IDs XXX should come with the firmware image...
|
||||
DEVICE_ID_RF50 = 0x4d,
|
||||
DEVICE_ID_HM_TRP= 0x4e,
|
||||
|
||||
// frequency code bytes XXX should come with the firmware image...
|
||||
FREQ_NONE = 0xf0,
|
||||
FREQ_433 = 0x43,
|
||||
FREQ_470 = 0x47,
|
||||
FREQ_868 = 0x86,
|
||||
FREQ_915 = 0x91,
|
||||
};
|
||||
|
||||
public Uploader ()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// Upload the specified image_data.
|
||||
/// </summary>
|
||||
/// <param name='image_data'>
|
||||
/// Image_data to be uploaded.
|
||||
/// </param>
|
||||
public void upload (SerialPort on_port, IHex image_data)
|
||||
{
|
||||
progress (0);
|
||||
|
||||
port = on_port;
|
||||
|
||||
try {
|
||||
connect_and_sync ();
|
||||
upload_and_verify (image_data);
|
||||
cmdReboot ();
|
||||
} catch (Exception e) {
|
||||
if (port.IsOpen)
|
||||
port.Close ();
|
||||
throw e;
|
||||
}
|
||||
}
|
||||
|
||||
public void connect_and_sync ()
|
||||
{
|
||||
// configure the port
|
||||
port.ReadTimeout = 2000; // must be longer than full flash erase time (~1s)
|
||||
|
||||
// synchronise with the bootloader
|
||||
//
|
||||
// The second sync attempt here is mostly laziness, though it does verify that we
|
||||
// can send more than one packet.
|
||||
//
|
||||
for (int i = 0; i < 3; i++) {
|
||||
if (cmdSync ())
|
||||
break;
|
||||
log (string.Format ("sync({0}) failed\n", i), 1);
|
||||
}
|
||||
if (!cmdSync ()) {
|
||||
log ("FAIL: could not synchronise with the bootloader");
|
||||
throw new Exception ("SYNC FAIL");
|
||||
}
|
||||
checkDevice ();
|
||||
|
||||
log ("connected to bootloader\n");
|
||||
}
|
||||
|
||||
private void upload_and_verify (IHex image_data)
|
||||
{
|
||||
|
||||
// erase the program area first
|
||||
log ("erasing program flash\n");
|
||||
cmdErase ();
|
||||
|
||||
// progress fractions
|
||||
bytes_to_process = 0;
|
||||
foreach (byte[] bytes in image_data.Values) {
|
||||
bytes_to_process += bytes.Length;
|
||||
}
|
||||
bytes_to_process *= 2; // once to program, once to verify
|
||||
bytes_processed = 0;
|
||||
|
||||
// program the flash blocks
|
||||
log ("programming\n");
|
||||
foreach (KeyValuePair<UInt32, byte[]> kvp in image_data) {
|
||||
// move the program pointer to the base of this block
|
||||
cmdSetAddress (kvp.Key);
|
||||
log (string.Format ("prog 0x{0:X}/{1}\n", kvp.Key, kvp.Value.Length), 1);
|
||||
|
||||
upload_block_multi (kvp.Value);
|
||||
}
|
||||
|
||||
// and read them back to verify that they were programmed
|
||||
log ("verifying\n");
|
||||
foreach (KeyValuePair<UInt32, byte[]> kvp in image_data) {
|
||||
// move the program pointer to the base of this block
|
||||
cmdSetAddress (kvp.Key);
|
||||
log (string.Format ("verf 0x{0:X}/{1}\n", kvp.Key, kvp.Value.Length), 1);
|
||||
|
||||
verify_block_multi (kvp.Value);
|
||||
bytes_processed += kvp.Value.GetLength (0);
|
||||
progress ((double)bytes_processed / bytes_to_process);
|
||||
}
|
||||
log ("Success\n");
|
||||
}
|
||||
|
||||
private void upload_block (byte[] data)
|
||||
{
|
||||
foreach (byte b in data) {
|
||||
cmdProgram (b);
|
||||
progress ((double)(++bytes_processed) / bytes_to_process);
|
||||
}
|
||||
}
|
||||
|
||||
private void upload_block_multi (byte[] data)
|
||||
{
|
||||
int offset = 0;
|
||||
int to_send;
|
||||
int length = data.GetLength (0);
|
||||
|
||||
// Chunk the block in units of no more than what the bootloader
|
||||
// will program.
|
||||
while (offset < length) {
|
||||
to_send = length - offset;
|
||||
if (to_send > (int)Code.PROG_MULTI_MAX)
|
||||
to_send = (int)Code.PROG_MULTI_MAX;
|
||||
|
||||
log (string.Format ("multi {0}/{1}\n", offset, to_send), 1);
|
||||
cmdProgramMulti (data, offset, to_send);
|
||||
offset += to_send;
|
||||
|
||||
bytes_processed += to_send;
|
||||
progress ((double)bytes_processed / bytes_to_process);
|
||||
}
|
||||
}
|
||||
|
||||
private void verify_block_multi (byte[] data)
|
||||
{
|
||||
int offset = 0;
|
||||
int to_verf;
|
||||
int length = data.GetLength (0);
|
||||
|
||||
// Chunk the block in units of no more than what the bootloader
|
||||
// will read.
|
||||
while (offset < length) {
|
||||
to_verf = length - offset;
|
||||
if (to_verf > (int)Code.READ_MULTI_MAX)
|
||||
to_verf = (int)Code.READ_MULTI_MAX;
|
||||
|
||||
log (string.Format ("multi {0}/{1}\n", offset, to_verf), 1);
|
||||
cmdVerifyMulti (data, offset, to_verf);
|
||||
offset += to_verf;
|
||||
|
||||
bytes_processed += to_verf;
|
||||
progress ((double)bytes_processed / bytes_to_process);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Requests a sync reply.
|
||||
/// </summary>
|
||||
/// <returns>
|
||||
/// True if in sync, false otherwise.
|
||||
/// </returns>
|
||||
private bool cmdSync ()
|
||||
{
|
||||
port.DiscardInBuffer ();
|
||||
|
||||
send (Code.GET_SYNC);
|
||||
send (Code.EOC);
|
||||
|
||||
try {
|
||||
getSync ();
|
||||
} catch {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Erases the device.
|
||||
/// </summary>
|
||||
private void cmdErase ()
|
||||
{
|
||||
send (Code.CHIP_ERASE);
|
||||
send (Code.EOC);
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Set the address for the next program or read operation.
|
||||
/// </summary>
|
||||
/// <param name='address'>
|
||||
/// Address to be set.
|
||||
/// </param>
|
||||
private void cmdSetAddress (UInt32 address)
|
||||
{
|
||||
send (Code.LOAD_ADDRESS);
|
||||
send ((UInt16)address);
|
||||
send (Code.EOC);
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Programs a byte and advances the program address by one.
|
||||
/// </summary>
|
||||
/// <param name='data'>
|
||||
/// Data to program.
|
||||
/// </param>
|
||||
private void cmdProgram (byte data)
|
||||
{
|
||||
send (Code.PROG_FLASH);
|
||||
send (data);
|
||||
send (Code.EOC);
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
private void cmdProgramMulti (byte[] data, int offset, int length)
|
||||
{
|
||||
send (Code.PROG_MULTI);
|
||||
send ((byte)length);
|
||||
for (int i = 0; i < length; i++)
|
||||
send (data [offset + i]);
|
||||
send (Code.EOC);
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Verifies the byte at the current program address.
|
||||
/// </summary>
|
||||
/// <param name='data'>
|
||||
/// Data expected to be found.
|
||||
/// </param>
|
||||
/// <exception cref='VerifyFail'>
|
||||
/// Is thrown when the verify fail.
|
||||
/// </exception>
|
||||
private void cmdVerify (byte data)
|
||||
{
|
||||
send (Code.READ_FLASH);
|
||||
send (Code.EOC);
|
||||
|
||||
if (recv () != data)
|
||||
throw new Exception ("flash verification failed");
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
private void cmdVerifyMulti (byte[] data, int offset, int length)
|
||||
{
|
||||
send (Code.READ_MULTI);
|
||||
send ((byte)length);
|
||||
send (Code.EOC);
|
||||
|
||||
for (int i = 0; i < length; i++) {
|
||||
if (recv () != data [offset + i]) {
|
||||
log ("flash verification failed\n");
|
||||
throw new Exception ("VERIFY FAIL");
|
||||
}
|
||||
}
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
private void cmdReboot ()
|
||||
{
|
||||
send (Code.REBOOT);
|
||||
}
|
||||
|
||||
private void checkDevice ()
|
||||
{
|
||||
Code id, freq;
|
||||
|
||||
send (Code.GET_DEVICE);
|
||||
send (Code.EOC);
|
||||
|
||||
id = (Code)recv ();
|
||||
freq = (Code)recv ();
|
||||
|
||||
// XXX should be getting valid board/frequency data from firmware file
|
||||
if ((id != Code.DEVICE_ID_HM_TRP) && (id != Code.DEVICE_ID_RF50))
|
||||
throw new Exception ("bootloader device ID mismatch");
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Expect the two-byte synchronisation codes within the read timeout.
|
||||
/// </summary>
|
||||
/// <exception cref='NoSync'>
|
||||
/// Is thrown if the wrong bytes are read.
|
||||
/// <exception cref='TimeoutException'>
|
||||
/// Is thrown if the read timeout expires.
|
||||
/// </exception>
|
||||
private void getSync ()
|
||||
{
|
||||
try {
|
||||
Code c;
|
||||
|
||||
c = (Code)recv ();
|
||||
if (c != Code.INSYNC) {
|
||||
log (string.Format ("got {0:X} when expecting {1:X}\n", (int)c, (int)Code.INSYNC), 2);
|
||||
throw new Exception ("BAD SYNC");
|
||||
}
|
||||
c = (Code)recv ();
|
||||
if (c != Code.OK) {
|
||||
log (string.Format ("got {0:X} when expecting {1:X}\n", (int)c, (int)Code.EOC), 2);
|
||||
throw new Exception ("BAD STATUS");
|
||||
}
|
||||
} catch {
|
||||
log ("FAIL: lost synchronisation with the bootloader\n");
|
||||
throw new Exception ("SYNC LOST");
|
||||
}
|
||||
log ("in sync\n", 5);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Send the specified code to the bootloader.
|
||||
/// </summary>
|
||||
/// <param name='code'>
|
||||
/// Code to send.
|
||||
/// </param>
|
||||
private void send (Code code)
|
||||
{
|
||||
byte[] b = new byte[] { (byte)code };
|
||||
|
||||
log ("send ", 5);
|
||||
foreach (byte x in b) {
|
||||
log (string.Format (" {0:X}", x), 5);
|
||||
}
|
||||
log ("\n", 5);
|
||||
|
||||
port.Write (b, 0, 1);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Send the specified byte to the bootloader.
|
||||
/// </summary>
|
||||
/// <param name='data'>
|
||||
/// Data byte to send.
|
||||
/// </param>
|
||||
private void send (byte data)
|
||||
{
|
||||
byte[] b = new byte[] { data };
|
||||
|
||||
log ("send ", 5);
|
||||
foreach (byte x in b) {
|
||||
log (string.Format (" {0:X}", x), 5);
|
||||
}
|
||||
log ("\n", 5);
|
||||
|
||||
port.Write (b, 0, 1);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Send the specified 16-bit value, LSB first.
|
||||
/// </summary>
|
||||
/// <param name='data'>
|
||||
/// Data value to send.
|
||||
/// </param>
|
||||
private void send (UInt16 data)
|
||||
{
|
||||
byte[] b = new byte[2] { (byte)(data & 0xff), (byte)(data >> 8) };
|
||||
|
||||
log ("send ", 5);
|
||||
foreach (byte x in b) {
|
||||
log (string.Format (" {0:X}", x), 5);
|
||||
}
|
||||
log ("\n", 5);
|
||||
|
||||
port.Write (b, 0, 2);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Receive a byte.
|
||||
/// </summary>
|
||||
private byte recv ()
|
||||
{
|
||||
byte b;
|
||||
|
||||
b = (byte)port.ReadByte ();
|
||||
|
||||
log (string.Format ("recv {0:X}\n", b), 5);
|
||||
|
||||
return b;
|
||||
}
|
||||
|
||||
private void log (string message, int level = 0)
|
||||
{
|
||||
if (LogEvent != null)
|
||||
LogEvent (message, level);
|
||||
}
|
||||
|
||||
private void progress (double completed)
|
||||
{
|
||||
if (ProgressEvent != null)
|
||||
ProgressEvent (completed);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -64,7 +64,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
alt = (100 * MainV2.cs.multiplierdist).ToString("0");
|
||||
}
|
||||
if (DialogResult.Cancel == Common.InputBox("Enter Alt", "Enter Alt", ref alt))
|
||||
if (DialogResult.Cancel == Common.InputBox("Enter Alt", "Enter Alt (relative to home alt)", ref alt))
|
||||
return;
|
||||
|
||||
intalt = (int)(100 * MainV2.cs.multiplierdist);
|
||||
|
Binary file not shown.
Loading…
Reference in New Issue
Block a user