APM Planner 1.1.2

fix kml overlay
add jsbsim as simulator
generate gpx on log kml create
make georefrenceimage accessable (control-f)
This commit is contained in:
Michael Oborne 2011-12-09 11:27:19 +08:00
parent ced26d7ba2
commit 297ecbec1f
19 changed files with 1375 additions and 641 deletions

View File

@ -172,15 +172,6 @@
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.ExtensionAttribute.dll</HintPath>
</Reference>
<Reference Include="OpenGlobe.Core">
<HintPath>..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\Source\Examples\Chapter13\ClipmapTerrainOnGlobe\bin\Debug\OpenGlobe.Core.dll</HintPath>
</Reference>
<Reference Include="OpenGlobe.Renderer">
<HintPath>..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\Source\Examples\Chapter13\ClipmapTerrainOnGlobe\bin\Debug\OpenGlobe.Renderer.dll</HintPath>
</Reference>
<Reference Include="OpenGlobe.Scene">
<HintPath>..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\Source\Examples\Chapter13\ClipmapTerrainOnGlobe\bin\Debug\OpenGlobe.Scene.dll</HintPath>
</Reference>
<Reference Include="OpenTK, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\ThirdParty\OpenTKGL4\Binaries\OpenTK\Release\OpenTK.dll</HintPath>
@ -237,7 +228,9 @@
<Compile Include="ResEdit.Designer.cs">
<DependentUpon>ResEdit.cs</DependentUpon>
</Compile>
<Compile Include="georefimage.cs" />
<Compile Include="georefimage.cs">
<SubType>Form</SubType>
</Compile>
<Compile Include="HIL\Aircraft.cs" />
<Compile Include="HIL\Point3d.cs" />
<Compile Include="HIL\QuadCopter.cs" />
@ -403,6 +396,9 @@
<EmbeddedResource Include="Camera.resx">
<DependentUpon>Camera.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="georefimage.resx">
<DependentUpon>georefimage.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="ResEdit.resx">
<DependentUpon>ResEdit.cs</DependentUpon>
</EmbeddedResource>
@ -576,6 +572,9 @@
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
<SubType>Designer</SubType>
</Content>
<Content Include="JSBSim.exe">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</Content>
<Content Include="mavcmd.xml">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</Content>

View File

@ -19,6 +19,7 @@ using System.Reflection;
using System.ComponentModel;
using System.Threading;
using SharpKml.Base;
using SharpKml.Dom;
@ -658,19 +659,65 @@ namespace ArdupilotMega.GCSViews
void parser_ElementAdded(object sender, SharpKml.Base.ElementEventArgs e)
{
processKML(e.Element);
}
SharpKml.Dom.Polygon polygon = e.Element as SharpKml.Dom.Polygon;
if (polygon != null)
private void processKML(SharpKml.Dom.Element Element)
{
try
{
Console.WriteLine(Element.ToString() + " " + Element.Parent);
}
catch { }
SharpKml.Dom.Document doc = Element as SharpKml.Dom.Document;
SharpKml.Dom.Placemark pm = Element as SharpKml.Dom.Placemark;
SharpKml.Dom.Folder folder = Element as SharpKml.Dom.Folder;
SharpKml.Dom.Polygon polygon = Element as SharpKml.Dom.Polygon;
SharpKml.Dom.LineString ls = Element as SharpKml.Dom.LineString;
if (doc != null)
{
foreach (var feat in doc.Features)
{
GMapPolygon kmlpolygon = new GMapPolygon(new List<PointLatLng>(), "kmlpolygon");
foreach (var loc in polygon.OuterBoundary.LinearRing.Coordinates)
{
kmlpolygon.Points.Add(new PointLatLng(loc.Latitude,loc.Longitude));
}
kmlpolygons.Polygons.Add(kmlpolygon);
//Console.WriteLine("feat " + feat.GetType());
//processKML((Element)feat);
}
} else
if (folder != null )
{
foreach (Feature feat in folder.Features)
{
//Console.WriteLine("feat "+feat.GetType());
//processKML(feat);
}
}
else if (pm != null)
{
}
else if (polygon != null)
{
GMapPolygon kmlpolygon = new GMapPolygon(new List<PointLatLng>(), "kmlpolygon");
foreach (var loc in polygon.OuterBoundary.LinearRing.Coordinates)
{
kmlpolygon.Points.Add(new PointLatLng(loc.Latitude, loc.Longitude));
}
kmlpolygons.Polygons.Add(kmlpolygon);
}
else if (ls != null)
{
GMapRoute kmlroute = new GMapRoute(new List<PointLatLng>(), "kmlroute");
foreach (var loc in ls.Coordinates)
{
kmlroute.Points.Add(new PointLatLng(loc.Latitude, loc.Longitude));
}
kmlpolygons.Routes.Add(kmlroute);
}
}
private void ChangeColumnHeader(string command)
@ -2792,9 +2839,9 @@ namespace ArdupilotMega.GCSViews
// 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.Location = new System.Drawing.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);
label11.Location = new System.Drawing.Point(panelMap.Size.Width - 50, label11.Location.Y);
}
private void BUT_zoomto_Click(object sender, EventArgs e)
@ -2828,11 +2875,17 @@ namespace ArdupilotMega.GCSViews
try
{
kmlpolygons.Polygons.Clear();
kmlpolygons.Routes.Clear();
string kml = new StreamReader(File.OpenRead(file)).ReadToEnd();
kml = kml.Replace("<Snippet/>", "");
var parser = new SharpKml.Base.Parser();
parser.ElementAdded += new EventHandler<SharpKml.Base.ElementEventArgs>(parser_ElementAdded);
parser.Parse(File.OpenRead(file));
parser.ElementAdded += parser_ElementAdded;
parser.ParseString(kml,true);
}
catch (Exception ex) { MessageBox.Show("Bad KML File :" + ex.ToString()); }
}

