APM Planner 1.1.10

fix log crash
This commit is contained in:
Michael Oborne 2011-12-19 22:41:23 +08:00
parent e7568db237
commit 1ed7c48de4
6 changed files with 22 additions and 7 deletions

View File

@ -256,7 +256,7 @@ namespace ArdupilotMega.GCSViews
// re-request servo data
if (!(lastdata.AddSeconds(8) > DateTime.Now) && comPort.BaseStream.IsOpen)
{
Console.WriteLine("REQ streams - flightdata");
//Console.WriteLine("REQ streams - flightdata");
try
{
//System.Threading.Thread.Sleep(1000);

View File

@ -2863,7 +2863,7 @@ namespace ArdupilotMega.GCSViews
private void panelMap_Resize(object sender, EventArgs e)
{
// this is a mono fix for the zoom bar
Console.WriteLine("panelmap "+panelMap.Size.ToString());
//Console.WriteLine("panelmap "+panelMap.Size.ToString());
MainMap.Size = new Size(panelMap.Size.Width - 50,panelMap.Size.Height);
trackBar1.Location = new System.Drawing.Point(panelMap.Size.Width - 50,trackBar1.Location.Y);
trackBar1.Size = new System.Drawing.Size(trackBar1.Size.Width, panelMap.Size.Height - trackBar1.Location.Y);
@ -2968,6 +2968,12 @@ namespace ArdupilotMega.GCSViews
if (MainV2.comPort.param["FENCE_ACTION"].ToString() != "0")
MainV2.comPort.setParam("FENCE_ACTION", 0);
if (drawnpolygon == null)
{
MessageBox.Show("No polygon to upload");
return;
}
MainV2.comPort.setParam("FENCE_TOTAL", drawnpolygon.Points.Count);
byte a = 0;

View File

@ -318,6 +318,7 @@ namespace ArdupilotMega.GCSViews
/// <param name="write">true/false</param>
private void xmlconfig(bool write)
{
int fixme;
if (write)
{
ArdupilotMega.MainV2.config["REV_roll"] = CHKREV_roll.Checked.ToString();

View File

@ -87,7 +87,11 @@ namespace ArdupilotMega
System.Threading.Thread.Sleep(2000);
comPort.Write("\n\n\n\n");
try
{
comPort.Write("\n\n\n\n");
}
catch { }
while (threadrun)
{
@ -140,7 +144,11 @@ namespace ArdupilotMega
{
this.BeginInvoke((System.Windows.Forms.MethodInvoker)delegate()
{
TXT_status.Text = status.ToString() + " " + receivedbytes + " " + comPort.BytesToRead;
try
{
TXT_status.Text = status.ToString() + " " + receivedbytes + " " + comPort.BytesToRead;
}
catch { }
});
start = DateTime.Now;
}

View File

@ -2073,7 +2073,7 @@ namespace ArdupilotMega
if (bpstime.Second != DateTime.Now.Second && !logreadmode)
{
Console.Write("bps {0} loss {1} left {2} mem {3} \n", bps1, synclost, BaseStream.BytesToRead, System.GC.GetTotalMemory(false));
// Console.Write("bps {0} loss {1} left {2} mem {3} \n", bps1, synclost, BaseStream.BytesToRead, System.GC.GetTotalMemory(false));
bps2 = bps1; // prev sec
bps1 = 0; // current sec
bpstime = DateTime.Now;
@ -2170,7 +2170,7 @@ namespace ArdupilotMega
if (MainV2.talk != null && MainV2.config["speechenable"] != null && MainV2.config["speechenable"].ToString() == "True")
{
MainV2.talk.SpeakAsync(logdata);
//MainV2.talk.SpeakAsync(logdata);
}
}

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.9")]
[assembly: AssemblyFileVersion("1.1.10")]
[assembly: NeutralResourcesLanguageAttribute("")]