APM Planner 1.0.95

fix ac2 heli error
fix guide mode wp
fix tuning graph on mono
fix autozoom on planner map
modify prefetch - current screen
fix zoom bar for mono
fix base class for special functions
This commit is contained in:
Michael Oborne 2011-11-20 08:17:17 +08:00
parent e42dd2ccc6
commit d25766f7f3
17 changed files with 120 additions and 38 deletions

View File

@ -57,7 +57,7 @@
<DebugType>full</DebugType> <DebugType>full</DebugType>
<Optimize>true</Optimize> <Optimize>true</Optimize>
<OutputPath>bin\Release\</OutputPath> <OutputPath>bin\Release\</OutputPath>
<DefineConstants>TRACE;MAVLINK10cra</DefineConstants> <DefineConstants>DEBUG;TRACE;MAVLINK10cra</DefineConstants>
<ErrorReport>prompt</ErrorReport> <ErrorReport>prompt</ErrorReport>
<WarningLevel>4</WarningLevel> <WarningLevel>4</WarningLevel>
<AllowUnsafeBlocks>false</AllowUnsafeBlocks> <AllowUnsafeBlocks>false</AllowUnsafeBlocks>

View File

@ -57,7 +57,7 @@ namespace System.IO.Ports
get { return client.Available + rbuffer.Length - rbufferread; } get { return client.Available + rbuffer.Length - rbufferread; }
} }
public bool IsOpen { get { return client.Client.Connected; } } public bool IsOpen { get { try { return client.Client.Connected; } catch { return false; } } }
public bool DtrEnable public bool DtrEnable
{ {
@ -97,6 +97,11 @@ namespace System.IO.Ports
{ {
if (client == null || !IsOpen) if (client == null || !IsOpen)
{ {
try
{
client.Close();
}
catch { }
throw new Exception("The socket/serialproxy is closed"); throw new Exception("The socket/serialproxy is closed");
} }
} }
@ -216,11 +221,21 @@ namespace System.IO.Ports
public void Close() public void Close()
{ {
if (client.Client.Connected) try
{
if (client.Client.Connected)
{
client.Client.Close();
client.Close();
}
}
catch { }
try
{ {
client.Client.Close();
client.Close(); client.Close();
} }
catch { }
client = new TcpClient(); client = new TcpClient();
} }

View File

@ -681,7 +681,7 @@ namespace ArdupilotMega.GCSViews
} }
} }
lbl_status.Text = "Done"; lbl_status.Text = "Write Done... Waiting";
} }
else else
{ {
@ -696,6 +696,7 @@ namespace ArdupilotMega.GCSViews
System.Threading.Thread.Sleep(10000); // 10 seconds - new apvar erases eeprom on new format version, this should buy us some time. System.Threading.Thread.Sleep(10000); // 10 seconds - new apvar erases eeprom on new format version, this should buy us some time.
lbl_status.Text = "Done";
} }
catch (Exception ex) { lbl_status.Text = "Failed upload"; MessageBox.Show("Check port settings or Port in use? " + ex.ToString()); port.Close(); } catch (Exception ex) { lbl_status.Text = "Failed upload"; MessageBox.Show("Check port settings or Port in use? " + ex.ToString()); port.Close(); }
flashing = false; flashing = false;

View File