View File

@ -112,6 +112,7 @@
this.CHK_heli = new System.Windows.Forms.CheckBox();
this.RAD_aerosimrc = new System.Windows.Forms.RadioButton();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.RAD_JSBSim = new System.Windows.Forms.RadioButton();
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
this.panel1.SuspendLayout();
this.panel2.SuspendLayout();
@ -692,10 +693,19 @@
this.RAD_aerosimrc.UseVisualStyleBackColor = true;
this.RAD_aerosimrc.CheckedChanged += new System.EventHandler(this.RAD_aerosimrc_CheckedChanged);
//
// RAD_JSBSim
//
resources.ApplyResources(this.RAD_JSBSim, "RAD_JSBSim");
this.RAD_JSBSim.Name = "RAD_JSBSim";
this.toolTip1.SetToolTip(this.RAD_JSBSim, resources.GetString("RAD_JSBSim.ToolTip"));
this.RAD_JSBSim.UseVisualStyleBackColor = true;
this.RAD_JSBSim.CheckedChanged += new System.EventHandler(this.RAD_JSBSim_CheckedChanged);
//
// Simulation
//
resources.ApplyResources(this, "$this");
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.Controls.Add(this.RAD_JSBSim);
this.Controls.Add(this.RAD_aerosimrc);
this.Controls.Add(this.CHK_heli);
this.Controls.Add(this.BUT_startxplane);
@ -825,5 +835,6 @@
private System.Windows.Forms.CheckBox CHK_heli;
private System.Windows.Forms.RadioButton RAD_aerosimrc;
private System.Windows.Forms.ToolTip toolTip1;
private System.Windows.Forms.RadioButton RAD_JSBSim;
}
}

View File

