APM Planner 1.0.67 - git build

This commit is contained in:
Michael Oborne 2011-09-10 14:15:14 +08:00
parent a540f60cc8
commit c9bde44275
16 changed files with 79 additions and 489 deletions

4
Tools/ArdupilotMegaPlanner/.gitignore vendored Normal file
View File

@ -0,0 +1,4 @@
*.pfx
*.suo
*.user

View File

@ -346,6 +346,7 @@
</Compile> </Compile>
<EmbeddedResource Include="AGauge.resx"> <EmbeddedResource Include="AGauge.resx">
<DependentUpon>AGauge.cs</DependentUpon> <DependentUpon>AGauge.cs</DependentUpon>
<SubType>Designer</SubType>
</EmbeddedResource> </EmbeddedResource>
<EmbeddedResource Include="Log.zh-Hans.resx"> <EmbeddedResource Include="Log.zh-Hans.resx">
<DependentUpon>Log.cs</DependentUpon> <DependentUpon>Log.cs</DependentUpon>

View File

@ -1,13 +0,0 @@
<?xml version="1.0" encoding="utf-8"?>
<Project ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
<PropertyGroup>
<PublishUrlHistory>publish/|ftp://vps.oborne.me/ardupilotmegaplanner/|ftp://vps.oborne.me/|ftp://www.vps.oborne.me/ardupilotmegaplanner/|http://www.vps.oborne.me/dav/ardupilotmegaplanner/</PublishUrlHistory>
<InstallUrlHistory>http://www.vps.oborne.me/ardupilotmegaplanner/|http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/publish/</InstallUrlHistory>
<SupportUrlHistory>http://www.diydrones.com/</SupportUrlHistory>
<UpdateUrlHistory>http://www.vps.oborne.me/ardupilotmegaplanner/|http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/publish/|http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Publish/</UpdateUrlHistory>
<BootstrapperUrlHistory />
<ErrorReportUrlHistory />
<FallbackCulture>en-US</FallbackCulture>
<VerifyUploadedFiles>false</VerifyUploadedFiles>
</PropertyGroup>
</Project>

View File