@ -141,6 +141,8 @@ namespace ArdupilotMega.GCSViews
CMB_setwp.SelectedIndex = 0; CMB_setwp.SelectedIndex = 0;
zg1.Visible = true;
CreateChart(zg1); CreateChart(zg1);
// config map // config map
@ -734,6 +736,7 @@ namespace ArdupilotMega.GCSViews
ZedGraphTimer.Enabled = true; ZedGraphTimer.Enabled = true;
ZedGraphTimer.Start(); ZedGraphTimer.Start();
zg1.Visible = true; zg1.Visible = true;
zg1.Refresh();
} }
else else
{ {
@ -807,9 +810,9 @@ namespace ArdupilotMega.GCSViews
Locationwp gotohere = new Locationwp(); Locationwp gotohere = new Locationwp();
gotohere.id = (byte)MAVLink.MAV_CMD.WAYPOINT; gotohere.id = (byte)MAVLink.MAV_CMD.WAYPOINT;
gotohere.alt = (int)(intalt / MainV2.cs.multiplierdist * 100); // back to m gotohere.alt = (float)(intalt / MainV2.cs.multiplierdist); // back to m
gotohere.lat = (int)(gotolocation.Lat * 10000000); gotohere.lat = (float)(gotolocation.Lat);
gotohere.lng = (int)(gotolocation.Lng * 10000000); gotohere.lng = (float)(gotolocation.Lng);
try try
{ {

View File

@ -649,6 +649,7 @@
this.panelMap.ForeColor = System.Drawing.SystemColors.ControlText; this.panelMap.ForeColor = System.Drawing.SystemColors.ControlText;
this.panelMap.MinimumSize = new System.Drawing.Size(27, 27); this.panelMap.MinimumSize = new System.Drawing.Size(27, 27);
this.panelMap.Name = "panelMap"; this.panelMap.Name = "panelMap";
this.panelMap.Resize += new System.EventHandler(this.panelMap_Resize);
// //
// lbl_distance // lbl_distance
// //

View File

@ -642,6 +642,11 @@ namespace ArdupilotMega.GCSViews
updateCMDParams(); updateCMDParams();
// mono
panelMap.Dock = DockStyle.None;
panelMap.Dock = DockStyle.Fill;
panelMap_Resize(null,null);
writeKML(); writeKML();
} }
@ -672,7 +677,12 @@ namespace ArdupilotMega.GCSViews
{ {
selectedrow = e.RowIndex; selectedrow = e.RowIndex;
string option = Commands[Command.Index, selectedrow].EditedFormattedValue.ToString(); string option = Commands[Command.Index, selectedrow].EditedFormattedValue.ToString();
string cmd = Commands[0, selectedrow].Value.ToString(); string cmd;
try
{
cmd = Commands[Command.Index, selectedrow].Value.ToString();
}
catch { cmd = option; }
Console.WriteLine("editformat " + option + " value " + cmd); Console.WriteLine("editformat " + option + " value " + cmd);
ChangeColumnHeader(cmd); ChangeColumnHeader(cmd);
} }
@ -873,14 +883,8 @@ namespace ArdupilotMega.GCSViews
{ {
if (Commands.Rows[a].HeaderCell.Value == null) if (Commands.Rows[a].HeaderCell.Value == null)
{ {
if (ArdupilotMega.MainV2.MAC) Commands.Rows[a].HeaderCell.Style.Alignment = DataGridViewContentAlignment.MiddleCenter;
{
Commands.Rows[a].HeaderCell.Value = " " + (a + 1).ToString(); // mac doesnt auto center header text
}
else
{
Commands.Rows[a].HeaderCell.Value = (a + 1).ToString(); Commands.Rows[a].HeaderCell.Value = (a + 1).ToString();
}
} }
// skip rows with the correct number // skip rows with the correct number
string rowno = Commands.Rows[a].HeaderCell.Value.ToString(); string rowno = Commands.Rows[a].HeaderCell.Value.ToString();
@ -920,14 +924,14 @@ namespace ArdupilotMega.GCSViews
pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt, (a + 1).ToString())); pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt, (a + 1).ToString()));
addpolygonmarker((a + 1).ToString(), double.Parse(cell4), double.Parse(cell3), (int)double.Parse(cell2)); addpolygonmarker((a + 1).ToString(), double.Parse(cell4), double.Parse(cell3), (int)double.Parse(cell2));
avglong += double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()); avglong += double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString());
avglat += double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()); avglat += double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString());
usable++; usable++;
maxlong = Math.Max(double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()), maxlong); maxlong = Math.Max(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()), maxlong);
maxlat = Math.Max(double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()), maxlat); maxlat = Math.Max(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()), maxlat);
minlong = Math.Min(double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()), minlong); minlong = Math.Min(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()), minlong);
minlat = Math.Min(double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()), minlat); minlat = Math.Min(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()), minlat);
System.Diagnostics.Debug.WriteLine(temp - System.Diagnostics.Stopwatch.GetTimestamp()); System.Diagnostics.Debug.WriteLine(temp - System.Diagnostics.Stopwatch.GetTimestamp());
} }
@ -974,9 +978,11 @@ namespace ArdupilotMega.GCSViews
else if (home.Length > 5 && usable == 0) else if (home.Length > 5 && usable == 0)
{ {
lookat = "<LookAt> <longitude>" + TXT_homelng.Text.ToString(new System.Globalization.CultureInfo("en-US")) + "</longitude> <latitude>" + TXT_homelat.Text.ToString(new System.Globalization.CultureInfo("en-US")) + "</latitude> <range>4000</range> </LookAt>"; lookat = "<LookAt> <longitude>" + TXT_homelng.Text.ToString(new System.Globalization.CultureInfo("en-US")) + "</longitude> <latitude>" + TXT_homelat.Text.ToString(new System.Globalization.CultureInfo("en-US")) + "</latitude> <range>4000</range> </LookAt>";
MainMap.HoldInvalidation = true;
MainMap.ZoomAndCenterMarkers("objects"); MainMap.ZoomAndCenterMarkers("objects");
MainMap.Zoom -= 2; MainMap.Zoom -= 2;
MainMap_OnMapZoomChanged(); MainMap_OnMapZoomChanged();
MainMap.HoldInvalidation = false;
} }
RegeneratePolygon(); RegeneratePolygon();
@ -2176,12 +2182,21 @@ namespace ArdupilotMega.GCSViews
private void BUT_Prefetch_Click(object sender, EventArgs e) private void BUT_Prefetch_Click(object sender, EventArgs e)
{ {
RectLatLng area = MainMap.SelectedArea; RectLatLng area = MainMap.SelectedArea;
if (area.IsEmpty)
{
DialogResult res = MessageBox.Show("No ripp area defined, ripp displayed on screen?", "Rip", MessageBoxButtons.YesNo);
if (res == DialogResult.Yes)
{
area = MainMap.CurrentViewArea;
}
}
if (!area.IsEmpty) if (!area.IsEmpty)
{ {
for (int i = (int)MainMap.Zoom; i <= MainMap.MaxZoom; i++) DialogResult res = MessageBox.Show("Ready ripp at Zoom = " + (int)MainMap.Zoom + " ?", "GMap.NET", MessageBoxButtons.YesNo);
{
DialogResult res = MessageBox.Show("Ready ripp at Zoom = " + i + " ?", "GMap.NET", MessageBoxButtons.YesNoCancel);
for (int i = 1; i <= MainMap.MaxZoom; i++)
{
if (res == DialogResult.Yes) if (res == DialogResult.Yes)
{ {
TilePrefetcher obj = new TilePrefetcher(); TilePrefetcher obj = new TilePrefetcher();
@ -2588,6 +2603,7 @@ namespace ArdupilotMega.GCSViews
private void clearMissionToolStripMenuItem_Click(object sender, EventArgs e) private void clearMissionToolStripMenuItem_Click(object sender, EventArgs e)
{ {
Commands.Rows.Clear(); Commands.Rows.Clear();
selectedrow = 0;
writeKML(); writeKML();
} }
@ -2611,7 +2627,7 @@ namespace ArdupilotMega.GCSViews
Commands.Rows[row].Cells[Param1.Index].Value = 1; Commands.Rows[row].Cells[Param1.Index].Value = 1;
Commands.Rows[row].Cells[Param3.Index].Value = repeat; Commands.Rows[row].Cells[Param2.Index].Value = repeat;
} }
private void jumpwPToolStripMenuItem_Click(object sender, EventArgs e) private void jumpwPToolStripMenuItem_Click(object sender, EventArgs e)
@ -2627,7 +2643,7 @@ namespace ArdupilotMega.GCSViews
Commands.Rows[row].Cells[Param1.Index].Value = wp; Commands.Rows[row].Cells[Param1.Index].Value = wp;
Commands.Rows[row].Cells[Param3.Index].Value = repeat; Commands.Rows[row].Cells[Param2.Index].Value = repeat;
} }
private void deleteWPToolStripMenuItem_Click(object sender, EventArgs e) private void deleteWPToolStripMenuItem_Click(object sender, EventArgs e)
@ -2697,5 +2713,15 @@ namespace ArdupilotMega.GCSViews
MainV2.fixtheme(form); MainV2.fixtheme(form);
form.Show(); form.Show();
} }
private void panelMap_Resize(object sender, EventArgs e)
{
// this is a mono fix for the zoom bar
Console.WriteLine("panelmap "+panelMap.Size.ToString());
MainMap.Size = new Size(panelMap.Size.Width - 50,panelMap.Size.Height);
trackBar1.Location = new Point(panelMap.Size.Width - 50,trackBar1.Location.Y);
trackBar1.Size = new System.Drawing.Size(trackBar1.Size.Width, panelMap.Size.Height - trackBar1.Location.Y);
label11.Location = new Point(panelMap.Size.Width - 50, label11.Location.Y);
}
} }
} }