@ -22,7 +22,8 @@ namespace ArdupilotMega.GCSViews
UdpClient XplanesSEND;
UdpClient MavLink;
Socket SimulatorRECV;
//TcpClient FlightGearSEND;
TcpClient JSBSimSEND;
UdpClient SITLSEND;
EndPoint Remote = (EndPoint)(new IPEndPoint(IPAddress.Any, 0));
byte[] udpdata = new byte[113 * 9 + 5]; // 113 types - 9 items per type (index+8) + 5 byte header
float[][] DATA = new float[113][];
@ -246,7 +247,22 @@ namespace ArdupilotMega.GCSViews
}
else
{
//SetupTcpFlightGear(); // old style
if (RAD_JSBSim.Checked)
{
System.Diagnostics.ProcessStartInfo _procstartinfo = new System.Diagnostics.ProcessStartInfo();
_procstartinfo.WorkingDirectory = Path.GetDirectoryName(Application.ExecutablePath);
_procstartinfo.Arguments = "--realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=jsbsim/fgout.xml --script=jsbsim/rascal_test.xml";
_procstartinfo.FileName = "JSBSim.exe";
// Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar +
_procstartinfo.UseShellExecute = true;
System.Diagnostics.Process.Start(_procstartinfo);
SITLSEND = new UdpClient(simIP, 5501);
}
SetupTcpJSBSim(); // old style
SetupUDPXplanes(); // fg udp style
SetupUDPMavLink(); // pass traffic - raw
}
@ -560,14 +576,14 @@ namespace ArdupilotMega.GCSViews
if (hzcounttime.Second != DateTime.Now.Second)
{
// Console.WriteLine("SIM hz {0}", hzcount);
//Console.WriteLine("SIM hz {0}", hzcount);
hzcount = 0;
hzcounttime = DateTime.Now;
}
System.Threading.Thread.Sleep(5); // this controls send speed to sim
System.Threading.Thread.Sleep(1); // this controls send speed to sim
}
}
@ -587,7 +603,25 @@ namespace ArdupilotMega.GCSViews
SimulatorRECV.Bind(ipep);
OutputLog.AppendText("Listerning on port " + recvPort + " (sim->planner)\n");
OutputLog.AppendText("Listerning on port UDP " + recvPort + " (sim->planner)\n");
}
private void SetupTcpJSBSim()
{
try
{
JSBSimSEND = new TcpClient();
JSBSimSEND.Client.NoDelay = true;
JSBSimSEND.Connect(simIP, simPort);
OutputLog.AppendText("Sending to port TCP " + simPort + " (planner->sim)\n");
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("info\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set attitude/phi-rad 0\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("set attitude/theta-rad 0\n"));
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("resume\n"));
}
catch { }
}
private void SetupUDPXplanes()
@ -595,7 +629,7 @@ namespace ArdupilotMega.GCSViews
// setup sender
XplanesSEND = new UdpClient(simIP, simPort);
OutputLog.AppendText("Sending to port " + simPort + " (planner->sim)\n");
OutputLog.AppendText("Sending to port UDP " + simPort + " (planner->sim)\n");
}
private void SetupUDPMavLink()
@ -944,7 +978,7 @@ namespace ArdupilotMega.GCSViews
asp.airspeed = ((float)Math.Sqrt((yvec * yvec) + (xvec * xvec)));
}
else if (receviedbytes > 0x100)
else if (receviedbytes == 408)
{
FGNetFDM fdm = new FGNetFDM();
@ -997,7 +1031,7 @@ namespace ArdupilotMega.GCSViews
gps.v = ((float)Math.Sqrt((fdm.v_north * fdm.v_north) + (fdm.v_east * fdm.v_east)) * ft2m);
#endif
asp.airspeed = fdm.vcas * kts2fps * ft2m;
asp.airspeed = fdm.vcas * ft2m;
}
else
{
@ -1080,6 +1114,37 @@ namespace ArdupilotMega.GCSViews
return;
}
if (RAD_JSBSim.Checked && chkSensor.Checked)
{
byte[] sitlout = new byte[16 * 8 + 1 * 4]; // 16 * double + 1 * int
int a = 0;
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.latitude), a, sitlout, a, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.longitude), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.altitude), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.psi), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.v_north), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.v_east), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.A_X_pilot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.A_Y_pilot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.A_Z_pilot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.phidot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.thetadot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.psidot), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.phi), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.theta), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.psi), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.vcas), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((int)0x4c56414e), 0, sitlout, a += 8, 4);
SITLSEND.Send(sitlout, sitlout.Length);
return;
}
#if MAVLINK10
TimeSpan gpsspan = DateTime.Now - lastgpsupdate;
@ -1354,7 +1419,7 @@ namespace ArdupilotMega.GCSViews
updateScreenDisplay(DATA[20][0] * deg2rad, DATA[20][1] * deg2rad, DATA[20][2] * .3048, DATA[18][1] * deg2rad, DATA[18][0] * deg2rad, DATA[19][2] * deg2rad, DATA[18][2] * deg2rad, roll_out, pitch_out, rudder_out, throttle_out);
}
if (RAD_softFlightGear.Checked)
if (RAD_softFlightGear.Checked || RAD_JSBSim.Checked)
{
updateScreenDisplay(lastfdmdata.latitude, lastfdmdata.longitude, lastfdmdata.altitude * .3048, lastfdmdata.phi, lastfdmdata.theta, lastfdmdata.psi, lastfdmdata.psi, roll_out, pitch_out, rudder_out, throttle_out);
}
@ -1392,6 +1457,23 @@ namespace ArdupilotMega.GCSViews
catch { }
}
//JSBSim
if (RAD_JSBSim.Checked)
{
roll_out = Constrain(roll_out * REV_roll, -1f, 1f);
pitch_out = Constrain(-pitch_out * REV_pitch, -1f,1f);
rudder_out = Constrain(rudder_out * REV_rudder, -1f, 1f);
throttle_out = Constrain(throttle_out, -0.0f, 1f);
string cmd = string.Format("set fcs/aileron-cmd-norm {0}\r\nset fcs/elevator-cmd-norm {1}\r\nset fcs/rudder-cmd-norm {2}\r\nset fcs/throttle-cmd-norm {3}\r\n",roll_out,pitch_out,rudder_out,throttle_out);
//Console.Write(cmd);
byte[] data = System.Text.Encoding.ASCII.GetBytes(cmd);
JSBSimSEND.Client.Send(data);
}
// Flightgear
if (RAD_softFlightGear.Checked)
@ -1975,5 +2057,10 @@ namespace ArdupilotMega.GCSViews
RAD_softFlightGear.Checked = false;
}
}
private void RAD_JSBSim_CheckedChanged(object sender, EventArgs e)
{
}
}
}

File diff suppressed because it is too large Load Diff

View File

@ -243,19 +243,26 @@ namespace hud
starttime = DateTime.Now;
if (opengl)
try
{
MakeCurrent();
GL.Clear(ClearBufferMask.ColorBufferBit);
if (opengl)
{
MakeCurrent();
GL.Clear(ClearBufferMask.ColorBufferBit);
}
doPaint(e);
if (opengl)
{
this.SwapBuffers();
}
}
doPaint(e);
if (opengl) {
this.SwapBuffers();
}
catch (Exception ex) { Console.WriteLine(ex.ToString()); }
count++;

View File

