APM Planner 1.1.15

fix reset issue
add Circle AP Mode
change time to wait to 17 secs
This commit is contained in:
Michael Oborne 2011-12-29 18:31:42 +08:00
parent cd145fd7a9
commit 8b2f14c40a
12 changed files with 33 additions and 17 deletions

View File

@ -27,6 +27,8 @@ namespace ArdupilotMega
//void Write(char[] buffer, int offset, int count); //void Write(char[] buffer, int offset, int count);
void WriteLine(string text); void WriteLine(string text);
void toggleDTR();
// Properties // Properties
//Stream BaseStream { get; } //Stream BaseStream { get; }
int BaudRate { get; set; } int BaudRate { get; set; }

View File

@ -9,5 +9,12 @@ namespace ArdupilotMega
class SerialPort : System.IO.Ports.SerialPort,ICommsSerial class SerialPort : System.IO.Ports.SerialPort,ICommsSerial
{ {
public void toggleDTR()
{
DtrEnable = true;
System.Threading.Thread.Sleep(100);
DtrEnable = false;
}
} }
} }

View File

@ -35,6 +35,10 @@ namespace System.IO.Ports
Port = "5760"; Port = "5760";
} }
public void toggleDTR()
{
}
public string Port { get; set; } public string Port { get; set; }
public int ReadTimeout public int ReadTimeout

View File

@ -35,6 +35,10 @@ namespace System.IO.Ports
Port = "14550"; Port = "14550";
} }
public void toggleDTR()
{
}
public string Port { get; set; } public string Port { get; set; }
public int ReadTimeout public int ReadTimeout

View File

@ -461,7 +461,7 @@ namespace ArdupilotMega
} }
break; break;
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_TEST3: case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_TEST3:
mode = "FBW B"; mode = "Circle";
break; break;
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_AUTO: case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_AUTO:
switch (sysstatus.nav_mode) switch (sysstatus.nav_mode)

View File

@ -693,7 +693,7 @@ namespace ArdupilotMega.GCSViews
} }
} }
lbl_status.Text = "Write Done... Waiting (90 sec)"; lbl_status.Text = "Write Done... Waiting (17 sec)";
} }
else else
{ {
@ -714,7 +714,7 @@ namespace ArdupilotMega.GCSViews
DateTime startwait = DateTime.Now; DateTime startwait = DateTime.Now;
while ((DateTime.Now - startwait).TotalSeconds < 75) while ((DateTime.Now - startwait).TotalSeconds < 17)
{ {
try try
{ {
@ -722,7 +722,7 @@ namespace ArdupilotMega.GCSViews
} }
catch { } catch { }
System.Threading.Thread.Sleep(1000); System.Threading.Thread.Sleep(1000);
progress.Value = (int)((DateTime.Now - startwait).TotalSeconds / 75 * 100); progress.Value = (int)((DateTime.Now - startwait).TotalSeconds / 17 * 100);
progress.Refresh(); progress.Refresh();
} }
try try

View File

@ -172,14 +172,14 @@ namespace ArdupilotMega.GCSViews
if (comPort.IsOpen) if (comPort.IsOpen)
comPort.Close(); comPort.Close();
comPort.DtrEnable = true;
comPort.ReadBufferSize = 1024 * 1024; comPort.ReadBufferSize = 1024 * 1024;
comPort.PortName = MainV2.comportname; comPort.PortName = MainV2.comportname;
comPort.Open(); comPort.Open();
comPort.toggleDTR();
System.Threading.Thread t11 = new System.Threading.Thread(delegate() System.Threading.Thread t11 = new System.Threading.Thread(delegate()
{ {
threadrun = true; threadrun = true;

View File

@ -69,9 +69,7 @@ namespace ArdupilotMega
//comPort.ReadBufferSize = 1024 * 1024; //comPort.ReadBufferSize = 1024 * 1024;
try try
{ {
comPort.DtrEnable = false; comPort.toggleDTR();
System.Threading.Thread.Sleep(100);
comPort.DtrEnable = true;
//comPort.Open(); //comPort.Open();
} }
catch (Exception) catch (Exception)

View File

@ -98,10 +98,7 @@ namespace ArdupilotMega
BaseStream.DiscardInBuffer(); BaseStream.DiscardInBuffer();
System.Threading.Thread.Sleep(200); // allow reset to work BaseStream.toggleDTR();
if (BaseStream.DtrEnable)
BaseStream.DtrEnable = false;
// allow 2560 connect timeout on usb // allow 2560 connect timeout on usb
System.Threading.Thread.Sleep(1000); System.Threading.Thread.Sleep(1000);

View File

@ -685,7 +685,7 @@ namespace ArdupilotMega
comPort.BaseStream.DtrEnable = false; comPort.BaseStream.DtrEnable = false;
if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true) if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true)
comPort.BaseStream.DtrEnable = true; comPort.BaseStream.toggleDTR();
try try
{ {
@ -1047,6 +1047,8 @@ namespace ArdupilotMega
{ {
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.disconnect; this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.disconnect;
this.MenuConnect.BackgroundImage.Tag = "Disconnect"; this.MenuConnect.BackgroundImage.Tag = "Disconnect";
CMB_baudrate.Enabled = false;
CMB_serialport.Enabled = false;
}); });
} }
} }
@ -1058,6 +1060,8 @@ namespace ArdupilotMega
{ {
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect; this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
this.MenuConnect.BackgroundImage.Tag = "Connect"; this.MenuConnect.BackgroundImage.Tag = "Connect";
CMB_baudrate.Enabled = true;
CMB_serialport.Enabled = true;
}); });
} }
} }

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

View File

@ -811,11 +811,11 @@ namespace ArdupilotMega.Setup
} }
catch (Exception ex) { MainV2.givecomport = false; MessageBox.Show("Invalid Comport Settings : " + ex.Message); return; } catch (Exception ex) { MainV2.givecomport = false; MessageBox.Show("Invalid Comport Settings : " + ex.Message); return; }
BUT_reset.Text = "Rebooting (75 sec)"; BUT_reset.Text = "Rebooting (17 sec)";
BUT_reset.Refresh(); BUT_reset.Refresh();
Application.DoEvents(); Application.DoEvents();
Sleep(75000, comPortT); // wait for boot/reset Sleep(17000, comPortT); // wait for boot/reset
comPortT.DtrEnable = false; comPortT.DtrEnable = false;