APM Planner 1.0.68

bug fix
test srtm
This commit is contained in:
Michael Oborne 2011-09-14 21:31:00 +08:00
parent c2d20808ec
commit b965da89d1
15 changed files with 137 additions and 69 deletions

View File

@ -232,7 +232,6 @@
<Compile Include="MyUserControl.cs"> <Compile Include="MyUserControl.cs">
<SubType>UserControl</SubType> <SubType>UserControl</SubType>
</Compile> </Compile>
<Compile Include="NetSerialServer.cs" />
<Compile Include="ArduinoSTKv2.cs"> <Compile Include="ArduinoSTKv2.cs">
<SubType>Component</SubType> <SubType>Component</SubType>
</Compile> </Compile>
@ -302,7 +301,6 @@
<DependentUpon>ElevationProfile.cs</DependentUpon> <DependentUpon>ElevationProfile.cs</DependentUpon>
</Compile> </Compile>
<Compile Include="MAVLink.cs" /> <Compile Include="MAVLink.cs" />
<Compile Include="NetSerial.cs" />
<Compile Include="ArduinoSTK.cs"> <Compile Include="ArduinoSTK.cs">
<SubType>Component</SubType> <SubType>Component</SubType>
</Compile> </Compile>
@ -338,6 +336,7 @@
<Compile Include="Splash.Designer.cs"> <Compile Include="Splash.Designer.cs">
<DependentUpon>Splash.cs</DependentUpon> <DependentUpon>Splash.cs</DependentUpon>
</Compile> </Compile>
<Compile Include="srtm.cs" />
<Compile Include="temp.cs"> <Compile Include="temp.cs">
<SubType>Form</SubType> <SubType>Form</SubType>
</Compile> </Compile>
@ -374,6 +373,7 @@
</EmbeddedResource> </EmbeddedResource>
<EmbeddedResource Include="GCSViews\Firmware.zh-Hans.resx"> <EmbeddedResource Include="GCSViews\Firmware.zh-Hans.resx">
<DependentUpon>Firmware.cs</DependentUpon> <DependentUpon>Firmware.cs</DependentUpon>
<SubType>Designer</SubType>
</EmbeddedResource> </EmbeddedResource>
<EmbeddedResource Include="GCSViews\FlightData.zh-Hans.resx"> <EmbeddedResource Include="GCSViews\FlightData.zh-Hans.resx">
<DependentUpon>FlightData.cs</DependentUpon> <DependentUpon>FlightData.cs</DependentUpon>
@ -424,6 +424,7 @@
<EmbeddedResource Include="GCSViews\Firmware.resx"> <EmbeddedResource Include="GCSViews\Firmware.resx">
<DependentUpon>Firmware.cs</DependentUpon> <DependentUpon>Firmware.cs</DependentUpon>
<CopyToOutputDirectory>Always</CopyToOutputDirectory> <CopyToOutputDirectory>Always</CopyToOutputDirectory>
<SubType>Designer</SubType>
</EmbeddedResource> </EmbeddedResource>
<EmbeddedResource Include="GCSViews\FlightData.resx"> <EmbeddedResource Include="GCSViews\FlightData.resx">
<DependentUpon>FlightData.cs</DependentUpon> <DependentUpon>FlightData.cs</DependentUpon>

View File

@ -6,7 +6,6 @@ using System.IO.Ports;
using System.Threading; using System.Threading;
using System.Net; // dns, ip address using System.Net; // dns, ip address
using System.Net.Sockets; // tcplistner using System.Net.Sockets; // tcplistner
using SerialProxy;
namespace System.IO.Ports namespace System.IO.Ports
{ {

View File

@ -257,6 +257,8 @@ namespace ArdupilotMega.GCSViews
internal void processToScreen() internal void processToScreen()
{ {
Params.Rows.Clear(); Params.Rows.Clear();
// process hashdefines and update display // process hashdefines and update display
@ -541,7 +543,10 @@ namespace ArdupilotMega.GCSViews
private void BUT_writePIDS_Click(object sender, EventArgs e) private void BUT_writePIDS_Click(object sender, EventArgs e)
{ {
foreach (string value in changes.Keys)
Hashtable temp = (Hashtable)changes.Clone();
foreach (string value in temp.Keys)
{ {
try try
{ {
@ -566,6 +571,7 @@ namespace ArdupilotMega.GCSViews
if (row.Cells[0].Value.ToString() == value) if (row.Cells[0].Value.ToString() == value)
{ {
row.Cells[1].Style.BackColor = Color.FromArgb(0x43, 0x44, 0x45); row.Cells[1].Style.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
changes.Remove(value);
break; break;
} }
} }
@ -575,8 +581,6 @@ namespace ArdupilotMega.GCSViews
} }
catch { MessageBox.Show("Set " + value + " Failed"); } catch { MessageBox.Show("Set " + value + " Failed"); }
} }
changes.Clear();
} }
const float rad2deg = (float)(180 / Math.PI); const float rad2deg = (float)(180 / Math.PI);
@ -600,9 +604,11 @@ namespace ArdupilotMega.GCSViews
MainV2.fixtheme(temp); MainV2.fixtheme(temp);
TabSetup.Controls.Clear(); temp.ShowDialog();
TabSetup.Controls.Add(temp.Controls[0]); startup = true;
processToScreen();
startup = false;
} }
} }
} }