View File

@ -1627,7 +1627,7 @@
<value>Clear Mission</value> <value>Clear Mission</value>
</data> </data>
<data name="contextMenuStrip1.Size" type="System.Drawing.Size, System.Drawing"> <data name="contextMenuStrip1.Size" type="System.Drawing.Size, System.Drawing">
<value>168, 186</value> <value>168, 164</value>
</data> </data>
<data name="&gt;&gt;contextMenuStrip1.Name" xml:space="preserve"> <data name="&gt;&gt;contextMenuStrip1.Name" xml:space="preserve">
<value>contextMenuStrip1</value> <value>contextMenuStrip1</value>
@ -1636,7 +1636,7 @@
<value>System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value> <value>System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data> </data>
<data name="MainMap.Location" type="System.Drawing.Point, System.Drawing"> <data name="MainMap.Location" type="System.Drawing.Point, System.Drawing">
<value>3, 4</value> <value>0, 0</value>
</data> </data>
<data name="MainMap.Size" type="System.Drawing.Size, System.Drawing"> <data name="MainMap.Size" type="System.Drawing.Size, System.Drawing">
<value>838, 306</value> <value>838, 306</value>

View File

@ -556,7 +556,7 @@ namespace ArdupilotMega.GCSViews
processArduPilot(); processArduPilot();
} }
} }
catch { } catch (Exception ex) { Console.WriteLine("SIM Main loop exception " + ex.ToString()); }
if (hzcounttime.Second != DateTime.Now.Second) if (hzcounttime.Second != DateTime.Now.Second)
{ {

View File

@ -203,7 +203,14 @@ namespace ArdupilotMega
if (getparams == true) if (getparams == true)
getParamList(); getParamList();
} }
catch (Exception e) { MainV2.givecomport = false; frm.Close(); throw e; } catch (Exception e) {
try {
BaseStream.Close();
} catch { }
MainV2.givecomport = false;
frm.Close();
throw e;
}
frm.Close(); frm.Close();
@ -485,6 +492,12 @@ namespace ArdupilotMega
/// <param name="value"></param> /// <param name="value"></param>
public bool setParam(string paramname, float value) public bool setParam(string paramname, float value)
{ {
if (!param.ContainsKey(paramname))
{
Console.WriteLine("Param doesnt exist " + paramname);
return false;
}
MainV2.givecomport = true; MainV2.givecomport = true;
__mavlink_param_set_t req = new __mavlink_param_set_t(); __mavlink_param_set_t req = new __mavlink_param_set_t();

View File

@ -48,6 +48,7 @@
// //
// MenuFlightData // MenuFlightData
// //
this.MenuFlightData.AutoSize = false;
this.MenuFlightData.BackgroundImage = global::ArdupilotMega.Properties.Resources.data; this.MenuFlightData.BackgroundImage = global::ArdupilotMega.Properties.Resources.data;
this.MenuFlightData.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuFlightData.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuFlightData.ImageTransparentColor = System.Drawing.Color.Magenta; this.MenuFlightData.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -59,6 +60,7 @@
// //
// MenuFlightPlanner // MenuFlightPlanner
// //
this.MenuFlightPlanner.AutoSize = false;
this.MenuFlightPlanner.BackgroundImage = global::ArdupilotMega.Properties.Resources.planner; this.MenuFlightPlanner.BackgroundImage = global::ArdupilotMega.Properties.Resources.planner;
this.MenuFlightPlanner.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuFlightPlanner.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuFlightPlanner.ImageTransparentColor = System.Drawing.Color.Magenta; this.MenuFlightPlanner.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -72,6 +74,7 @@
// //
// MenuConfiguration // MenuConfiguration
// //
this.MenuConfiguration.AutoSize = false;
this.MenuConfiguration.BackgroundImage = global::ArdupilotMega.Properties.Resources.configuration; this.MenuConfiguration.BackgroundImage = global::ArdupilotMega.Properties.Resources.configuration;
this.MenuConfiguration.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuConfiguration.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuConfiguration.ImageTransparentColor = System.Drawing.Color.Magenta; this.MenuConfiguration.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -85,6 +88,7 @@
// //
// MenuSimulation // MenuSimulation
// //
this.MenuSimulation.AutoSize = false;
this.MenuSimulation.BackgroundImage = global::ArdupilotMega.Properties.Resources.simulation; this.MenuSimulation.BackgroundImage = global::ArdupilotMega.Properties.Resources.simulation;
this.MenuSimulation.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuSimulation.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuSimulation.ImageTransparentColor = System.Drawing.Color.Magenta; this.MenuSimulation.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -98,6 +102,7 @@
// //
// MenuFirmware // MenuFirmware
// //
this.MenuFirmware.AutoSize = false;
this.MenuFirmware.BackgroundImage = global::ArdupilotMega.Properties.Resources.firmware; this.MenuFirmware.BackgroundImage = global::ArdupilotMega.Properties.Resources.firmware;
this.MenuFirmware.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuFirmware.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuFirmware.ImageTransparentColor = System.Drawing.Color.Magenta; this.MenuFirmware.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -112,6 +117,7 @@
// MenuConnect // MenuConnect
// //
this.MenuConnect.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right; this.MenuConnect.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
this.MenuConnect.AutoSize = false;
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect; this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
this.MenuConnect.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuConnect.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuConnect.ImageTransparentColor = System.Drawing.Color.Magenta; this.MenuConnect.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -132,6 +138,7 @@
// //
// MainMenu // MainMenu
// //
this.MainMenu.AutoSize = false;
this.MainMenu.BackColor = System.Drawing.SystemColors.Control; this.MainMenu.BackColor = System.Drawing.SystemColors.Control;
this.MainMenu.BackgroundImage = ((System.Drawing.Image)(resources.GetObject("MainMenu.BackgroundImage"))); this.MainMenu.BackgroundImage = ((System.Drawing.Image)(resources.GetObject("MainMenu.BackgroundImage")));
this.MainMenu.GripMargin = new System.Windows.Forms.Padding(0); this.MainMenu.GripMargin = new System.Windows.Forms.Padding(0);
@ -159,6 +166,7 @@
// //
// MenuTerminal // MenuTerminal
// //
this.MenuTerminal.AutoSize = false;
this.MenuTerminal.BackgroundImage = global::ArdupilotMega.Properties.Resources.terminal; this.MenuTerminal.BackgroundImage = global::ArdupilotMega.Properties.Resources.terminal;
this.MenuTerminal.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuTerminal.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuTerminal.ImageTransparentColor = System.Drawing.Color.Magenta; this.MenuTerminal.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -198,6 +206,7 @@
// //
// MenuHelp // MenuHelp
// //
this.MenuHelp.AutoSize = false;
this.MenuHelp.BackgroundImage = global::ArdupilotMega.Properties.Resources.help; this.MenuHelp.BackgroundImage = global::ArdupilotMega.Properties.Resources.help;
this.MenuHelp.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image; this.MenuHelp.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
this.MenuHelp.ImageTransparentColor = System.Drawing.Color.Magenta; this.MenuHelp.ImageTransparentColor = System.Drawing.Color.Magenta;
@ -247,7 +256,6 @@
this.MainMenu.ResumeLayout(false); this.MainMenu.ResumeLayout(false);
this.MainMenu.PerformLayout(); this.MainMenu.PerformLayout();
this.ResumeLayout(false); this.ResumeLayout(false);
this.PerformLayout();
} }

