mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 18:38:28 -04:00
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
a82958656a
@ -199,6 +199,10 @@ static void init_ardupilot()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// agmatthews USERHOOKS
|
||||||
|
#ifdef USERHOOK_INIT
|
||||||
|
USERHOOK_INIT
|
||||||
|
#endif
|
||||||
// Logging:
|
// Logging:
|
||||||
// --------
|
// --------
|
||||||
// DataFlash log initialization
|
// DataFlash log initialization
|
||||||
|
@ -168,6 +168,8 @@ namespace ArdupilotMega.GCSViews
|
|||||||
|
|
||||||
comPort.ReadBufferSize = 1024 * 1024;
|
comPort.ReadBufferSize = 1024 * 1024;
|
||||||
|
|
||||||
|
comPort.PortName = MainV2.comportname;
|
||||||
|
|
||||||
comPort.Open();
|
comPort.Open();
|
||||||
|
|
||||||
System.Threading.Thread t11 = new System.Threading.Thread(delegate()
|
System.Threading.Thread t11 = new System.Threading.Thread(delegate()
|
||||||
|
@ -75,7 +75,8 @@ namespace ArdupilotMega
|
|||||||
comPort.DtrEnable = true;
|
comPort.DtrEnable = true;
|
||||||
//comPort.Open();
|
//comPort.Open();
|
||||||
}
|
}
|
||||||
catch (Exception) {
|
catch (Exception)
|
||||||
|
{
|
||||||
MessageBox.Show("Error opening comport");
|
MessageBox.Show("Error opening comport");
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -158,7 +159,8 @@ namespace ArdupilotMega
|
|||||||
if (!line.Contains("\n"))
|
if (!line.Contains("\n"))
|
||||||
line = line + "\n";
|
line = line + "\n";
|
||||||
}
|
}
|
||||||
catch {
|
catch
|
||||||
|
{
|
||||||
line = comPort.ReadExisting();
|
line = comPort.ReadExisting();
|
||||||
//byte[] data = readline(comPort);
|
//byte[] data = readline(comPort);
|
||||||
//line = Encoding.ASCII.GetString(data, 0, data.Length);
|
//line = Encoding.ASCII.GetString(data, 0, data.Length);
|
||||||
@ -172,7 +174,7 @@ namespace ArdupilotMega
|
|||||||
{
|
{
|
||||||
case serialstatus.Connecting:
|
case serialstatus.Connecting:
|
||||||
|
|
||||||
if (line.Contains("reset to FLY") || line.Contains("interactive setup"))
|
if (line.Contains("reset to FLY") || line.Contains("interactive setup") || line.Contains("CLI:"))
|
||||||
{
|
{
|
||||||
comPort.Write("logs\r");
|
comPort.Write("logs\r");
|
||||||
}
|
}
|
||||||
@ -199,6 +201,8 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
MainV2.cs.firmware = MainV2.Firmwares.ArduPlane;
|
MainV2.cs.firmware = MainV2.Firmwares.ArduPlane;
|
||||||
|
|
||||||
|
TXT_seriallog.AppendText("Createing KML for " + logfile);
|
||||||
|
|
||||||
while (tr.Peek() != -1)
|
while (tr.Peek() != -1)
|
||||||
{
|
{
|
||||||
processLine(tr.ReadLine());
|
processLine(tr.ReadLine());
|
||||||
@ -206,7 +210,11 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
tr.Close();
|
tr.Close();
|
||||||
|
|
||||||
|
try
|
||||||
|
{
|
||||||
writeKML(logfile + ".kml");
|
writeKML(logfile + ".kml");
|
||||||
|
}
|
||||||
|
catch { } // usualy invalid lat long error
|
||||||
status = serialstatus.Done;
|
status = serialstatus.Done;
|
||||||
break;
|
break;
|
||||||
case serialstatus.Createfile:
|
case serialstatus.Createfile:
|
||||||
@ -286,12 +294,15 @@ namespace ArdupilotMega
|
|||||||
{
|
{
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
|
Application.DoEvents();
|
||||||
|
|
||||||
line = line.Replace(", ", ",");
|
line = line.Replace(", ", ",");
|
||||||
line = line.Replace(": ", ":");
|
line = line.Replace(": ", ":");
|
||||||
|
|
||||||
string[] items = line.Split(',', ':');
|
string[] items = line.Split(',', ':');
|
||||||
|
|
||||||
if (items[0].Contains("CMD")) {
|
if (items[0].Contains("CMD"))
|
||||||
|
{
|
||||||
if (flightdata.Count == 0)
|
if (flightdata.Count == 0)
|
||||||
{
|
{
|
||||||
if (int.Parse(items[2]) <= (int)MAVLink.MAV_CMD.LAST) // wps
|
if (int.Parse(items[2]) <= (int)MAVLink.MAV_CMD.LAST) // wps
|
||||||
@ -529,6 +540,9 @@ namespace ArdupilotMega
|
|||||||
}
|
}
|
||||||
catch { }
|
catch { }
|
||||||
|
|
||||||
|
try
|
||||||
|
{
|
||||||
|
|
||||||
pmplane.Point = new KmlPoint((float)model.Location.longitude, (float)model.Location.latitude, (float)model.Location.altitude);
|
pmplane.Point = new KmlPoint((float)model.Location.longitude, (float)model.Location.latitude, (float)model.Location.altitude);
|
||||||
pmplane.Point.AltitudeMode = altmode;
|
pmplane.Point.AltitudeMode = altmode;
|
||||||
|
|
||||||
@ -540,6 +554,8 @@ namespace ArdupilotMega
|
|||||||
pmplane.Model = model;
|
pmplane.Model = model;
|
||||||
|
|
||||||
planes.Add(pmplane);
|
planes.Add(pmplane);
|
||||||
|
}
|
||||||
|
catch { } // bad lat long value
|
||||||
|
|
||||||
lastmodel = mod.model;
|
lastmodel = mod.model;
|
||||||
|
|
||||||
@ -643,7 +659,8 @@ namespace ArdupilotMega
|
|||||||
comPort.Write(a.ToString() + "\r");
|
comPort.Write(a.ToString() + "\r");
|
||||||
status = serialstatus.Createfile;
|
status = serialstatus.Createfile;
|
||||||
|
|
||||||
while (status != serialstatus.Done) {
|
while (status != serialstatus.Done)
|
||||||
|
{
|
||||||
System.Threading.Thread.Sleep(100);
|
System.Threading.Thread.Sleep(100);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -687,6 +704,7 @@ namespace ArdupilotMega
|
|||||||
System.Threading.Thread.Sleep(500);
|
System.Threading.Thread.Sleep(500);
|
||||||
comPort.Write("erase\r");
|
comPort.Write("erase\r");
|
||||||
System.Threading.Thread.Sleep(100);
|
System.Threading.Thread.Sleep(100);
|
||||||
|
TXT_seriallog.AppendText("!!Allow 30 seconds for erase\n");
|
||||||
status = serialstatus.Done;
|
status = serialstatus.Done;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -321,6 +321,13 @@ namespace ArdupilotMega
|
|||||||
RichTextBox txtr = (RichTextBox)ctl;
|
RichTextBox txtr = (RichTextBox)ctl;
|
||||||
txtr.BorderStyle = BorderStyle.None;
|
txtr.BorderStyle = BorderStyle.None;
|
||||||
}
|
}
|
||||||
|
else if (((Type)ctl.GetType()) == typeof(CheckedListBox))
|
||||||
|
{
|
||||||
|
ctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||||
|
ctl.ForeColor = Color.White;
|
||||||
|
CheckedListBox txtr = (CheckedListBox)ctl;
|
||||||
|
txtr.BorderStyle = BorderStyle.None;
|
||||||
|
}
|
||||||
else if (((Type)ctl.GetType()) == typeof(TabPage))
|
else if (((Type)ctl.GetType()) == typeof(TabPage))
|
||||||
{
|
{
|
||||||
ctl.BackColor = Color.FromArgb(0x26, 0x27, 0x28); //Color.FromArgb(0x43, 0x44, 0x45);
|
ctl.BackColor = Color.FromArgb(0x26, 0x27, 0x28); //Color.FromArgb(0x43, 0x44, 0x45);
|
||||||
@ -682,7 +689,7 @@ namespace ArdupilotMega
|
|||||||
private void CMB_serialport_SelectedIndexChanged(object sender, EventArgs e)
|
private void CMB_serialport_SelectedIndexChanged(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
comportname = CMB_serialport.Text;
|
comportname = CMB_serialport.Text;
|
||||||
if (comportname == "UDP")
|
if (comportname == "UDP" || comportname == "TCP")
|
||||||
CMB_baudrate.Enabled = false;
|
CMB_baudrate.Enabled = false;
|
||||||
else
|
else
|
||||||
CMB_baudrate.Enabled = true;
|
CMB_baudrate.Enabled = true;
|
||||||
|
@ -34,5 +34,5 @@ using System.Resources;
|
|||||||
// by using the '*' as shown below:
|
// by using the '*' as shown below:
|
||||||
// [assembly: AssemblyVersion("1.0.*")]
|
// [assembly: AssemblyVersion("1.0.*")]
|
||||||
[assembly: AssemblyVersion("1.0.0.0")]
|
[assembly: AssemblyVersion("1.0.0.0")]
|
||||||
[assembly: AssemblyFileVersion("1.0.83")]
|
[assembly: AssemblyFileVersion("1.0.84")]
|
||||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||||
|
@ -11,7 +11,7 @@
|
|||||||
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
|
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
|
||||||
</dsig:Transforms>
|
</dsig:Transforms>
|
||||||
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
|
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
|
||||||
<dsig:DigestValue>xG04b9X6TXBWirLuQOgI+3TR8H0=</dsig:DigestValue>
|
<dsig:DigestValue>sVd4w+f3LroCsyok5UsAi4Bq9eI=</dsig:DigestValue>
|
||||||
</hash>
|
</hash>
|
||||||
</dependentAssembly>
|
</dependentAssembly>
|
||||||
</dependency>
|
</dependency>
|
||||||
|
Loading…
Reference in New Issue
Block a user