View File

@ -519,13 +519,18 @@ namespace ArdupilotMega.GCSViews
} }
catch (Exception ex) { lbl_status.Text = "Failed download"; MessageBox.Show("Failed to download new firmware : " + ex.Message); return; } catch (Exception ex) { lbl_status.Text = "Failed download"; MessageBox.Show("Failed to download new firmware : " + ex.Message); return; }
UploadFlash(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"firmware.hex", board);
}
void UploadFlash(string filename, string board)
{
byte[] FLASH = new byte[1]; byte[] FLASH = new byte[1];
StreamReader sr = null; StreamReader sr = null;
try try
{ {
lbl_status.Text = "Reading Hex File"; lbl_status.Text = "Reading Hex File";
this.Refresh(); this.Refresh();
sr = new StreamReader(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"firmware.hex"); sr = new StreamReader(filename);
FLASH = readIntelHEXv2(sr); FLASH = readIntelHEXv2(sr);
sr.Close(); sr.Close();
Console.WriteLine("\n\nSize: {0}\n\n", FLASH.Length); Console.WriteLine("\n\nSize: {0}\n\n", FLASH.Length);

View File

@ -343,16 +343,16 @@
<value>NoControl</value> <value>NoControl</value>
</data> </data>
<data name="label1.Location" type="System.Drawing.Point, System.Drawing"> <data name="label1.Location" type="System.Drawing.Point, System.Drawing">
<value>101, 165</value> <value>113, 167</value>
</data> </data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing"> <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value> <value>56, 13</value>
</data> </data>
<data name="label1.TabIndex" type="System.Int32, mscorlib"> <data name="label1.TabIndex" type="System.Int32, mscorlib">
<value>8</value> <value>8</value>
</data> </data>
<data name="label1.Text" xml:space="preserve"> <data name="label1.Text" xml:space="preserve">
<value>ArduPilot Mega</value> <value>ArduPlane</value>
</data> </data>
<data name="&gt;&gt;label1.Name" xml:space="preserve"> <data name="&gt;&gt;label1.Name" xml:space="preserve">
<value>label1</value> <value>label1</value>
@ -403,16 +403,16 @@
<value>NoControl</value> <value>NoControl</value>
</data> </data>
<data name="label3.Location" type="System.Drawing.Point, System.Drawing"> <data name="label3.Location" type="System.Drawing.Point, System.Drawing">
<value>57, 362</value> <value>74, 361</value>
</data> </data>
<data name="label3.Size" type="System.Drawing.Size, System.Drawing"> <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
<value>168, 13</value> <value>142, 13</value>
</data> </data>
<data name="label3.TabIndex" type="System.Int32, mscorlib"> <data name="label3.TabIndex" type="System.Int32, mscorlib">
<value>10</value> <value>10</value>
</data> </data>
<data name="label3.Text" xml:space="preserve"> <data name="label3.Text" xml:space="preserve">
<value>ArduPilot Mega (Xplane simulator)</value> <value>ArduPlane (Xplane simulator)</value>
</data> </data>
<data name="&gt;&gt;label3.Name" xml:space="preserve"> <data name="&gt;&gt;label3.Name" xml:space="preserve">
<value>label3</value> <value>label3</value>

View File

@ -347,7 +347,7 @@ namespace ArdupilotMega.GCSViews
{ {
TXT_mouselat.Text = lat.ToString(); TXT_mouselat.Text = lat.ToString();
TXT_mouselong.Text = lng.ToString(); TXT_mouselong.Text = lng.ToString();
TXT_mousealt.Text = alt.ToString(); TXT_mousealt.Text = srtm.getAltitude(lat, lng).ToString("0");
try try
{ {

View File

@ -236,7 +236,7 @@ System.ComponentModel.Category("Values")]
{ {
//Console.WriteLine("ms "+(DateTime.Now - starttime).TotalMilliseconds); //Console.WriteLine("ms "+(DateTime.Now - starttime).TotalMilliseconds);
//e.Graphics.DrawImageUnscaled(objBitmap, 0, 0); //e.Graphics.DrawImageUnscaled(objBitmap, 0, 0);
return; //return;
} }
starttime = DateTime.Now; starttime = DateTime.Now;
@ -1365,6 +1365,18 @@ System.ComponentModel.Category("Values")]
charbitmaps = new Bitmap[charbitmaps.Length]; charbitmaps = new Bitmap[charbitmaps.Length];
try
{
foreach (int texid in charbitmaptexid)
{
if (texid != 0)
GL.DeleteTexture(texid);
}
}
catch { }
GC.Collect(); GC.Collect();
try try

View File

@ -366,45 +366,6 @@ namespace ArdupilotMega
} }
} }
private byte[] readline(NetSerial comport)
{
byte[] temp = new byte[1024];
int count = 0;
int timeout = 0;
while (timeout <= 100)
{
if (!comport.IsOpen) { break; }
if (comport.BytesToRead > 0)
{
byte letter = (byte)comport.ReadByte();
temp[count] = letter;
if (letter == '\n') // normal line
{
break;
}
count++;
if (count == temp.Length)
break;
timeout = 0;
} else {
timeout++;
System.Threading.Thread.Sleep(5);
}
}
if (timeout >= 100) {
Console.WriteLine("readline timeout");
}
Array.Resize<byte>(ref temp, count + 1);
return temp;
}
List<string> modelist = new List<string>(); List<string> modelist = new List<string>();
List<Core.Geometry.Point3D>[] position = new List<Core.Geometry.Point3D>[200]; List<Core.Geometry.Point3D>[] position = new List<Core.Geometry.Point3D>[200];
int positionindex = 0; int positionindex = 0;

View File

@ -951,6 +951,8 @@ namespace ArdupilotMega
req.seq = index; req.seq = index;
//Console.WriteLine("getwp req "+ DateTime.Now.Millisecond);
// request // request
generatePacket(MAVLINK_MSG_ID_WAYPOINT_REQUEST, req); generatePacket(MAVLINK_MSG_ID_WAYPOINT_REQUEST, req);
@ -972,11 +974,14 @@ namespace ArdupilotMega
MainV2.givecomport = false; MainV2.givecomport = false;
throw new Exception("Timeout on read - getWP"); throw new Exception("Timeout on read - getWP");
} }
//Console.WriteLine("getwp read " + DateTime.Now.Millisecond);
byte[] buffer = readPacket(); byte[] buffer = readPacket();
//Console.WriteLine("getwp readend " + DateTime.Now.Millisecond);
if (buffer.Length > 5) if (buffer.Length > 5)
{ {
if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT) if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT)
{ {
//Console.WriteLine("getwp ans " + DateTime.Now.Millisecond);
__mavlink_waypoint_t wp = new __mavlink_waypoint_t(); __mavlink_waypoint_t wp = new __mavlink_waypoint_t();
object temp = (object)wp; object temp = (object)wp;
@ -1070,7 +1075,7 @@ namespace ArdupilotMega
} }
else else
{ {
//Console.WriteLine(DateTime.Now + " PC getwp " + buffer[5]); Console.WriteLine(DateTime.Now + " PC getwp " + buffer[5]);
} }
} }
} }
@ -1455,16 +1460,18 @@ namespace ArdupilotMega
else else
{ {
int to = 0; int to = 0;
while (BaseStream.BytesToRead < length) while (BaseStream.BytesToRead < (length - 4))
{ {
if (to > 1000) if (to > 1000)
{ {
Console.WriteLine("MAVLINK: wait time out btr {0} len {1}", BaseStream.BytesToRead, length); Console.WriteLine("MAVLINK: wait time out btr {0} len {1}", BaseStream.BytesToRead, length);
break; break;
} }
System.Threading.Thread.Sleep(2); System.Threading.Thread.Sleep(1);
System.Windows.Forms.Application.DoEvents(); //System.Windows.Forms.Application.DoEvents();
to++; to++;
//Console.WriteLine("data " + 0 + " " + length + " aval " + BaseStream.BytesToRead);
} }
int read = BaseStream.Read(temp, 6, length - 4); int read = BaseStream.Read(temp, 6, length - 4);
} }

