APM Planner 1.1.41

fix mono ssl issue
modify log download
fix param dl on arduplane 2.28 (2x nulls in param list)
fix connect cancel
mono - add more comports
more error checking on radio
This commit is contained in:
Michael Oborne 2012-02-24 19:39:02 +08:00
parent ab0e1d7632
commit 06be0d24ba
11 changed files with 387 additions and 200 deletions

View File

@ -12,6 +12,8 @@ using GMap.NET;
using GMap.NET.WindowsForms;
using GMap.NET.WindowsForms.Markers;
using System.Security.Cryptography.X509Certificates;
using System.Net;
using System.Net.Sockets;
using System.Xml; // config file
@ -267,6 +269,15 @@ namespace ArdupilotMega
}
}
class NoCheckCertificatePolicy : ICertificatePolicy
{
public bool CheckValidationResult(ServicePoint srvPoint, X509Certificate certificate, WebRequest request, int certificateProblem)
{
return true;
}
}
public class Common
{
public enum distances
@ -491,9 +502,14 @@ namespace ArdupilotMega
}
#endif
public static bool getFilefromNet(string url,string saveto) {
try
{
// this is for mono to a ssl server
ServicePointManager.CertificatePolicy = new NoCheckCertificatePolicy();
// Create a request using a URL that can receive a post.
WebRequest request = WebRequest.Create(url);
request.Timeout = 5000;
@ -535,7 +551,7 @@ namespace ArdupilotMega
return true;
}
catch { return false; }
catch (Exception ex) { Console.WriteLine("getFilefromNet(): " + ex.ToString()); return false; }
}
public static Type getModes()

View File

@ -83,11 +83,11 @@ namespace ArdupilotMega
threadrun = true;
System.Threading.Thread.Sleep(4000);
System.Threading.Thread.Sleep(2000);
try
{
comPort.Write("\n\n\n\n");
comPort.Write("\n\n\n\n"); // more in "connecting"
}
catch { }
@ -187,8 +187,14 @@ namespace ArdupilotMega
{
case serialstatus.Connecting:
if (line.Contains("reset to FLY") || line.Contains("interactive setup") || line.Contains("CLI:") || line.Contains("Ardu"))
if (line.Contains("ENTER") || line.Contains("GROUND START") || line.Contains("reset to FLY") || line.Contains("interactive setup") || line.Contains("CLI") || line.Contains("Ardu"))
{
try
{
comPort.Write("\n\n\n\n");
}
catch { }
comPort.Write("logs\r");
status = serialstatus.Done;
}
@ -276,7 +282,7 @@ namespace ArdupilotMega
Console.Write(line);
TXT_seriallog.AppendText(line);
TXT_seriallog.AppendText(line.Replace((char)0x0,' '));
// auto scroll
if (TXT_seriallog.TextLength >= 10000)

View File

@ -285,6 +285,14 @@ namespace ArdupilotMega
if (getparams)
getParamListBG();
if (frmProgressReporter.doWorkArgs.CancelAcknowledged == true)
{
MainV2.givecomport = false;
if (BaseStream.IsOpen)
BaseStream.Close();
return;
}
}
catch (Exception e)
{
@ -592,7 +600,7 @@ namespace ArdupilotMega
private Hashtable getParamListBG()
{
MainV2.givecomport = true;
List<int> missed = new List<int>();
List<int> got = new List<int>();
// clear old
param = new Hashtable();
@ -612,7 +620,7 @@ namespace ArdupilotMega
DateTime start = DateTime.Now;
DateTime restart = DateTime.Now;
while (param_count < param_total)
while (got.Count < param_total)
{
if (frmProgressReporter.doWorkArgs.CancelRequested)
@ -634,7 +642,7 @@ namespace ArdupilotMega
continue;
}
MainV2.givecomport = false;
throw new Exception("Timeout on read - getParamList");
throw new Exception("Timeout on read - getParamList " + param_count +" "+ param_total);
}
byte[] buffer = readPacket();
@ -662,7 +670,9 @@ namespace ArdupilotMega
}
// check if we already have it
if (param.ContainsKey(paramID)) {
if (got.Contains(par.param_index))
{
//Console.WriteLine("Already got '"+paramID+"'");
continue;
}
@ -671,10 +681,11 @@ namespace ArdupilotMega
modifyParamForDisplay(true, paramID, ref par.param_value);
param[paramID] = (par.param_value);
param_count++;
got.Add(par.param_index);
// if (Progress != null)
// Progress((param.Count * 100) / param_total, "Got param " + paramID);
this.frmProgressReporter.UpdateProgressAndStatus((param.Count * 100) / param_total, "Got param " + paramID);
this.frmProgressReporter.UpdateProgressAndStatus((got.Count * 100) / param_total, "Got param " + paramID);
}
else
{
@ -685,11 +696,11 @@ namespace ArdupilotMega
}
}
if (param.Count != param_total)
if (got.Count != param_total)
{
if (retrys > 0)
{
this.frmProgressReporter.UpdateProgressAndStatus((param.Count * 100) / param_total, "Getting missed params");
this.frmProgressReporter.UpdateProgressAndStatus((got.Count * 100) / param_total, "Getting missed params");
retrys--;
goto goagain;
}

View File

@ -134,6 +134,7 @@
this.CMB_serialport.Name = "CMB_serialport";
this.CMB_serialport.Size = new System.Drawing.Size(150, 76);
this.CMB_serialport.SelectedIndexChanged += new System.EventHandler(this.CMB_serialport_SelectedIndexChanged);
this.CMB_serialport.Enter += new System.EventHandler(this.CMB_serialport_Enter);
this.CMB_serialport.Click += new System.EventHandler(this.CMB_serialport_Click);
//
// MainMenu

View File

@ -249,10 +249,18 @@ namespace ArdupilotMega
{
string[] devs = new string[0];
Console.WriteLine("Get Comports");
if (MONO)
{
if (Directory.Exists("/dev/"))
{
if (Directory.Exists("/dev/serial/by-id/"))
devs = Directory.GetFiles("/dev/serial/by-id/","*usb*");
devs = Directory.GetFiles("/dev/", "*ACM*");
devs = Directory.GetFiles("/dev/", "ttyUSB*");
}
}
string[] ports = SerialPort.GetPortNames();
@ -2137,5 +2145,10 @@ namespace ArdupilotMega
}
catch (Exception) { }
}
private void CMB_serialport_Enter(object sender, EventArgs e)
{
CMB_serialport_Click(sender, e);
}
}
}

