APM Planner - 1.1.34

fixs based on error emails - minor
This commit is contained in:
Michael Oborne 2012-02-08 07:55:46 +08:00
parent 83326a9d62
commit 54dbb4ace9
5 changed files with 85 additions and 55 deletions

View File

@ -12,6 +12,24 @@ namespace ArdupilotMega
{
public event ProgressEventHandler Progress;
public void Open()
{
// default dtr status is false
base.Open();
// let it settle
System.Threading.Thread.Sleep(10);
// pull dtr low
this.DtrEnable = true;
System.Threading.Thread.Sleep(1);
// free dtr
this.DtrEnable = false;
System.Threading.Thread.Sleep(1);
// pull dtr low
this.DtrEnable = true;
}
/// <summary>
/// Used to start initial connecting after serialport.open
/// </summary>

View File

@ -660,43 +660,41 @@ namespace ArdupilotMega.GCSViews
private void timer1_Tick(object sender, EventArgs e)
{
// Make sure that the curvelist has at least one curve
if (zg1.GraphPane.CurveList.Count <= 0)
return;
// Get the first CurveItem in the graph
LineItem curve = zg1.GraphPane.CurveList[0] as LineItem;
if (curve == null)
return;
// Get the PointPairList
IPointListEdit list = curve.Points as IPointListEdit;
// If this is null, it means the reference at curve.Points does not
// support IPointListEdit, so we won't be able to modify it
if (list == null)
return;
// Time is measured in seconds
double time = (Environment.TickCount - tickStart) / 1000.0;
// Keep the X scale at a rolling 30 second interval, with one
// major step between the max X value and the end of the axis
Scale xScale = zg1.GraphPane.XAxis.Scale;
if (time > xScale.Max - xScale.MajorStep)
{
xScale.Max = time + xScale.MajorStep;
xScale.Min = xScale.Max - 10.0;
}
// Make sure the Y axis is rescaled to accommodate actual data
try
{
// Make sure that the curvelist has at least one curve
if (zg1.GraphPane.CurveList.Count <= 0)
return;
// Get the first CurveItem in the graph
LineItem curve = zg1.GraphPane.CurveList[0] as LineItem;
if (curve == null)
return;
// Get the PointPairList
IPointListEdit list = curve.Points as IPointListEdit;
// If this is null, it means the reference at curve.Points does not
// support IPointListEdit, so we won't be able to modify it
if (list == null)
return;
// Time is measured in seconds
double time = (Environment.TickCount - tickStart) / 1000.0;
// Keep the X scale at a rolling 30 second interval, with one
// major step between the max X value and the end of the axis
Scale xScale = zg1.GraphPane.XAxis.Scale;
if (time > xScale.Max - xScale.MajorStep)
{
xScale.Max = time + xScale.MajorStep;
xScale.Min = xScale.Max - 10.0;
}
// Make sure the Y axis is rescaled to accommodate actual data
zg1.AxisChange();
}
catch { }
// Force a redraw
try
{
// Force a redraw
zg1.Invalidate();
}
catch { }

View File

@ -281,14 +281,15 @@ namespace ArdupilotMega.GCSViews
{
float result;
float.TryParse(TXT_homealt.Text, out result);
bool pass = float.TryParse(TXT_homealt.Text, out result);
if (result == 0)
if (result == 0 || pass == false)
{
MessageBox.Show("You must have a home altitude");
return;
}
if (!float.TryParse(TXT_DefaultAlt.Text, out result))
int results1;
if (!int.TryParse(TXT_DefaultAlt.Text, out results1))
{
MessageBox.Show("Your default alt is not valid");
return;
@ -2060,7 +2061,11 @@ namespace ArdupilotMega.GCSViews
{
if (MainMap.Zoom > 0)
{
trackBar1.Value = (int)(MainMap.Zoom);
try
{
trackBar1.Value = (int)(MainMap.Zoom);
}
catch { }
//textBoxZoomCurrent.Text = MainMap.Zoom.ToString();
center.Position = MainMap.Position;
}
@ -2199,9 +2204,13 @@ namespace ArdupilotMega.GCSViews
private void comboBoxMapType_SelectedValueChanged(object sender, EventArgs e)
{
MainMap.MapType = (MapType)comboBoxMapType.SelectedItem;
FlightData.mymap.MapType = (MapType)comboBoxMapType.SelectedItem;
MainV2.config["MapType"] = comboBoxMapType.Text;
try
{
MainMap.MapType = (MapType)comboBoxMapType.SelectedItem;
FlightData.mymap.MapType = (MapType)comboBoxMapType.SelectedItem;
MainV2.config["MapType"] = comboBoxMapType.Text;
}
catch { MessageBox.Show("Map change failed. try zomming out first."); }
}
private void Commands_EditingControlShowing(object sender, DataGridViewEditingControlShowingEventArgs e)
@ -2841,20 +2850,25 @@ namespace ArdupilotMega.GCSViews
}
else if (int.TryParse(CurentRectMarker.InnerMarker.Tag.ToString().Replace("grid", ""), out no))
{
drawnpolygon.Points.RemoveAt(no - 1);
drawnpolygons.Markers.Clear();
int a = 1;
foreach (PointLatLng pnt in drawnpolygon.Points)
try
{
addpolygonmarkergrid(a.ToString(), pnt.Lng, pnt.Lat, 0);
a++;
drawnpolygon.Points.RemoveAt(no - 1);
drawnpolygons.Markers.Clear();
int a = 1;
foreach (PointLatLng pnt in drawnpolygon.Points)
{
addpolygonmarkergrid(a.ToString(), pnt.Lng, pnt.Lat, 0);
a++;
}
MainMap.UpdatePolygonLocalPosition(drawnpolygon);
MainMap.Invalidate();
}
catch {
MessageBox.Show("Remove point Failed. Please try again.");
}
MainMap.UpdatePolygonLocalPosition(drawnpolygon);
MainMap.Invalidate();
}
}

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