View File

@ -742,9 +742,17 @@ namespace ArdupilotMega
{ {
comportname = CMB_serialport.Text; comportname = CMB_serialport.Text;
if (comportname == "UDP" || comportname == "TCP") if (comportname == "UDP" || comportname == "TCP")
{
CMB_baudrate.Enabled = false; CMB_baudrate.Enabled = false;
if (comportname == "TCP")
MainV2.comPort.BaseStream = new TcpSerial();
if (comportname == "UDP")
MainV2.comPort.BaseStream = new UdpSerial();
}
else else
{
CMB_baudrate.Enabled = true; CMB_baudrate.Enabled = true;
}
try try
{ {

View File

@ -24,7 +24,7 @@ namespace ArdupilotMega
Application.Idle += new EventHandler(Application_Idle); Application.Idle += new EventHandler(Application_Idle);
MessageBox.Show("NOTE: This version may break advanced mission scripting"); //MessageBox.Show("NOTE: This version may break advanced mission scripting");
Application.EnableVisualStyles(); Application.EnableVisualStyles();
Application.SetCompatibleTextRenderingDefault(false); Application.SetCompatibleTextRenderingDefault(false);

View File

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

View File

@ -1444,6 +1444,7 @@
this.Controls.Add(this.tabControl1); this.Controls.Add(this.tabControl1);
this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.SizableToolWindow; this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.SizableToolWindow;
this.Name = "Setup"; this.Name = "Setup";
this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Setup_FormClosing);
this.Load += new System.EventHandler(this.Setup_Load); this.Load += new System.EventHandler(this.Setup_Load);
this.tabControl1.ResumeLayout(false); this.tabControl1.ResumeLayout(false);
this.tabReset.ResumeLayout(false); this.tabReset.ResumeLayout(false);

View File

@ -75,7 +75,7 @@ namespace ArdupilotMega.Setup
if (tabControl1.SelectedTab == tabHeli) if (tabControl1.SelectedTab == tabHeli)
{ {
if (MainV2.comPort.param["HSV_MAN"].ToString() == "0") if (MainV2.comPort.param["HSV_MAN"] == null || MainV2.comPort.param["HSV_MAN"].ToString() == "0")
return; return;
if (HS3.minline == 0) if (HS3.minline == 0)
@ -1254,5 +1254,11 @@ namespace ArdupilotMega.Setup
if (int.Parse(temp.Text) > 2100) if (int.Parse(temp.Text) > 2100)
temp.Text = "2100"; temp.Text = "2100";
} }
private void Setup_FormClosing(object sender, FormClosingEventArgs e)
{
timer.Stop();
timer.Dispose();
}
} }
} }