View File

@ -71,7 +71,7 @@ namespace ArdupilotMega
MessageBox.Show("You are missing some DLL's. Please extract the zip file somewhere. OR Use the update feature from the menu");
return;
}
DialogResult dr = MessageBox.Show("An error has occurred\nReport this Error??? "+ex.ToString(), "Send Error", MessageBoxButtons.YesNo);
DialogResult dr = MessageBox.Show("An error has occurred\n"+ex.ToString() + "\n\nReport this Error???", "Send Error", MessageBoxButtons.YesNo);
if (DialogResult.Yes == dr)
{
try

View File

@ -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.41")]
[assembly: AssemblyFileVersion("1.1.42")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -64,15 +64,18 @@
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.lbl_status = new System.Windows.Forms.Label();
this.BUT_upload = new ArdupilotMega.MyButton();
this.BUT_syncS2 = new ArdupilotMega.MyButton();
this.BUT_syncS3 = new ArdupilotMega.MyButton();
this.BUT_syncS5 = 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.Location = new System.Drawing.Point(12, 402);
this.Progressbar.Name = "Progressbar";
this.Progressbar.Size = new System.Drawing.Size(294, 36);
this.Progressbar.TabIndex = 2;
@ -90,7 +93,7 @@
"4",
"2",
"1"});
this.S1.Location = new System.Drawing.Point(87, 103);
this.S1.Location = new System.Drawing.Point(87, 141);
this.S1.Name = "S1";
this.S1.Size = new System.Drawing.Size(80, 21);
this.S1.TabIndex = 4;
@ -99,7 +102,7 @@
// label1
//
this.label1.AutoSize = true;
this.label1.Location = new System.Drawing.Point(15, 111);
this.label1.Location = new System.Drawing.Point(15, 149);
this.label1.Name = "label1";
this.label1.Size = new System.Drawing.Size(32, 13);
this.label1.TabIndex = 5;
@ -107,7 +110,7 @@
//
// S0
//
this.S0.Location = new System.Drawing.Point(87, 77);
this.S0.Location = new System.Drawing.Point(87, 115);
this.S0.Name = "S0";
this.S0.ReadOnly = true;
this.S0.Size = new System.Drawing.Size(80, 20);
@ -116,7 +119,7 @@
// label2
//
this.label2.AutoSize = true;
this.label2.Location = new System.Drawing.Point(15, 84);
this.label2.Location = new System.Drawing.Point(15, 122);
this.label2.Name = "label2";
this.label2.Size = new System.Drawing.Size(39, 13);
this.label2.TabIndex = 8;
@ -125,7 +128,7 @@
// label3
//
this.label3.AutoSize = true;
this.label3.Location = new System.Drawing.Point(15, 138);
this.label3.Location = new System.Drawing.Point(15, 176);
this.label3.Name = "label3";
this.label3.Size = new System.Drawing.Size(53, 13);
this.label3.TabIndex = 10;
@ -142,7 +145,7 @@
"64",
"32",
"16"});
this.S2.Location = new System.Drawing.Point(87, 130);
this.S2.Location = new System.Drawing.Point(87, 168);
this.S2.Name = "S2";
this.S2.Size = new System.Drawing.Size(80, 21);
this.S2.TabIndex = 9;
@ -151,7 +154,7 @@
// label4
//
this.label4.AutoSize = true;
this.label4.Location = new System.Drawing.Point(15, 165);
this.label4.Location = new System.Drawing.Point(15, 203);
this.label4.Name = "label4";
this.label4.Size = new System.Drawing.Size(38, 13);
this.label4.TabIndex = 12;
@ -191,7 +194,7 @@
"28",
"29",
"30"});
this.S3.Location = new System.Drawing.Point(87, 157);
this.S3.Location = new System.Drawing.Point(87, 195);
this.S3.Name = "S3";
this.S3.Size = new System.Drawing.Size(80, 21);
this.S3.TabIndex = 11;
@ -200,7 +203,7 @@
// label5
//
this.label5.AutoSize = true;
this.label5.Location = new System.Drawing.Point(15, 192);
this.label5.Location = new System.Drawing.Point(15, 230);
this.label5.Name = "label5";
this.label5.Size = new System.Drawing.Size(52, 13);
this.label5.TabIndex = 14;
@ -231,7 +234,7 @@
"18",
"19",
"20"});
this.S4.Location = new System.Drawing.Point(87, 184);
this.S4.Location = new System.Drawing.Point(87, 222);
this.S4.Name = "S4";
this.S4.Size = new System.Drawing.Size(80, 21);
this.S4.TabIndex = 13;
@ -240,7 +243,7 @@
// label6
//
this.label6.AutoSize = true;
this.label6.Location = new System.Drawing.Point(15, 219);
this.label6.Location = new System.Drawing.Point(15, 257);
this.label6.Name = "label6";
this.label6.Size = new System.Drawing.Size(28, 13);
this.label6.TabIndex = 16;
@ -248,7 +251,7 @@
//
// S5
//
this.S5.Location = new System.Drawing.Point(87, 211);
this.S5.Location = new System.Drawing.Point(87, 249);
this.S5.Name = "S5";
this.S5.Size = new System.Drawing.Size(80, 21);
this.S5.TabIndex = 15;
@ -257,7 +260,7 @@
// label7
//
this.label7.AutoSize = true;
this.label7.Location = new System.Drawing.Point(15, 246);
this.label7.Location = new System.Drawing.Point(15, 284);
this.label7.Name = "label7";
this.label7.Size = new System.Drawing.Size(44, 13);
this.label7.TabIndex = 18;
@ -265,7 +268,7 @@
//
// S6
//
this.S6.Location = new System.Drawing.Point(87, 238);
this.S6.Location = new System.Drawing.Point(87, 276);
this.S6.Name = "S6";
this.S6.Size = new System.Drawing.Size(80, 21);
this.S6.TabIndex = 17;
@ -274,7 +277,7 @@
// label8
//
this.label8.AutoSize = true;
this.label8.Location = new System.Drawing.Point(15, 273);
this.label8.Location = new System.Drawing.Point(15, 311);
this.label8.Name = "label8";
this.label8.Size = new System.Drawing.Size(68, 13);
this.label8.TabIndex = 20;
@ -282,7 +285,7 @@
//
// S7
//
this.S7.Location = new System.Drawing.Point(87, 265);
this.S7.Location = new System.Drawing.Point(87, 303);
this.S7.Name = "S7";
this.S7.Size = new System.Drawing.Size(80, 21);
this.S7.TabIndex = 19;
@ -290,7 +293,7 @@
//
// RS7
//
this.RS7.Location = new System.Drawing.Point(201, 265);
this.RS7.Location = new System.Drawing.Point(201, 303);
this.RS7.Name = "RS7";
this.RS7.Size = new System.Drawing.Size(80, 21);
this.RS7.TabIndex = 29;
@ -298,7 +301,7 @@
//
// RS6
//
this.RS6.Location = new System.Drawing.Point(201, 238);
this.RS6.Location = new System.Drawing.Point(201, 276);
this.RS6.Name = "RS6";
this.RS6.Size = new System.Drawing.Size(80, 21);
this.RS6.TabIndex = 28;
@ -306,7 +309,7 @@
//
// RS5
//
this.RS5.Location = new System.Drawing.Point(201, 211);
this.RS5.Location = new System.Drawing.Point(201, 249);
this.RS5.Name = "RS5";
this.RS5.Size = new System.Drawing.Size(80, 21);
this.RS5.TabIndex = 27;
@ -337,7 +340,7 @@
"18",
"19",
"20"});
this.RS4.Location = new System.Drawing.Point(201, 184);
this.RS4.Location = new System.Drawing.Point(201, 222);
this.RS4.Name = "RS4";
this.RS4.Size = new System.Drawing.Size(80, 21);
this.RS4.TabIndex = 26;
@ -377,7 +380,7 @@
"28",
"29",
"30"});
this.RS3.Location = new System.Drawing.Point(201, 157);
this.RS3.Location = new System.Drawing.Point(201, 195);
this.RS3.Name = "RS3";
this.RS3.Size = new System.Drawing.Size(80, 21);
this.RS3.TabIndex = 25;
@ -394,7 +397,7 @@
"64",
"32",
"16"});
this.RS2.Location = new System.Drawing.Point(201, 130);
this.RS2.Location = new System.Drawing.Point(201, 168);
this.RS2.Name = "RS2";
this.RS2.Size = new System.Drawing.Size(80, 21);
this.RS2.TabIndex = 24;
@ -413,7 +416,7 @@
"4",
"2",
"1"});
this.RS1.Location = new System.Drawing.Point(201, 103);
this.RS1.Location = new System.Drawing.Point(201, 141);
this.RS1.Name = "RS1";
this.RS1.Size = new System.Drawing.Size(80, 21);
this.RS1.TabIndex = 22;
@ -421,7 +424,7 @@
//
// RS0
//
this.RS0.Location = new System.Drawing.Point(201, 77);
this.RS0.Location = new System.Drawing.Point(201, 115);
this.RS0.Name = "RS0";
this.RS0.ReadOnly = true;
this.RS0.Size = new System.Drawing.Size(80, 20);
@ -464,9 +467,10 @@
// RSSI
//
this.RSSI.Location = new System.Drawing.Point(87, 51);
this.RSSI.Multiline = true;
this.RSSI.Name = "RSSI";
this.RSSI.ReadOnly = true;
this.RSSI.Size = new System.Drawing.Size(194, 20);
this.RSSI.Size = new System.Drawing.Size(194, 58);
this.RSSI.TabIndex = 34;
//
// label11
@ -489,7 +493,7 @@
//
// BUT_savesettings
//
this.BUT_savesettings.Location = new System.Drawing.Point(99, 292);
this.BUT_savesettings.Location = new System.Drawing.Point(99, 330);
this.BUT_savesettings.Name = "BUT_savesettings";
this.BUT_savesettings.Size = new System.Drawing.Size(75, 39);
this.BUT_savesettings.TabIndex = 21;
@ -499,7 +503,7 @@
//
// BUT_getcurrent
//
this.BUT_getcurrent.Location = new System.Drawing.Point(18, 292);
this.BUT_getcurrent.Location = new System.Drawing.Point(18, 330);
this.BUT_getcurrent.Name = "BUT_getcurrent";
this.BUT_getcurrent.Size = new System.Drawing.Size(75, 39);
this.BUT_getcurrent.TabIndex = 6;
@ -511,16 +515,15 @@
//
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.BackColor = System.Drawing.Color.Transparent;
this.lbl_status.Location = new System.Drawing.Point(12, 374);
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.Location = new System.Drawing.Point(180, 330);
this.BUT_upload.Name = "BUT_upload";
this.BUT_upload.Size = new System.Drawing.Size(127, 39);
this.BUT_upload.TabIndex = 0;
@ -528,11 +531,44 @@
this.BUT_upload.UseVisualStyleBackColor = true;
this.BUT_upload.Click += new System.EventHandler(this.BUT_upload_Click);
//
// BUT_syncS2
//
this.BUT_syncS2.Location = new System.Drawing.Point(173, 168);
this.BUT_syncS2.Name = "BUT_syncS2";
this.BUT_syncS2.Size = new System.Drawing.Size(22, 23);
this.BUT_syncS2.TabIndex = 38;
this.BUT_syncS2.Text = ">";
this.BUT_syncS2.UseVisualStyleBackColor = true;
this.BUT_syncS2.Click += new System.EventHandler(this.BUT_syncS2_Click);
//
// BUT_syncS3
//
this.BUT_syncS3.Location = new System.Drawing.Point(173, 195);
this.BUT_syncS3.Name = "BUT_syncS3";
this.BUT_syncS3.Size = new System.Drawing.Size(22, 23);
this.BUT_syncS3.TabIndex = 39;
this.BUT_syncS3.Text = ">";
this.BUT_syncS3.UseVisualStyleBackColor = true;
this.BUT_syncS3.Click += new System.EventHandler(this.BUT_syncS3_Click);
//
// BUT_syncS5
//
this.BUT_syncS5.Location = new System.Drawing.Point(173, 247);
this.BUT_syncS5.Name = "BUT_syncS5";
this.BUT_syncS5.Size = new System.Drawing.Size(22, 23);
this.BUT_syncS5.TabIndex = 40;
this.BUT_syncS5.Text = ">";
this.BUT_syncS5.UseVisualStyleBackColor = true;
this.BUT_syncS5.Click += new System.EventHandler(this.BUT_syncS5_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.ClientSize = new System.Drawing.Size(318, 444);
this.Controls.Add(this.BUT_syncS5);
this.Controls.Add(this.BUT_syncS3);
this.Controls.Add(this.BUT_syncS2);
this.Controls.Add(this.label12);
this.Controls.Add(this.label11);
this.Controls.Add(this.RSSI);
@ -569,7 +605,9 @@
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.MaximizeBox = false;
this.MinimizeBox = false;
this.MinimumSize = new System.Drawing.Size(334, 482);
this.Name = "_3DRradio";
this.Text = "3DRradio";
this.ResumeLayout(false);
@ -581,7 +619,7 @@
private MyButton BUT_upload;
private System.Windows.Forms.ProgressBar Progressbar;
private MyLabel lbl_status;
private System.Windows.Forms.Label lbl_status;
private System.Windows.Forms.ComboBox S1;
private System.Windows.Forms.Label label1;
private MyButton BUT_getcurrent;
@ -616,5 +654,8 @@
private System.Windows.Forms.TextBox RSSI;
private System.Windows.Forms.Label label11;
private System.Windows.Forms.Label label12;
private MyButton BUT_syncS2;
private MyButton BUT_syncS3;
private MyButton BUT_syncS5;
}
}