@ -41,6 +41,7 @@ namespace ArdupilotMega
public Model model;
public string[] ntun;
public string[] ctun;
public int datetime;
}
enum serialstatus
@ -364,16 +365,24 @@ namespace ArdupilotMega
{
try
{
if (lastpos.X != 0 && oldlastpos != lastpos)
if (lastpos.X != 0 && oldlastpos.X != lastpos.X && oldlastpos.Y != lastpos.Y)
{
Data dat = new Data();
try
{
dat.datetime = int.Parse(lastline.Split(',', ':')[1]);
}
catch { }
runmodel = new Model();
runmodel.Location.longitude = lastpos.X;
runmodel.Location.latitude = lastpos.Y;
runmodel.Location.altitude = lastpos.Z;
oldlastpos = lastpos;
runmodel.Orientation.roll = double.Parse(items[1], new System.Globalization.CultureInfo("en-US")) / -100;
runmodel.Orientation.tilt = double.Parse(items[2], new System.Globalization.CultureInfo("en-US")) / -100;
runmodel.Orientation.heading = double.Parse(items[3], new System.Globalization.CultureInfo("en-US")) / 100;
@ -398,9 +407,51 @@ namespace ArdupilotMega
List<Core.Geometry.Point3D>[] position = new List<Core.Geometry.Point3D>[200];
int positionindex = 0;
private void writeGPX(string filename)
{
System.Xml.XmlTextWriter xw = new System.Xml.XmlTextWriter(Path.GetDirectoryName(filename) + Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(filename) + ".gpx",Encoding.ASCII);
xw.WriteStartElement("gpx");
xw.WriteStartElement("trk");
xw.WriteStartElement("trkseg");
DateTime start = new DateTime(DateTime.Now.Year,DateTime.Now.Month,DateTime.Now.Day,0,0,0);
foreach (Data mod in flightdata)
{
xw.WriteStartElement("trkpt");
xw.WriteAttributeString("lat",mod.model.Location.latitude.ToString());
xw.WriteAttributeString("lon", mod.model.Location.longitude.ToString());
xw.WriteElementString("ele", mod.model.Location.altitude.ToString());
xw.WriteElementString("time", start.AddMilliseconds(mod.datetime).ToString("yyyy-MM-ddTHH:mm:sszzzzzz"));
xw.WriteElementString("course", (mod.model.Orientation.heading).ToString());
xw.WriteElementString("roll", mod.model.Orientation.roll.ToString());
xw.WriteElementString("pitch", mod.model.Orientation.tilt.ToString());
//xw.WriteElementString("speed", mod.model.Orientation.);
//xw.WriteElementString("fix", mod.model.Location.altitude);
xw.WriteEndElement();
}
xw.WriteEndElement();
xw.WriteEndElement();
xw.WriteEndElement();
xw.Close();
}
private void writeKML(string filename)
{
try
{
writeGPX(filename);
}
catch { }
Color[] colours = { Color.Red, Color.Orange, Color.Yellow, Color.Green, Color.Blue, Color.Indigo, Color.Violet, Color.Pink };
AltitudeMode altmode = AltitudeMode.absolute;

View File

@ -81,10 +81,6 @@ namespace ArdupilotMega
public MainV2()
{
//new temp().ShowDialog();
//return;
Form splash = new Splash();
splash.Show();
@ -96,17 +92,8 @@ namespace ArdupilotMega
Application.DoEvents();
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
srtm.datadirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "srtm";
georefimage temp = new georefimage();
//temp.dowork(244 + 60*60*24 * -1 );
//return;
var t = Type.GetType("Mono.Runtime");
MONO = (t != null);

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

View File

@ -2,10 +2,6 @@
<configuration>
<configSections>
</configSections>
<startup>
<supportedRuntime version="v2.0.50727"/>
</startup>
<!--<startup useLegacyV2RuntimeActivationPolicy="true">
<supportedRuntime version="v4.0"/>
</startup>-->
<startup useLegacyV2RuntimeActivationPolicy="true">
</startup>
</configuration>

View File

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

View File

@ -4,14 +4,14 @@
<description asmv2:publisher="Michael Oborne" asmv2:product="ArdupilotMegaPlanner" xmlns="urn:schemas-microsoft-com:asm.v1" />
<deployment install="true" />
<dependency>
<dependentAssembly dependencyType="install" codebase="ArdupilotMegaPlanner.exe.manifest" size="25308">
<dependentAssembly dependencyType="install" codebase="ArdupilotMegaPlanner.exe.manifest" size="23682">
<assemblyIdentity name="ArdupilotMegaPlanner.exe" version="0.0.0.1" publicKeyToken="0000000000000000" language="en-US" processorArchitecture="x86" type="win32" />
<hash>
<dsig:Transforms>
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
</dsig:Transforms>
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
<dsig:DigestValue>mN7pjMOs48ZdF2S8vaEAJbtq8b4=</dsig:DigestValue>
<dsig:DigestValue>+BB2J7z2to1UULmX82O0PxoC594=</dsig:DigestValue>
</hash>
</dependentAssembly>
</dependency>

View File

@ -2,10 +2,6 @@
<configuration>
<configSections>
</configSections>
<startup>
<supportedRuntime version="v2.0.50727"/>
</startup>
<!--<startup useLegacyV2RuntimeActivationPolicy="true">
<supportedRuntime version="v4.0"/>
</startup>-->
<startup useLegacyV2RuntimeActivationPolicy="true">
</startup>
</configuration>

View File

@ -0,0 +1,2 @@
<?xml version="1.0"?>
<output name="localhost" type="FLIGHTGEAR" port="5123" protocol="udp" rate="1000"/>

View File

@ -0,0 +1,33 @@
<?xml version="1.0" encoding="utf-8"?>
<?xml-stylesheet type="text/xsl" href="http://jsbsim.sf.net/JSBSimScript.xsl"?>
<runscript xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:noNamespaceSchemaLocation="http://jsbsim.sf.net/JSBSimScript.xsd"
name="Testing Rascal110">
<description>
test ArduPlane using Rascal110 and JSBSim
</description>
<use aircraft="Rascal" initialize="reset_CMAC"/>
<!-- we control the servos via the jsbsim console
interface on TCP 5124 -->
<input port="5124"/>
<run start="0" end="10000000" dt="0.001">
<property value="0"> simulation/notify-time-trigger </property>
<event name="start engine">
<condition> simulation/sim-time-sec le 0.01 </condition>
<set name="propulsion/engine[0]/set-running" value="1"/>
<notify/>
</event>
<event name="Trim">
<condition>simulation/sim-time-sec ge 0.01</condition>
<set name="simulation/do_simple_trim" value="2"/>
<notify/>
</event>
</run>
</runscript>

View File

@ -5,14 +5,26 @@ using System.Text;
using System.Drawing;
using System.Drawing.Imaging;
using System.IO;
using System.Windows.Forms;
namespace ArdupilotMega
{
class georefimage
class georefimage : Form
{
private OpenFileDialog openFileDialog1;
private MyButton BUT_browselog;
private MyButton BUT_browsedir;
private TextBox TXT_logfile;
private TextBox TXT_jpgdir;
private TextBox TXT_offsetseconds;
private MyButton BUT_doit;
private FolderBrowserDialog folderBrowserDialog1;
private Label label1;
private TextBox TXT_outputlog;
public string logFile = "";
public string dirWithImages = "";
internal georefimage() {
InitializeComponent();
}
DateTime getPhotoTime(string fn)
{
@ -69,18 +81,18 @@ namespace ArdupilotMega
return list;
}
public void dowork(float offsetseconds)
public void dowork(string logFile, string dirWithImages, float offsetseconds)
{
DateTime localmin = DateTime.MaxValue;
DateTime localmax = DateTime.MinValue;
DateTime startTime = DateTime.MinValue;
logFile = @"C:\temp\farm 1-10-2011\100SSCAM\2011-10-01 11-48 1.log";
//logFile = @"C:\Users\hog\Pictures\farm 1-10-2011\100SSCAM\2011-10-01 11-48 1.log";
List<string[]> list = readLog(logFile);
dirWithImages = @"C:\temp\farm 1-10-2011\100SSCAM";
//dirWithImages = @"C:\Users\hog\Pictures\farm 1-10-2011\100SSCAM";
string[] files = Directory.GetFiles(dirWithImages);
@ -91,6 +103,8 @@ namespace ArdupilotMega
sw.WriteLine("#longitude and latitude - in degrees");
sw.WriteLine("#name utc longitude latitude height");
int first = 0;
foreach (string file in files)
{
if (file.ToLower().EndsWith(".jpg"))
@ -112,18 +126,33 @@ namespace ArdupilotMega
}
Console.WriteLine("min " + localmin + " max " + localmax);
TXT_outputlog.AppendText("Log min " + localmin + " max " + localmax + "\r\n");
}
TXT_outputlog.AppendText("Photo " + Path.GetFileNameWithoutExtension(file) + " time " + dt + "\r\n");
foreach (string[] arr in list)
{
Application.DoEvents();
DateTime crap = startTime.AddMilliseconds(int.Parse(arr[1])).AddSeconds(offsetseconds);
if (first == 0)
{
TXT_outputlog.AppendText("Photo " + Path.GetFileNameWithoutExtension(file) + " " + dt + " vs Log " + crap + "\r\n");
TXT_outputlog.AppendText("offset should be about " + (dt -crap).TotalSeconds + "\r\n");
first++;
}
Console.Write("ph " + dt + " log " + crap + " \r");
if (dt.Equals(crap))
{
TXT_outputlog.AppendText("MATCH Photo " + Path.GetFileNameWithoutExtension(file) + " " + dt + "\r\n");
sw2.WriteLine(Path.GetFileNameWithoutExtension(file) + " " + arr[5] + " " + arr[4] + " " + arr[7]);
sw.WriteLine(Path.GetFileNameWithoutExtension(file) + "\t" + crap.ToString("yyyy:MM:dd HH:mm:ss") +"\t"+ arr[5] + "\t" + arr[4] + "\t" + arr[7]);
sw.Flush();
@ -141,6 +170,159 @@ namespace ArdupilotMega
sw2.Close();
sw.Close();
MessageBox.Show("Done");
}
private void InitializeComponent()
{
this.openFileDialog1 = new System.Windows.Forms.OpenFileDialog();
this.BUT_browselog = new ArdupilotMega.MyButton();
this.BUT_browsedir = new ArdupilotMega.MyButton();
this.TXT_logfile = new System.Windows.Forms.TextBox();
this.TXT_jpgdir = new System.Windows.Forms.TextBox();
this.TXT_offsetseconds = new System.Windows.Forms.TextBox();
this.BUT_doit = new ArdupilotMega.MyButton();
this.folderBrowserDialog1 = new System.Windows.Forms.FolderBrowserDialog();
this.TXT_outputlog = new System.Windows.Forms.TextBox();
this.label1 = new System.Windows.Forms.Label();
this.SuspendLayout();
//
// openFileDialog1
//
this.openFileDialog1.FileName = "openFileDialog1";
//
// BUT_browselog
//
this.BUT_browselog.Location = new System.Drawing.Point(351, 12);
this.BUT_browselog.Name = "BUT_browselog";
this.BUT_browselog.Size = new System.Drawing.Size(75, 23);
this.BUT_browselog.TabIndex = 0;
this.BUT_browselog.Text = "Browse Log";
this.BUT_browselog.UseVisualStyleBackColor = true;
this.BUT_browselog.Click += new System.EventHandler(this.BUT_browselog_Click);
//
// BUT_browsedir
//
this.BUT_browsedir.Location = new System.Drawing.Point(351, 41);
this.BUT_browsedir.Name = "BUT_browsedir";
this.BUT_browsedir.Size = new System.Drawing.Size(75, 23);
this.BUT_browsedir.TabIndex = 1;
this.BUT_browsedir.Text = "Browse Directory";
this.BUT_browsedir.UseVisualStyleBackColor = true;
this.BUT_browsedir.Click += new System.EventHandler(this.BUT_browsedir_Click);
//
// TXT_logfile
//
this.TXT_logfile.Location = new System.Drawing.Point(28, 14);
this.TXT_logfile.Name = "TXT_logfile";
this.TXT_logfile.Size = new System.Drawing.Size(317, 20);
this.TXT_logfile.TabIndex = 2;
this.TXT_logfile.Text = "C:\\Users\\hog\\Pictures\\farm 1-10-2011\\100SSCAM\\2011-10-01 11-48 1.log";
//
// TXT_jpgdir
//
this.TXT_jpgdir.Location = new System.Drawing.Point(28, 43);
this.TXT_jpgdir.Name = "TXT_jpgdir";
this.TXT_jpgdir.Size = new System.Drawing.Size(317, 20);
this.TXT_jpgdir.TabIndex = 3;
this.TXT_jpgdir.Text = "C:\\Users\\hog\\Pictures\\farm 1-10-2011\\100SSCAM";
//
// TXT_offsetseconds
//
this.TXT_offsetseconds.Location = new System.Drawing.Point(180, 69);
this.TXT_offsetseconds.Name = "TXT_offsetseconds";
this.TXT_offsetseconds.Size = new System.Drawing.Size(100, 20);
this.TXT_offsetseconds.TabIndex = 4;
this.TXT_offsetseconds.Text = "-86156";
//
// BUT_doit
//
this.BUT_doit.Location = new System.Drawing.Point(194, 105);
this.BUT_doit.Name = "BUT_doit";
this.BUT_doit.Size = new System.Drawing.Size(75, 23);
this.BUT_doit.TabIndex = 5;
this.BUT_doit.Text = "Do It";
this.BUT_doit.UseVisualStyleBackColor = true;
this.BUT_doit.Click += new System.EventHandler(this.BUT_doit_Click);
//
// TXT_outputlog
//
this.TXT_outputlog.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom)
| System.Windows.Forms.AnchorStyles.Left)
| System.Windows.Forms.AnchorStyles.Right)));
this.TXT_outputlog.Location = new System.Drawing.Point(28, 144);
this.TXT_outputlog.Multiline = true;
this.TXT_outputlog.Name = "TXT_outputlog";
this.TXT_outputlog.ReadOnly = true;
this.TXT_outputlog.ScrollBars = System.Windows.Forms.ScrollBars.Both;
this.TXT_outputlog.Size = new System.Drawing.Size(398, 143);
this.TXT_outputlog.TabIndex = 6;
//
// label1
//
this.label1.AutoSize = true;
this.label1.Location = new System.Drawing.Point(94, 75);
this.label1.Name = "label1";
this.label1.Size = new System.Drawing.Size(78, 13);
this.label1.TabIndex = 7;
this.label1.Text = "Seconds offset";
//
// georefimage
//
this.ClientSize = new System.Drawing.Size(453, 299);
this.Controls.Add(this.label1);
this.Controls.Add(this.TXT_outputlog);
this.Controls.Add(this.BUT_doit);
this.Controls.Add(this.TXT_offsetseconds);
this.Controls.Add(this.TXT_jpgdir);
this.Controls.Add(this.TXT_logfile);
this.Controls.Add(this.BUT_browsedir);
this.Controls.Add(this.BUT_browselog);
this.Name = "georefimage";
this.ResumeLayout(false);
this.PerformLayout();
}
private void BUT_browselog_Click(object sender, EventArgs e)
{
openFileDialog1.Filter = "Logs|*.log";
openFileDialog1.ShowDialog();
if (File.Exists(openFileDialog1.FileName))
{
TXT_logfile.Text = openFileDialog1.FileName;
}
}
private void BUT_browsedir_Click(object sender, EventArgs e)
{
folderBrowserDialog1.ShowDialog();
if (folderBrowserDialog1.SelectedPath != "")
{
TXT_jpgdir.Text = folderBrowserDialog1.SelectedPath;
}
}
private void BUT_doit_Click(object sender, EventArgs e)
{
if (!File.Exists(TXT_logfile.Text))
return;
if (!Directory.Exists(TXT_jpgdir.Text))
return;
float seconds;
if (float.TryParse(TXT_offsetseconds.Text, out seconds) == false)
return;
BUT_doit.Enabled = false;
try
{
dowork(TXT_logfile.Text, TXT_jpgdir.Text, seconds);
}
catch { }
BUT_doit.Enabled = true;
}
}
}

View File

@ -0,0 +1,126 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<metadata name="openFileDialog1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>17, 17</value>
</metadata>
<metadata name="folderBrowserDialog1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>297, 17</value>
</metadata>
</root>

View File

@ -44,7 +44,7 @@
this.BUT_geinjection = new ArdupilotMega.MyButton();
this.BUT_clearcustommaps = new ArdupilotMega.MyButton();
this.BUT_lang_edit = new ArdupilotMega.MyButton();
this.myButton1 = new ArdupilotMega.MyButton();
this.BUT_georefimage = new ArdupilotMega.MyButton();
this.SuspendLayout();
//
// button1
@ -175,7 +175,7 @@
//
// BUT_geinjection
//
this.BUT_geinjection.Location = new System.Drawing.Point(190, 199);
this.BUT_geinjection.Location = new System.Drawing.Point(150, 229);
this.BUT_geinjection.Name = "BUT_geinjection";
this.BUT_geinjection.Size = new System.Drawing.Size(209, 40);
this.BUT_geinjection.TabIndex = 14;
@ -185,7 +185,7 @@
//
// BUT_clearcustommaps
//
this.BUT_clearcustommaps.Location = new System.Drawing.Point(405, 199);
this.BUT_clearcustommaps.Location = new System.Drawing.Point(365, 229);
this.BUT_clearcustommaps.Name = "BUT_clearcustommaps";
this.BUT_clearcustommaps.Size = new System.Drawing.Size(209, 40);
this.BUT_clearcustommaps.TabIndex = 15;
@ -195,7 +195,7 @@
//
// BUT_lang_edit
//
this.BUT_lang_edit.Location = new System.Drawing.Point(405, 138);
this.BUT_lang_edit.Location = new System.Drawing.Point(365, 164);
this.BUT_lang_edit.Name = "BUT_lang_edit";
this.BUT_lang_edit.Size = new System.Drawing.Size(75, 23);
this.BUT_lang_edit.TabIndex = 16;
@ -203,22 +203,21 @@
this.BUT_lang_edit.UseVisualStyleBackColor = true;
this.BUT_lang_edit.Click += new System.EventHandler(this.BUT_lang_edit_Click);
//
// myButton1
// BUT_georefimage
//
this.myButton1.Location = new System.Drawing.Point(30, 174);
this.myButton1.Name = "myButton1";
this.myButton1.Size = new System.Drawing.Size(75, 23);
this.myButton1.TabIndex = 17;
this.myButton1.Text = "myButton1";
this.myButton1.UseVisualStyleBackColor = true;
this.myButton1.Click += new System.EventHandler(this.myButton1_Click);
this.BUT_georefimage.Location = new System.Drawing.Point(263, 164);
this.BUT_georefimage.Name = "BUT_georefimage";
this.BUT_georefimage.Size = new System.Drawing.Size(96, 23);
this.BUT_georefimage.TabIndex = 0;
this.BUT_georefimage.Text = "Geo ref images";
this.BUT_georefimage.Click += new System.EventHandler(this.BUT_georefimage_Click);
//
// temp
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.ClientSize = new System.Drawing.Size(731, 281);
this.Controls.Add(this.myButton1);
this.Controls.Add(this.BUT_georefimage);
this.Controls.Add(this.BUT_lang_edit);
this.Controls.Add(this.BUT_clearcustommaps);
this.Controls.Add(this.BUT_geinjection);
@ -261,7 +260,7 @@
private MyButton BUT_geinjection;
private MyButton BUT_clearcustommaps;
private MyButton BUT_lang_edit;
private MyButton myButton1;
private MyButton BUT_georefimage;
//private SharpVectors.Renderers.Forms.SvgPictureBox svgPictureBox1;
}