View File

@ -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>N43U7y77mNy6nfkD9v5DNdwNLps=</dsig:DigestValue> <dsig:DigestValue>d1SWduiRJYsMADkinyiFASzMBV8=</dsig:DigestValue>
</hash> </hash>
</dependentAssembly> </dependentAssembly>
</dependency> </dependency>

View File

@ -1627,7 +1627,7 @@
<value>Clear Mission</value> <value>Clear Mission</value>
</data> </data>
<data name="contextMenuStrip1.Size" type="System.Drawing.Size, System.Drawing"> <data name="contextMenuStrip1.Size" type="System.Drawing.Size, System.Drawing">
<value>168, 186</value> <value>168, 164</value>
</data> </data>
<data name="&gt;&gt;contextMenuStrip1.Name" xml:space="preserve"> <data name="&gt;&gt;contextMenuStrip1.Name" xml:space="preserve">
<value>contextMenuStrip1</value> <value>contextMenuStrip1</value>
@ -1636,7 +1636,7 @@
<value>System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value> <value>System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data> </data>
<data name="MainMap.Location" type="System.Drawing.Point, System.Drawing"> <data name="MainMap.Location" type="System.Drawing.Point, System.Drawing">
<value>3, 4</value> <value>0, 0</value>
</data> </data>
<data name="MainMap.Size" type="System.Drawing.Size, System.Drawing"> <data name="MainMap.Size" type="System.Drawing.Size, System.Drawing">
<value>838, 306</value> <value>838, 306</value>