View File

@ -22,6 +22,9 @@ namespace ArdupilotMega
public _3DRradio()
{
InitializeComponent();
S3.DataSource = Enumerable.Range(0, 500).ToArray();
RS3.DataSource = S3.DataSource;
}
bool getFirmware()
@ -50,13 +53,21 @@ namespace ArdupilotMega
uploader.Uploader uploader = new uploader.Uploader();
try
{
comPort.PortName = MainV2.comPort.BaseStream.PortName;
comPort.BaudRate = 115200;
comPort.Open();
}
catch { MessageBox.Show("Invalid ComPort or in use"); return; }
bool bootloadermode = false;
uploader.ProgressEvent += new ProgressEventHandler(uploader_ProgressEvent);
uploader.LogEvent += new LogEventHandler(uploader_LogEvent);
try
{
uploader_ProgressEvent(0);
@ -66,39 +77,17 @@ namespace ArdupilotMega
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();
catch {
comPort.Close();
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
comPort.Open();
uploader_LogEvent("Trying Firmware Mode");
bootloadermode = false;
}
if (version.Contains("on HM-TRP") || bootloadermode)
if (bootloadermode || doConnect(comPort))
{
if (getFirmware())
{
@ -116,20 +105,22 @@ namespace ArdupilotMega
if (!bootloadermode)
{
try
{
comPort.Write("AT&UPDATE\r\n");
string left = comPort.ReadExisting();
Console.WriteLine(left);
Sleep(700);
comPort.BaudRate = 115200;
}
catch { }
}
try
{
uploader.upload(comPort, iHex);
}
catch (Exception ex) { MessageBox.Show("Upload Failed " + ex.Message); goto exit; }
catch (Exception ex) { MessageBox.Show("Upload Failed " + ex.Message); }
}
else
{
@ -144,6 +135,7 @@ namespace ArdupilotMega
exit:
if (comPort.IsOpen)
comPort.Close();
}
void iHex_ProgressEvent(double completed)
@ -198,13 +190,19 @@ namespace ArdupilotMega
{
SerialPort comPort = new SerialPort();
try {
comPort.PortName = MainV2.comPort.BaseStream.PortName;
comPort.BaudRate = 57600;
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
comPort.ReadTimeout = 4000;
comPort.Open();
}
catch { MessageBox.Show("Invalid ComPort or in use"); return; }
lbl_status.Text = "Connecting";
if (doConnect(comPort))
@ -213,18 +211,16 @@ namespace ArdupilotMega
lbl_status.Text = "Doing Command ATI & RTI";
ATI.Text = doCommand(comPort, "ATI1");
ATI.Text = doCommand(comPort, "ATI1").Trim();
RTI.Text = doCommand(comPort, "RTI1");
RTI.Text = doCommand(comPort, "RTI1").Trim();
RSSI.Text = doCommand(comPort, "ATI7");
RSSI.Text = doCommand(comPort, "ATI7").Trim();
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)
@ -253,6 +249,12 @@ namespace ArdupilotMega
}
// remote
foreach (Control ctl in this.Controls)
{
if (ctl.Name.StartsWith("RS") && ctl.Name != "RSSI")
ctl.ResetText();
}
comPort.DiscardInBuffer();
@ -260,8 +262,6 @@ namespace ArdupilotMega
answer = doCommand(comPort, "RTI5");
Console.Write("Remote\n" + answer);
items = answer.Split('\n');
foreach (string item in items)
@ -272,50 +272,113 @@ namespace ArdupilotMega
if (values.Length == 3)
{
Control[] controls = this.Controls.Find("R"+values[0].Trim(), false);
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 if (controls[0].GetType() == typeof(TextBox))
{
((TextBox)controls[0]).Text = values[2].Trim();
}
else if (controls[0].GetType() == typeof(ComboBox))
{
((ComboBox)controls[0]).SelectedText = values[2].Trim();
}
}
else
{
controls[0].Text = values[2].Trim();
}
Console.WriteLine("Odd config line :" + item);
}
}
}
// off hook
doCommand(comPort, "ATO");
lbl_status.Text = "Done";
}
else
{
// off hook
doCommand(comPort, "ATO");
lbl_status.Text = "Fail";
MessageBox.Show("Failed to enter command mode");
}
comPort.WriteLine("ATZ");
comPort.Close();
}
string doCommand(SerialPort comPort, string cmd)
string Serial_ReadLine(SerialPort comPort)
{
StringBuilder sb = new StringBuilder();
DateTime Deadline = DateTime.Now.AddMilliseconds(comPort.ReadTimeout);
while (DateTime.Now < Deadline)
{
if (comPort.BytesToRead > 0)
{
byte data = (byte)comPort.ReadByte();
sb.Append((char)data);
if (data == '\n')
break;
}
}
return sb.ToString();
}
string doCommand(SerialPort comPort, string cmd, int level = 0)
{
if (!comPort.IsOpen)
return "";
comPort.ReadTimeout = 1000;
// setup to known state
comPort.Write("\r\n");
// alow some time to gather thoughts
Sleep(100);
// ignore all existing data
comPort.DiscardInBuffer();
lbl_status.Text = "Doing Command "+cmd;
Console.WriteLine("Doing Command "+cmd);
// write command
comPort.Write(cmd + "\r\n");
string temp = comPort.ReadLine(); // echo
// read echoed line or existing data
string temp;
try
{
temp = Serial_ReadLine(comPort);
}
catch { temp = comPort.ReadExisting(); }
Console.WriteLine("cmd "+cmd + " echo "+ temp);
// delay for command
Sleep(500);
// get responce
string ans = "";
while (comPort.BytesToRead > 0)
{
ans = ans + comPort.ReadLine() + "\n";
try
{
ans = ans + Serial_ReadLine(comPort) +"\n";
}
catch { ans = ans + comPort.ReadExisting() + "\n"; }
Sleep(50);
if (ans.Length > 500)
return "";
{
break;
}
}
Console.WriteLine("responce " +level+ " " + ans);
// try again
if (ans == "" && level == 0)
return doCommand(comPort, cmd, 1);
return ans;
}
@ -323,7 +386,6 @@ namespace ArdupilotMega
bool doConnect(SerialPort comPort)
{
// clear buffer
comPort.DiscardOutBuffer();
comPort.DiscardInBuffer();
// setup a known enviroment
comPort.Write("\r\n");
@ -334,7 +396,10 @@ namespace ArdupilotMega
// wait
Sleep(1100);
// check for config responce "OK"
if (comPort.ReadExisting().Contains("OK"))
Console.WriteLine("Connect btr " + comPort.BytesToRead + " baud " + comPort.BaudRate);
string conn = comPort.ReadExisting();
Console.WriteLine("Connect first responce "+conn + " " + conn.Length);
if (conn.Contains("OK"))
{
//return true;
}
@ -346,7 +411,7 @@ namespace ArdupilotMega
string version = doCommand(comPort, "ATI");
Console.Write("Connect Version: "+version);
Console.Write("Connect Version: " + version.Trim() + "\n");
if (version.Contains("on HM-TRP"))
{
@ -360,13 +425,18 @@ namespace ArdupilotMega
{
SerialPort comPort = new SerialPort();
try {
comPort.PortName = MainV2.comPort.BaseStream.PortName;
comPort.BaudRate = 57600;
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
comPort.ReadTimeout = 4000;
comPort.Open();
}
catch { MessageBox.Show("Invalid ComPort or in use"); return; }
lbl_status.Text = "Connecting";
if (doConnect(comPort))
@ -375,11 +445,12 @@ namespace ArdupilotMega
lbl_status.Text = "Doing Command";
if (RTI.Text != "")
{
// remote
string answer = doCommand(comPort, "RTI5");
Console.Write("Remote\n"+answer);
string[] items = answer.Split('\n');
foreach (string item in items)
@ -390,7 +461,7 @@ namespace ArdupilotMega
if (values.Length == 3)
{
Control[] controls = this.Controls.Find("R"+values[0].Trim(), false);
Control[] controls = this.Controls.Find("R" + values[0].Trim(), false);
if (controls.Length > 0)
{
@ -414,7 +485,7 @@ namespace ArdupilotMega
}
else
{
if (controls[0].Text != values[2].Trim())
if (controls[0].Text != values[2].Trim() && controls[0].Text != "")
{
string cmdanswer = doCommand(comPort, "RT" + values[0].Trim() + "=" + controls[0].Text + "\r");
@ -437,19 +508,17 @@ namespace ArdupilotMega
doCommand(comPort, "RT&W");
// return to normal mode
comPort.WriteLine("RTZ");
comPort.Write("\r\n");
doCommand(comPort, "RTZ");
Sleep(100);
}
comPort.DiscardInBuffer();
{
//local
answer = doCommand(comPort, "ATI5");
string answer = doCommand(comPort, "ATI5");
Console.Write("Local\n" + answer);
items = answer.Split('\n');
string[] items = answer.Split('\n');
foreach (string item in items)
{
@ -505,18 +574,40 @@ namespace ArdupilotMega
// write it
doCommand(comPort, "AT&W");
// return to normal mode
doCommand(comPort, "ATZ");
}
lbl_status.Text = "Done";
}
else
{
// return to normal mode
doCommand(comPort, "ATZ");
lbl_status.Text = "Fail";
MessageBox.Show("Failed to enter command mode");
}
// return to normal mode
comPort.WriteLine("ATZ");
comPort.Close();
}
private void BUT_syncS2_Click(object sender, EventArgs e)
{
RS2.Text = S2.Text;
}
private void BUT_syncS3_Click(object sender, EventArgs e)
{
RS3.Text = S3.Text;
}
private void BUT_syncS5_Click(object sender, EventArgs e)
{
RS5.Checked = S5.Checked;
}
}
}

View File

@ -418,6 +418,14 @@ namespace uploader
{
byte b;
DateTime Deadline = DateTime.Now.AddMilliseconds(port.ReadTimeout);
while (DateTime.Now < Deadline && port.BytesToRead == 0)
{
}
if (port.BytesToRead == 0)
throw new Exception("Timeout");
b = (byte)port.ReadByte ();
log (string.Format ("recv {0:X}\n", b), 5);