@ -384,7 +384,7 @@ namespace ArdupilotMega
public static Type getModes() public static Type getModes()
{ {
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega) if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{ {
return typeof(apmmodes); return typeof(apmmodes);
} }

View File

@ -145,7 +145,7 @@ namespace ArdupilotMega
public ushort rcoverridech4 { get; set; } public ushort rcoverridech4 { get; set; }
// current firmware // current firmware
public MainV2.Firmwares firmware = MainV2.Firmwares.ArduPilotMega; public MainV2.Firmwares firmware = MainV2.Firmwares.ArduPlane;
public float freemem { get; set; } public float freemem { get; set; }
public float brklevel { get; set; } public float brklevel { get; set; }

View File

@ -52,7 +52,7 @@ namespace ArdupilotMega.GCSViews
// enable disable relevbant hardware tabs // enable disable relevbant hardware tabs
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPilotMega) if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
{ {
ConfigTabs.SelectedIndex = 0; ConfigTabs.SelectedIndex = 0;
TabAPM2.Enabled = true; TabAPM2.Enabled = true;
@ -524,7 +524,7 @@ namespace ArdupilotMega.GCSViews
{ {
StreamWriter sw = new StreamWriter(sfd.OpenFile()); StreamWriter sw = new StreamWriter(sfd.OpenFile());
string input = DateTime.Now + " Frame : + | Arducopter Kit | Kit motors"; string input = DateTime.Now + " Frame : + | Arducopter Kit | Kit motors";
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPilotMega) if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
{ {
input = DateTime.Now + " Plane: Skywalker"; input = DateTime.Now + " Plane: Skywalker";
} }

View File

@ -250,7 +250,7 @@ namespace ArdupilotMega.GCSViews
{ {
if (keyData == (Keys.Control | Keys.B)) if (keyData == (Keys.Control | Keys.B))
{ {
findfirmware("APM-trunk"); findfirmware("AP-trunk");
return true; return true;
} }
if (keyData == (Keys.Control | Keys.A)) if (keyData == (Keys.Control | Keys.A))
@ -273,8 +273,6 @@ namespace ArdupilotMega.GCSViews
public int k_format_version; public int k_format_version;
} }
FRAMETYPES currentframe = FRAMETYPES.NONE;
public enum FRAMETYPES public enum FRAMETYPES
{ {
NONE, NONE,
@ -306,7 +304,7 @@ namespace ArdupilotMega.GCSViews
try try
{ {
using (XmlTextReader xmlreader = new XmlTextReader("http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/Firmware/firmware2.xml")) using (XmlTextReader xmlreader = new XmlTextReader("http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml"))
{ {
while (xmlreader.Read()) while (xmlreader.Read())
{ {
@ -378,49 +376,41 @@ namespace ArdupilotMega.GCSViews
private void pictureBoxAPM_Click(object sender, EventArgs e) private void pictureBoxAPM_Click(object sender, EventArgs e)
{ {
currentframe = FRAMETYPES.APM; findfirmware("firmware/AP-");
findfirmware("APM2-");
} }
private void pictureBoxAPMHIL_Click(object sender, EventArgs e) private void pictureBoxAPMHIL_Click(object sender, EventArgs e)
{ {
currentframe = FRAMETYPES.APMHIL; findfirmware("firmware/APHIL-");
findfirmware("APM2HIL-");
} }
private void pictureBoxQuad_Click(object sender, EventArgs e) private void pictureBoxQuad_Click(object sender, EventArgs e)
{ {
currentframe = FRAMETYPES.QUAD;
findfirmware("AC2-Quad-"); findfirmware("AC2-Quad-");
} }
private void pictureBoxHexa_Click(object sender, EventArgs e) private void pictureBoxHexa_Click(object sender, EventArgs e)
{ {
currentframe = FRAMETYPES.HEXA;
findfirmware("AC2-Hexa-"); findfirmware("AC2-Hexa-");
} }
private void pictureBoxTri_Click(object sender, EventArgs e) private void pictureBoxTri_Click(object sender, EventArgs e)
{ {
currentframe = FRAMETYPES.TRI;
findfirmware("AC2-Tri-"); findfirmware("AC2-Tri-");
} }
private void pictureBoxY6_Click(object sender, EventArgs e) private void pictureBoxY6_Click(object sender, EventArgs e)
{ {
currentframe = FRAMETYPES.Y6;
findfirmware("AC2-Y6-"); findfirmware("AC2-Y6-");
} }
private void pictureBoxHeli_Click(object sender, EventArgs e) private void pictureBoxHeli_Click(object sender, EventArgs e)
{ {
currentframe = FRAMETYPES.HELI;
findfirmware("AC2-Heli-"); findfirmware("AC2-Heli-");
} }
private void pictureBoxQuadHil_Click(object sender, EventArgs e) private void pictureBoxQuadHil_Click(object sender, EventArgs e)
{ {
currentframe = FRAMETYPES.QUAD;
findfirmware("AC2-QUADHIL"); findfirmware("AC2-QUADHIL");
} }
@ -502,15 +492,19 @@ namespace ArdupilotMega.GCSViews
this.Refresh(); this.Refresh();
while (dataStream.CanRead && bytes > 0) dataStream.ReadTimeout = 30000;
while (dataStream.CanRead)
{ {
try try
{ {
progress.Value = (int)(((float)(response.ContentLength - bytes) / (float)response.ContentLength) * 100); progress.Value = 50;// (int)(((float)(response.ContentLength - bytes) / (float)response.ContentLength) * 100);
this.progress.Refresh(); this.progress.Refresh();
} }
catch { } catch { }
int len = dataStream.Read(buf1, 0, 1024); int len = dataStream.Read(buf1, 0, 1024);
if (len == 0)
break;
bytes -= len; bytes -= len;
fs.Write(buf1, 0, len); fs.Write(buf1, 0, len);
} }
@ -704,420 +698,6 @@ namespace ArdupilotMega.GCSViews
} }
} }
private void ACSetup_Click(object sender, EventArgs e)
{
MainV2.givecomport = true;
MessageBox.Show("Please make sure you are in CLI/Setup mode");
ICommsSerial comPortT = MainV2.comPort.BaseStream;
if (comPortT.IsOpen)
comPortT.Close();
comPortT.DtrEnable = true;
if (MainV2.comportname == null)
{
MessageBox.Show("Please select a valid comport! look in the Options menu");
MainV2.givecomport = false;
return;
}
try
{
comPortT.Open();
}
catch (Exception ex) { MainV2.givecomport = false; MessageBox.Show("Invalid Comport Settings : " + ex.Message); return; }
lbl_status.Text = "Comport Opened";
this.Refresh();
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
System.Threading.Thread.Sleep(3000);
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
string data = "";
DateTime timeout = DateTime.Now;
///////////////////////// FIX ME////////////////////////////////////////////////////////
int step = 0;
//System.Threading.Thread.Sleep(2000);
//comPortT.Write("IMU\r");
comPortT.ReadTimeout = -1;
while (comPortT.IsOpen)
{
string line;
try
{
line = comPortT.ReadLine();
}
catch
{
try { line = comPortT.ReadExisting(); }
catch { MessageBox.Show("Can not read from serial port - existing"); return; }
}
this.Refresh();
Console.Write(line + "\n");
switch (step)
{
case 0:
if (line.Contains("interactive"))
{
lbl_status.Text = "Erasing EEPROM.. (20 seconds)";
this.Refresh();
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
System.Threading.Thread.Sleep(50);
comPortT.Write("erase\r");
System.Threading.Thread.Sleep(50);
comPortT.Write("y\r");
step = 0;
}
if (line.Contains("done"))
{
lbl_status.Text = "Rebooting APM..";
this.Refresh();
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
System.Threading.Thread.Sleep(3000);
comPortT.DtrEnable = false;
Console.WriteLine(comPortT.ReadExisting());
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
step = 1;
}
break;
case 1:
if (line.Contains("interactive")) // becuase we rebooted
{
lbl_status.Text = "Setup Radio..";
this.Refresh();
Console.WriteLine(comPortT.ReadExisting());
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
System.Threading.Thread.Sleep(200);
MessageBox.Show("Ensure that your RC transmitter is on, and that you have your ArduCopter battery plugged in or are otherwise powering APM's RC pins (USB power does NOT power the RC receiver)", "Radio Setup");
comPortT.Write("radio\r");
MessageBox.Show("Move all your radio controls to each extreme. Hit OK when done.", "Radio Setup");
//comPortT.DiscardInBuffer();
comPortT.Write("\r\r");
step = 2;
}
break;
case 2:
if (data.Contains("----"))
data = "";
data += line;
if (line.Contains("CH7")) //
{
MessageBox.Show("Here are the detected radio options\nNOTE Channels not connected are displayed as 1500\nNormal values are around 1100 | 1900\nChannel:Min | Max \n" + data, "Radio");
lbl_status.Text = "Setup Accel Offsets..";
this.Refresh();
MessageBox.Show("Ensure your quad is level, and click OK to continue", "Offset Setup");
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
System.Threading.Thread.Sleep(50);
comPortT.Write("level\r");
System.Threading.Thread.Sleep(1000);
step = 3;
}
break;
case 3:
if (line.Contains("IMU")) //
{
lbl_status.Text = "Setup Options";
this.Refresh();
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
DialogResult dr;
/*
dr = MessageBox.Show("Do you have a Current sensor attached?","Current Sensor",MessageBoxButtons.YesNo);
if (dr == System.Windows.Forms.DialogResult.Yes)
{
comPortT.Write("current on\r");
System.Threading.Thread.Sleep(100);
}*/
dr = MessageBox.Show("Do you have a Sonar sensor attached?", "Sonar Sensor", MessageBoxButtons.YesNo);
if (dr == System.Windows.Forms.DialogResult.Yes)
{
comPortT.Write("sonar on\r");
System.Threading.Thread.Sleep(100);
}
dr = MessageBox.Show("Do you have a Compass sensor attached?", "Compass Sensor", MessageBoxButtons.YesNo);
if (dr == System.Windows.Forms.DialogResult.Yes)
{
comPortT.Write("compass on\r");
System.Threading.Thread.Sleep(100);
MessageBox.Show("Next a webpage will appear to get your magnetic declination,\nenter it in the box that appears next", "Mag Dec");
try
{
//System.Diagnostics.Process.Start("http://www.ngdc.noaa.gov/geomagmodels/Declination.jsp");
System.Diagnostics.Process.Start("http://www.magnetic-declination.com/");
}
catch { MessageBox.Show("Webpage open failed... do you have a virus?\nhttp://www.magnetic-declination.com/"); }
//This can be taken from
try
{
string declination = "0";
Common.InputBox("Declination", "Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3", ref declination);
float dec = 0.0f;
float.TryParse(declination, out dec);
float deg = (float)((int)dec);
float mins = (dec - deg);
if (dec > 0)
{
dec += ((mins) / 60.0f);
}
else
{
dec -= ((mins) / 60.0f);
}
comPortT.Write("exit\rsetup\rdeclination " + dec.ToString("0.00") + "\r");
}
catch { MessageBox.Show("Invalid input!"); }
}
if (currentframe == FRAMETYPES.Y6 || currentframe == FRAMETYPES.Y6)
{
}
else
{
string frame = "+";
Common.InputBox("Frame", "Enter Frame type (options +, x)", ref frame);
System.Text.ASCIIEncoding encoding = new System.Text.ASCIIEncoding();
byte[] data2 = encoding.GetBytes("exit\rsetup\rframe " + frame.ToLower() + "\r");
comPortT.Write(data2, 0, data2.Length);
}
Console.WriteLine(comPortT.ReadExisting());
MessageBox.Show("NOTE: this setup has defaulted all modes to stabilize.\n To change your flight modes, please use the CLI menu via the Terminal tab");
comPortT.Close();
MainV2.givecomport = false;
return;
//step = 4;
}
break;
//
}
}
}
private void APMSetup_Click(object sender, EventArgs e)
{
MainV2.givecomport = true;
MessageBox.Show("Please make sure you are in CLI/Setup mode");
ICommsSerial comPortT = MainV2.comPort.BaseStream;
if (comPortT.IsOpen)
comPortT.Close();
comPortT.DtrEnable = true;
if (MainV2.comportname == null)
{
MessageBox.Show("Please select a valid comport! look in the Options menu");
MainV2.givecomport = false;
return;
}
try
{
comPortT.Open();
}
catch (Exception ex) { MainV2.givecomport = false; MessageBox.Show("Invalid Comport Settings : " + ex.Message); return; }
lbl_status.Text = "Comport Opened";
this.Refresh();
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
System.Threading.Thread.Sleep(3000);
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
string data = "";
DateTime timeout = DateTime.Now;
///////////////////////// FIX ME////////////////////////////////////////////////////////
int step = 0;
//System.Threading.Thread.Sleep(2000);
//comPortT.Write("CH7\r");
comPortT.ReadTimeout = -1;
while (comPortT.IsOpen)
{
string line;
try
{
line = comPortT.ReadLine();
}
catch
{
try { line = comPortT.ReadExisting(); }
catch { MessageBox.Show("Can not read from serial port - existing"); return; }
}
this.Refresh();
Console.Write(line + "\n");
switch (step)
{
case 0:
if (line.Contains("interactive"))
{
lbl_status.Text = "Erasing EEPROM.. (20 seconds)";
this.Refresh();
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
System.Threading.Thread.Sleep(50);
comPortT.Write("erase\r");
System.Threading.Thread.Sleep(50);
comPortT.Write("y\r");
step = 0;
}
if (line.Contains("done"))
{
lbl_status.Text = "Rebooting APM..";
this.Refresh();
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
System.Threading.Thread.Sleep(3000);
comPortT.DtrEnable = false;
System.Threading.Thread.Sleep(100);
comPortT.DtrEnable = true;
step = 1;
}
break;
case 1:
if (line.Contains("interactive")) // becuase we rebooted
{
lbl_status.Text = "Setup Radio..";
this.Refresh();
System.Threading.Thread.Sleep(1000);
Console.WriteLine(comPortT.ReadExisting());
System.Threading.Thread.Sleep(50);
comPortT.Write("setup\r");
System.Threading.Thread.Sleep(200);
MessageBox.Show("Ensure that your RC transmitter is on, and that you have your ArduPilot battery plugged in or are otherwise powering APM's RC pins (USB power does NOT power the RC receiver)", "Radio Setup");
comPortT.Write("radio\r");
Console.WriteLine(comPortT.ReadExisting());
MessageBox.Show("Move all your radio controls to each extreme. Hit OK when done.", "Radio Setup");
comPortT.Write("\r\r");
step = 2;
}
break;
case 2:
if (data.Contains("----"))
data = "";
data += line;
if (line.Contains("CH7")) //
{
MessageBox.Show("Here are the detected radio options\nNOTE Channels not connected are displayed as 1500\nNormal values are around 1100 | 1900\nChannel:Min | Max \n" + data, "Radio");
lbl_status.Text = "Clearing Log Dataflash (this may take a minute)";
this.Refresh();
System.Threading.Thread.Sleep(50);
comPortT.Write("exit\rlogs\rerase\r");
System.Threading.Thread.Sleep(200);
Console.WriteLine(comPortT.ReadExisting());
step = 3;
}
break;
case 3:
if (line.Contains("Log erased"))
{
lbl_status.Text = "Setup Options";
this.Refresh();
Console.WriteLine(comPortT.ReadExisting());
System.Threading.Thread.Sleep(50);
comPortT.Write("exit\rsetup\r");
DialogResult dr;
dr = MessageBox.Show("Do you have a Compass sensor attached?", "Compass Sensor", MessageBoxButtons.YesNo);
if (dr == System.Windows.Forms.DialogResult.Yes)
{
comPortT.Write("compass on\r");
System.Threading.Thread.Sleep(100);
MessageBox.Show("Next a webpage will appear to get your magnetic declination,\nenter it in the box that appears next", "Mag Dec");
try
{
//System.Diagnostics.Process.Start("http://www.ngdc.noaa.gov/geomagmodels/Declination.jsp");
System.Diagnostics.Process.Start("http://www.magnetic-declination.com/");
}
catch { MessageBox.Show("Webpage open failed... do you have a virus?\nhttp://www.magnetic-declination.com/"); }
//This can be taken from
string declination = "0";
Common.InputBox("Declination", "Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3", ref declination);
float dec = 0.0f;
float.TryParse(declination, out dec);
float deg = (float)((int)dec);
float mins = (dec - deg);
if (dec > 0)
{
dec += ((mins) / 60.0f);
}
else
{
dec -= ((mins) / 60.0f);
}
comPortT.Write("exit\rsetup\rdeclination " + dec.ToString() + "\r");
}
MessageBox.Show("NOTE: this setup has defaulted all modes to there default.\n As you are new these are the safest.\n To change this option please use the modes option in the CLI");
Console.WriteLine(comPortT.ReadExisting());
comPortT.Close();
MainV2.givecomport = false;
lbl_status.Text = "Setup Done";
this.Refresh();
return;
//step = 4;
}
break;
//
}
}
}
private void BUT_setup_Click(object sender, EventArgs e) private void BUT_setup_Click(object sender, EventArgs e)
{ {
Form temp = new Setup.Setup(); Form temp = new Setup.Setup();

View File

@ -368,7 +368,7 @@ namespace ArdupilotMega.GCSViews
PointLatLng currentloc = new PointLatLng(MainV2.cs.lat, MainV2.cs.lng); PointLatLng currentloc = new PointLatLng(MainV2.cs.lat, MainV2.cs.lng);
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega) if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{ {
routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing,MainV2.cs.target_bearing)); routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing,MainV2.cs.target_bearing));
} }

View File

@ -616,16 +616,16 @@ namespace ArdupilotMega.GCSViews
switch (command) switch (command)
{ {
case MAVLink.MAV_CMD.WAYPOINT: case MAVLink.MAV_CMD.WAYPOINT:
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPilotMega) if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
Commands.Columns[1].HeaderText = "N/A"; Commands.Columns[1].HeaderText = "N/A";
break; break;
case MAVLink.MAV_CMD.LAND: case MAVLink.MAV_CMD.LAND:
Commands.Columns[1].HeaderText = "N/A"; Commands.Columns[1].HeaderText = "N/A";
if (MainV2.APMFirmware != MainV2.Firmwares.ArduPilotMega) if (MainV2.APMFirmware != MainV2.Firmwares.ArduPlane)
Commands.Columns[2].HeaderText = "N/A"; Commands.Columns[2].HeaderText = "N/A";
break; break;
case MAVLink.MAV_CMD.TAKEOFF: case MAVLink.MAV_CMD.TAKEOFF:
if (MainV2.APMFirmware != MainV2.Firmwares.ArduPilotMega) if (MainV2.APMFirmware != MainV2.Firmwares.ArduPlane)
Commands.Columns[1].HeaderText = "N/A"; Commands.Columns[1].HeaderText = "N/A";
break; break;
} }
@ -1248,11 +1248,13 @@ namespace ArdupilotMega.GCSViews
} }
catch (Exception ex) { MessageBox.Show("Error : " + ex.ToString()); } catch (Exception ex) { MessageBox.Show("Error : " + ex.ToString()); }
MainV2.givecomport = false;
try try
{ {
this.BeginInvoke((System.Threading.ThreadStart)delegate() this.BeginInvoke((System.Threading.ThreadStart)delegate()
{ {
MainV2.givecomport = false;
BUT_write.Enabled = true; BUT_write.Enabled = true;
}); });
} }

View File

@ -167,9 +167,12 @@ System.ComponentModel.Category("Values")]
if (this.DesignMode) if (this.DesignMode)
return; return;
try
{
GraphicsMode test = this.GraphicsMode; GraphicsMode test = this.GraphicsMode;
Console.WriteLine(test.ToString()); Console.WriteLine(test.ToString());
Console.WriteLine("Vendor: "+GL.GetString(StringName.Vendor)); Console.WriteLine("Vendor: " + GL.GetString(StringName.Vendor));
Console.WriteLine("Version: " + GL.GetString(StringName.Version)); Console.WriteLine("Version: " + GL.GetString(StringName.Version));
Console.WriteLine("Device: " + GL.GetString(StringName.Renderer)); Console.WriteLine("Device: " + GL.GetString(StringName.Renderer));
//Console.WriteLine("Extensions: " + GL.GetString(StringName.Extensions)); //Console.WriteLine("Extensions: " + GL.GetString(StringName.Extensions));
@ -190,6 +193,9 @@ System.ComponentModel.Category("Values")]
GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha); GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha);
GL.Enable(EnableCap.Blend); GL.Enable(EnableCap.Blend);
}
catch (Exception ex) { Console.WriteLine("HUD opengl onload "+ex.ToString()); }
try try
{ {
GL.Hint(HintTarget.PerspectiveCorrectionHint, HintMode.Nicest); GL.Hint(HintTarget.PerspectiveCorrectionHint, HintMode.Nicest);

View File

@ -38,8 +38,6 @@ namespace ArdupilotMega
openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "logs"; openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "logs";
Common.getFilefromNet("url", Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "dataflashlog.xml");
if (openFileDialog1.ShowDialog() == DialogResult.OK) if (openFileDialog1.ShowDialog() == DialogResult.OK)
{ {
try try
@ -156,7 +154,7 @@ namespace ArdupilotMega
{ {
reader.Read(); reader.Read();
reader.ReadStartElement("LOGFORMAT"); reader.ReadStartElement("LOGFORMAT");
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPilotMega) if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
{ {
reader.ReadToFollowing("APM"); reader.ReadToFollowing("APM");
} }

View File

@ -1021,7 +1021,7 @@ namespace ArdupilotMega
break; break;
case (byte)MAV_CMD.LOITER_TIME: case (byte)MAV_CMD.LOITER_TIME:
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPilotMega) if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
{ {
loc.p1 = (byte)(wp.param1 / 10); // APM loiter time is in ten second increments loc.p1 = (byte)(wp.param1 / 10); // APM loiter time is in ten second increments
} }

View File

@ -36,7 +36,7 @@ namespace ArdupilotMega
public static string comportname = ""; public static string comportname = "";
public static Hashtable config = new Hashtable(); public static Hashtable config = new Hashtable();
public static bool givecomport = false; public static bool givecomport = false;
public static Firmwares APMFirmware = Firmwares.ArduPilotMega; public static Firmwares APMFirmware = Firmwares.ArduPlane;
public static bool MAC = false; public static bool MAC = false;
public static bool speechenable = false; public static bool speechenable = false;
@ -60,7 +60,7 @@ namespace ArdupilotMega
public enum Firmwares public enum Firmwares
{ {
ArduPilotMega, ArduPlane,
ArduCopter2, ArduCopter2,
} }
@ -595,7 +595,7 @@ namespace ArdupilotMega
} }
else if (float.Parse(comPort.param["SYSID_SW_TYPE"].ToString()) == 0) else if (float.Parse(comPort.param["SYSID_SW_TYPE"].ToString()) == 0)
{ {
TOOL_APMFirmware.SelectedIndex = TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduPilotMega); TOOL_APMFirmware.SelectedIndex = TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduPlane);
} }
} }
@ -1224,7 +1224,7 @@ namespace ArdupilotMega
{ {
try try
{ {
string baseurl = "http://ardupilot-mega.googlecode.com/svn/Tools/trunk/ArdupilotMegaPlanner/bin/Release/"; string baseurl = "http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/";
bool update = updatecheck(loadinglabel, baseurl, ""); bool update = updatecheck(loadinglabel, baseurl, "");
System.Diagnostics.Process P = new System.Diagnostics.Process(); System.Diagnostics.Process P = new System.Diagnostics.Process();
if (MAC) if (MAC)
@ -1266,6 +1266,7 @@ namespace ArdupilotMega
List<string> files = new List<string>(); List<string> files = new List<string>();
// Create a request using a URL that can receive a post. // Create a request using a URL that can receive a post.
Console.WriteLine(baseurl);
WebRequest request = WebRequest.Create(baseurl); WebRequest request = WebRequest.Create(baseurl);
request.Timeout = 10000; request.Timeout = 10000;
// Set the Method property of the request to POST. // Set the Method property of the request to POST.
@ -1308,6 +1309,10 @@ namespace ArdupilotMega
Directory.CreateDirectory(dir); Directory.CreateDirectory(dir);
foreach (string file in files) foreach (string file in files)
{ {
if (file.Equals("/"))
{
continue;
}
if (file.EndsWith("/")) if (file.EndsWith("/"))
{ {
update = updatecheck(loadinglabel, baseurl + file, file) && update; update = updatecheck(loadinglabel, baseurl + file, file) && update;
@ -1336,10 +1341,10 @@ namespace ArdupilotMega
{ {
FileInfo fi = new FileInfo(path); FileInfo fi = new FileInfo(path);
if (fi.Length != response.ContentLength || fi.LastWriteTimeUtc < DateTime.Parse(response.Headers["Last-Modified"].ToString())) if (fi.Length != response.ContentLength)
{ {
getfile = true; getfile = true;
Console.WriteLine("NEW FILE " + file + " " + fi.LastWriteTime + " < " + DateTime.Parse(response.Headers["Last-Modified"].ToString())); Console.WriteLine("NEW FILE " + file);
} }
} }
else else
@ -1390,7 +1395,9 @@ namespace ArdupilotMega
DateTime dt = DateTime.Now; DateTime dt = DateTime.Now;
while (dataStream.CanRead && bytes > 0) dataStream.ReadTimeout = 30000;
while (dataStream.CanRead)
{ {
Application.DoEvents(); Application.DoEvents();
try try
@ -1398,13 +1405,15 @@ namespace ArdupilotMega
if (dt.Second != DateTime.Now.Second) if (dt.Second != DateTime.Now.Second)
{ {
if (loadinglabel != null) if (loadinglabel != null)
loadinglabel.Text = "Getting " + file + ":" + (((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%"; loadinglabel.Text = "Getting " + file + ": " + Math.Abs(bytes) + " bytes";//(((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%";
dt = DateTime.Now; dt = DateTime.Now;
} }
} }
catch { } catch { }
Console.WriteLine(file + " " + bytes); Console.WriteLine(file + " " + bytes);
int len = dataStream.Read(buf1, 0, 1024); int len = dataStream.Read(buf1, 0, 1024);
if (len == 0)
break;
bytes -= len; bytes -= len;
fs.Write(buf1, 0, len); fs.Write(buf1, 0, len);
} }

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

View File

@ -48,7 +48,7 @@ namespace ArdupilotMega.Setup
float pwm = 0; float pwm = 0;
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega) // APM if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
{ {
pwm = MainV2.cs.ch8in; pwm = MainV2.cs.ch8in;
LBL_flightmodepwm.Text = "8: " + MainV2.cs.ch8in.ToString(); LBL_flightmodepwm.Text = "8: " + MainV2.cs.ch8in.ToString();
@ -251,7 +251,7 @@ namespace ArdupilotMega.Setup
{ {
if (tabControl1.SelectedTab == tabModes) if (tabControl1.SelectedTab == tabModes)
{ {
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega) // APM if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
{ {
CMB_fmode1.Items.Clear(); CMB_fmode1.Items.Clear();
CMB_fmode2.Items.Clear(); CMB_fmode2.Items.Clear();
@ -339,7 +339,7 @@ namespace ArdupilotMega.Setup
if (tabControl1.SelectedTab == tabArducopter) if (tabControl1.SelectedTab == tabArducopter)
{ {
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega) if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{ {
tabArducopter.Enabled = false; tabArducopter.Enabled = false;
return; return;
@ -394,7 +394,7 @@ namespace ArdupilotMega.Setup
{ {
try try
{ {
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPilotMega) // APM if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
{ {
MainV2.comPort.setParam("FLTMODE1", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode1.Text)); MainV2.comPort.setParam("FLTMODE1", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode1.Text));
MainV2.comPort.setParam("FLTMODE2", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode2.Text)); MainV2.comPort.setParam("FLTMODE2", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode2.Text));

View File

@ -0,0 +1,3 @@
*.pdb
*.xml