View File

@ -76,6 +76,8 @@ namespace ArdupilotMega
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US"); //System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US"); //System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
srtm.datadirectory = @"C:\srtm";
var t = Type.GetType("Mono.Runtime"); var t = Type.GetType("Mono.Runtime");
MAC = (t != null); MAC = (t != null);

View File

@ -50,7 +50,7 @@ namespace ArdupilotMega
if (!this.Enabled) if (!this.Enabled)
{ {
SolidBrush brush = new SolidBrush(Color.FromArgb(200, 0x2b, 0x3a, 0x03)); SolidBrush brush = new SolidBrush(Color.FromArgb(150, 0x2b, 0x3a, 0x03));
gr.FillRectangle(brush, 0, 0, this.Width, this.Height); gr.FillRectangle(brush, 0, 0, this.Width, this.Height);
} }

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

View File

@ -231,7 +231,6 @@ namespace ArdupilotMega.Setup
MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, oldrc); MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, oldrc);
MainV2.comPort.param = MainV2.comPort.getParamList();
if (Configuration != null) if (Configuration != null)
{ {
Configuration.startup = true; Configuration.startup = true;

View File

@ -343,16 +343,16 @@
<value>NoControl</value> <value>NoControl</value>
</data> </data>
<data name="label1.Location" type="System.Drawing.Point, System.Drawing"> <data name="label1.Location" type="System.Drawing.Point, System.Drawing">
<value>101, 165</value> <value>113, 167</value>
</data> </data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing"> <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>79, 13</value> <value>56, 13</value>
</data> </data>
<data name="label1.TabIndex" type="System.Int32, mscorlib"> <data name="label1.TabIndex" type="System.Int32, mscorlib">
<value>8</value> <value>8</value>
</data> </data>
<data name="label1.Text" xml:space="preserve"> <data name="label1.Text" xml:space="preserve">
<value>ArduPilot Mega</value> <value>ArduPlane</value>
</data> </data>
<data name="&gt;&gt;label1.Name" xml:space="preserve"> <data name="&gt;&gt;label1.Name" xml:space="preserve">
<value>label1</value> <value>label1</value>
@ -403,16 +403,16 @@
<value>NoControl</value> <value>NoControl</value>
</data> </data>
<data name="label3.Location" type="System.Drawing.Point, System.Drawing"> <data name="label3.Location" type="System.Drawing.Point, System.Drawing">
<value>57, 362</value> <value>74, 361</value>
</data> </data>
<data name="label3.Size" type="System.Drawing.Size, System.Drawing"> <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
<value>168, 13</value> <value>142, 13</value>
</data> </data>
<data name="label3.TabIndex" type="System.Int32, mscorlib"> <data name="label3.TabIndex" type="System.Int32, mscorlib">
<value>10</value> <value>10</value>
</data> </data>
<data name="label3.Text" xml:space="preserve"> <data name="label3.Text" xml:space="preserve">
<value>ArduPilot Mega (Xplane simulator)</value> <value>ArduPlane (Xplane simulator)</value>
</data> </data>
<data name="&gt;&gt;label3.Name" xml:space="preserve"> <data name="&gt;&gt;label3.Name" xml:space="preserve">
<value>label3</value> <value>label3</value>

View File

@ -0,0 +1,76 @@
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using System.IO;
namespace ArdupilotMega
{
class srtm
{
public static string datadirectory;
public static int getAltitude(double lat, double lng)
{
short alt = -32768;
lat += 0.0008;
//lng += 0.0008;
int x = (int)Math.Floor(lng);
int y = (int)Math.Floor(lat);
string ns;
if (y > 0)
ns = "N";
else
ns = "S";
string ew;
if (x > 0)
ew = "E";
else
ew = "W";
string filename = ns+ Math.Abs(y).ToString("00")+ew+ Math.Abs(x).ToString("000")+".hgt";
if (!File.Exists(datadirectory + Path.DirectorySeparatorChar + filename))
{
return alt;
}
FileStream fs = new FileStream(datadirectory + Path.DirectorySeparatorChar + filename, FileMode.Open,FileAccess.Read);
float posx = 0;
float row = 0;
if (fs.Length <= (1201 * 1201 * 2)) {
posx = (int)(((float)(lng - x)) * (1201 * 2));
row = (int)(((float)(lat - y)) * 1201) * (1201 * 2);
row = (1201 * 1201 * 2) - row;
} else {
posx = (int)(((float)(lng - x)) * (3601 * 2));
row = (int)(((float)(lat - y)) * 3601) * (3601 * 2);
row = (3601 * 3601 * 2) - row;
}
if (posx % 2 == 1)
{
posx--;
}
//Console.WriteLine(filename + " row " + row + " posx" + posx);
byte[] data = new byte[2];
fs.Seek((int)(row + posx), SeekOrigin.Begin);
fs.Read(data, 0, data.Length);
Array.Reverse(data);
alt = BitConverter.ToInt16(data,0);
return alt;
}
}
}