APM Planner - gps lat long bug fix.

This commit is contained in:
Michael Oborne 2012-02-21 11:55:36 +08:00
parent 3bb3cbe5b6
commit 06a1035953
5 changed files with 17 additions and 6 deletions

View File

@ -683,8 +683,8 @@ namespace ArdupilotMega
}
byte[] bytes = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT];
if (bytes != null)
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT];
if (bytearray != null)
{
var loc = bytearray.ByteArrayToStructure<MAVLink.__mavlink_global_position_int_t>(6);

View File

@ -535,7 +535,11 @@ namespace ArdupilotMega.GCSViews
{
this.BeginInvoke((System.Windows.Forms.MethodInvoker)delegate()
{
MainV2.cs.UpdateCurrentSettings(bindingSource1);
try
{
MainV2.cs.UpdateCurrentSettings(bindingSource1);
}
catch { }
});
}

View File

@ -145,8 +145,11 @@ namespace ArdupilotMega
return;
//Console.WriteLine(DateTime.Now.Millisecond + " timer2 serial");
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
try
{
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
}
catch { }
if (sw != null && sw.BaseStream.CanWrite)
{

View File

@ -48,7 +48,11 @@ namespace ArdupilotMega.Setup
void timer_Tick(object sender, EventArgs e)
{
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
try
{
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
}
catch { }
float pwm = 0;