View File

@ -14,11 +14,6 @@ using System.Net;
using GMap.NET.WindowsForms;
using GMap.NET.CacheProviders;
using OpenGlobe.Core;
using OpenGlobe.Renderer;
using OpenGlobe.Scene;
namespace ArdupilotMega
{
public partial class temp : Form
@ -867,222 +862,14 @@ namespace ArdupilotMega
Console.WriteLine("Removed {0} images",removed);
}
private void BUT_lang_edit_Click(object sender, EventArgs e)
{
new resedit.Form1().Show();
}
GraphicsWindow _window;
SceneState _sceneState;
CameraLookAtPoint _lookCamera;
CameraFly _flyCamera;
ClearState _clearState;
GlobeClipmapTerrain _clipmap;
HeadsUpDisplay _hud;
Font _hudFont;
RayCastedGlobe _globe;
ClearState _clearDepth;
Ellipsoid _ellipsoid;
private void myButton1_Click(object sender, EventArgs e)
private void BUT_georefimage_Click(object sender, EventArgs e)
{
_window = Device.CreateWindow(800, 600, "Chapter 13: Clipmap Terrain on a Globe");
_ellipsoid = Ellipsoid.Wgs84;
WorldWindTerrainSource terrainSource = new WorldWindTerrainSource();
GMapRestImagery imagery = new GMapRestImagery();
_clipmap = new GlobeClipmapTerrain(_window.Context, terrainSource, imagery, _ellipsoid, 511);
_clipmap.HeightExaggeration = 1.0f;
IList<GridResolution> gridResolutions = new List<GridResolution>();
gridResolutions.Add(new GridResolution(
new Interval(0, 1000000, IntervalEndpoint.Closed, IntervalEndpoint.Open),
new Vector2D(0.005, 0.005)));
gridResolutions.Add(new GridResolution(
new Interval(1000000, 2000000, IntervalEndpoint.Closed, IntervalEndpoint.Open),
new Vector2D(0.01, 0.01)));
gridResolutions.Add(new GridResolution(
new Interval(2000000, 20000000, IntervalEndpoint.Closed, IntervalEndpoint.Open),
new Vector2D(0.05, 0.05)));
gridResolutions.Add(new GridResolution(
new Interval(20000000, double.MaxValue, IntervalEndpoint.Closed, IntervalEndpoint.Open),
new Vector2D(0.1, 0.1)));
_sceneState = new SceneState();
_sceneState.DiffuseIntensity = 0.90f;
_sceneState.SpecularIntensity = 0.05f;
_sceneState.AmbientIntensity = 0.05f;
_sceneState.Camera.FieldOfViewY = Math.PI / 3.0;
_clearState = new ClearState();
_clearState.Color = Color.White;
_sceneState.Camera.PerspectiveNearPlaneDistance = 0.000001 * _ellipsoid.MaximumRadius;
_sceneState.Camera.PerspectiveFarPlaneDistance = 10.0 * _ellipsoid.MaximumRadius;
_sceneState.SunPosition = new Vector3D(200000, 300000, 200000) * _ellipsoid.MaximumRadius;
_lookCamera = new CameraLookAtPoint(_sceneState.Camera, _window, _ellipsoid);
_lookCamera.Range = 1.5 * _ellipsoid.MaximumRadius;
_globe = new RayCastedGlobe(_window.Context);
_globe.Shape = _ellipsoid;
Bitmap bitmap = new Bitmap("NE2_50M_SR_W_4096.jpg");
_globe.Texture = Device.CreateTexture2D(bitmap, TextureFormat.RedGreenBlue8, false);
//_globe.GridResolutions = new GridResolutionCollection(gridResolutions);
_clearDepth = new ClearState();
_clearDepth.Buffers = ClearBuffers.DepthBuffer | ClearBuffers.StencilBuffer;
//_window.Keyboard.KeyDown += OnKeyDown;
_window.Resize += OnResize;
_window.RenderFrame += OnRenderFrame;
_window.PreRenderFrame += OnPreRenderFrame;
_hudFont = new Font("Arial", 16);
_hud = new HeadsUpDisplay();
_hud.Color = Color.Blue;
//_flyCamera = new CameraFly(_sceneState.Camera, _window);
//_flyCamera.MovementRate = 1200.0;
//_flyCamera.InputEnabled = true;
_sceneState.Camera.Target = new Vector3D(115, -35, 100.0);
_window.Run(30);
new georefimage().Show();
}
private void OnResize()
{
_window.Context.Viewport = new Rectangle(0, 0, _window.Width, _window.Height);
_sceneState.Camera.AspectRatio = _window.Width / (double)_window.Height;
}
private void OnRenderFrame()
{
Context context = _window.Context;
context.Clear(_clearState);
_globe.Render(context, _sceneState);
context.Clear(_clearDepth);
_clipmap.Render(context, _sceneState);
//_sceneState.Camera.Target = new Vector3D(115000, -350000, 100000.0);
if (_hud != null)
{
//_hud.Render(context, _sceneState);
}
}
private void OnPreRenderFrame()
{
Context context = _window.Context;
_clipmap.PreRender(context, _sceneState);
}
}
public class GMapRestImagery : RasterSource
{
GMapControl MainMap;
public GMapRestImagery()
{
//_baseUri = baseUri;
_levels = new RasterLevel[NumberOfLevels];
_levelsCollection = new RasterLevelCollection(_levels);
double deltaLongitude = LevelZeroDeltaLongitudeDegrees;
double deltaLatitude = LevelZeroDeltaLatitudeDegrees;
for (int i = 0; i < _levels.Length; ++i)
{
int longitudePosts = (int)Math.Round(360.0 / deltaLongitude) * TileLongitudePosts + 1;
int latitudePosts = (int)Math.Round(180 / deltaLatitude) * TileLatitudePosts + 1;
_levels[i] = new RasterLevel(this, i, _extent, longitudePosts, latitudePosts, TileLongitudePosts, TileLatitudePosts);
deltaLongitude /= 2.0;
deltaLatitude /= 2.0;
}
MainMap = new GMapControl();
MainMap.MapType = GMap.NET.MapType.GoogleSatellite;
MainMap.CacheLocation = Path.GetDirectoryName(Application.ExecutablePath) + "/gmapcache/";
}
public override GeodeticExtent Extent
{
get { return _extent; }
}
public int TileLongitudePosts
{
get { return 256; }
}
public int TileLatitudePosts
{
get { return 256; }
}
public override RasterLevelCollection Levels
{
get { return _levelsCollection; }
}
public override Texture2D LoadTileTexture(RasterTileIdentifier identifier)
{
//if (identifier.Level > 4)
//return null;
int level = identifier.Level; // 0 is -180 long
int longitudeIndex = ((_levels[level].LongitudePosts / _levels[level].LongitudePostsPerTile) / 2 / 2) + identifier.X; // (_levels[level].LongitudePosts / _levels[level].LongitudePostsPerTile) -
int latitudeIndex = identifier.Y; // (_levels[level].LatitudePosts / _levels[level].LatitudePostsPerTile) -
int damn = (1 << level) - latitudeIndex - 1;
Console.WriteLine(" z {0} lat {1} lon {2} ", level, damn, longitudeIndex);
GMap.NET.PureImage img = MainMap.Manager.ImageCacheLocal.GetImageFromCache(GMap.NET.MapType.GoogleSatellite, new GMap.NET.GPoint(longitudeIndex, damn), level);
Application.DoEvents();
try
{
Bitmap bitmap = new Bitmap(new Bitmap(img.Data), 256, 256);
Graphics e = Graphics.FromImage(bitmap);
e.DrawString(level + " " +longitudeIndex + "," + damn, new Font("Arial", 20), Brushes.White, new PointF(0, 0));
return Device.CreateTexture2DRectangle(bitmap, TextureFormat.RedGreenBlue8);
}
catch {
try
{
return null;
}
catch { return null; }
}
}
private Uri _baseUri;
private GeodeticExtent _extent = new GeodeticExtent(-0, -90, 360, 90);
private int _tilesLoaded;
private RasterLevel[] _levels;
private RasterLevelCollection _levelsCollection;
private const int NumberOfLevels = 20;
private const double LevelZeroDeltaLongitudeDegrees = 180;
private const double LevelZeroDeltaLatitudeDegrees = 180;
}
}