APM Planner 1.1.6

fix updater for recursive dirs
add network kml = google earth 3d display
remove ]]> from kml
swap geo ref from ms image parse to custom
This commit is contained in:
Michael Oborne 2011-12-16 08:17:13 +08:00
parent 291aaffdd9
commit f3bbe5e2a6
5 changed files with 122 additions and 16 deletions

View File

@ -556,6 +556,9 @@
<None Include="defines.h"> <None Include="defines.h">
<CopyToOutputDirectory>Always</CopyToOutputDirectory> <CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None> </None>
<None Include="m3u\networklink.kml">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None>
<None Include="MAC\Info.plist" /> <None Include="MAC\Info.plist" />
<None Include="MAC\run.sh" /> <None Include="MAC\run.sh" />
<None Include="mykey.snk" /> <None Include="mykey.snk" />

View File

@ -1375,8 +1375,92 @@ namespace ArdupilotMega
} }
} }
} }
else if (url.Contains(".html")) else if (url.Contains("network.kml"))
{ {
string header = "HTTP/1.1 200 OK\r\nContent-Type: application/vnd.google-earth.kml+xml\n\n";
byte[] temp = encoding.GetBytes(header);
stream.Write(temp, 0, temp.Length);
SharpKml.Dom.Document kml = new SharpKml.Dom.Document();
SharpKml.Dom.Placemark pmplane = new SharpKml.Dom.Placemark();
pmplane.Name = "P/Q ";
pmplane.Visibility = true;
SharpKml.Dom.Location loc = new SharpKml.Dom.Location();
loc.Latitude = cs.lat;
loc.Longitude = cs.lng;
loc.Altitude = cs.alt;
if (loc.Altitude < 0)
loc.Altitude = 0.01;
SharpKml.Dom.Orientation ori = new SharpKml.Dom.Orientation();
ori.Heading = cs.yaw;
ori.Roll = -cs.roll;
ori.Tilt = -cs.pitch;
SharpKml.Dom.Scale sca = new SharpKml.Dom.Scale();
sca.X = 2;
sca.Y = 2;
sca.Z = 2;
SharpKml.Dom.Model model = new SharpKml.Dom.Model();
model.Location = loc;
model.Orientation = ori;
model.AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute;
model.Scale = sca;
SharpKml.Dom.Link link = new SharpKml.Dom.Link();
link.Href = new Uri("block_plane_0.dae", UriKind.Relative);
model.Link = link;
pmplane.Geometry = model;
SharpKml.Dom.LookAt la = new SharpKml.Dom.LookAt()
{ Altitude = loc.Altitude.Value, Latitude = loc.Latitude.Value, Longitude = loc.Longitude.Value, Tilt = 80,
Heading = cs.yaw, AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute, Range = 50};
kml.Viewpoint = la;
kml.AddFeature(pmplane);
SharpKml.Base.Serializer serializer = new SharpKml.Base.Serializer();
serializer.Serialize(kml);
byte[] buffer = Encoding.ASCII.GetBytes(serializer.Xml);
stream.Write(buffer, 0, buffer.Length);
stream.Close();
}
else if (url.Contains("block_plane_0.dae"))
{
string header = "HTTP/1.1 200 OK\r\nContent-Type: text/plain\n\n";
byte[] temp = encoding.GetBytes(header);
stream.Write(temp, 0, temp.Length);
BinaryReader file = new BinaryReader(File.Open("block_plane_0.dae", FileMode.Open, FileAccess.Read, FileShare.Read));
byte[] buffer = new byte[1024];
while (file.PeekChar() != -1)
{
int leng = file.Read(buffer, 0, buffer.Length);
stream.Write(buffer, 0, leng);
}
file.Close();
stream.Close();
}
else if (url.Contains("hud.html"))
{
string header = "HTTP/1.1 200 OK\r\nContent-Type: text/html\n\n";
byte[] temp = encoding.GetBytes(header);
stream.Write(temp, 0, temp.Length);
BinaryReader file = new BinaryReader(File.Open("hud.html", FileMode.Open, FileAccess.Read, FileShare.Read)); BinaryReader file = new BinaryReader(File.Open("hud.html", FileMode.Open, FileAccess.Read, FileShare.Read));
byte[] buffer = new byte[1024]; byte[] buffer = new byte[1024];
while (file.PeekChar() != -1) while (file.PeekChar() != -1)
@ -1589,7 +1673,7 @@ namespace ArdupilotMega
} }
if (file.EndsWith("/")) if (file.EndsWith("/"))
{ {
update = updatecheck(loadinglabel, baseurl + file, file) && update; update = updatecheck(loadinglabel, baseurl + file, subdir.Replace("/", "\\") + file) && update;
continue; continue;
} }
if (loadinglabel != null) if (loadinglabel != null)

View File

@ -227,8 +227,8 @@ namespace ArdupilotMega
<tr><td>Pitch: " + model.Orientation.Tilt.Value.ToString("0.00") + @" </td></tr> <tr><td>Pitch: " + model.Orientation.Tilt.Value.ToString("0.00") + @" </td></tr>
<tr><td>Yaw: " + model.Orientation.Heading.Value.ToString("0.00") + @" </td></tr> <tr><td>Yaw: " + model.Orientation.Heading.Value.ToString("0.00") + @" </td></tr>
<tr><td>Time: " + cs.datetime.ToString("HH:mm:sszzzzzz") + @" </td></tr> <tr><td>Time: " + cs.datetime.ToString("HH:mm:sszzzzzz") + @" </td></tr>
</table> </table> ";
]]>"; // ]]>";
pmplane.Description = desc; pmplane.Description = desc;
} }

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

View File

@ -0,0 +1,19 @@
<?xml version="1.0" encoding="UTF-8"?>
<kml xmlns="http://www.opengis.net/kml/2.2" xmlns:gx="http://www.google.com/kml/ext/2.2" xmlns:kml="http://www.opengis.net/kml/2.2" xmlns:atom="http://www.w3.org/2005/Atom">
<Folder>
<name>Network Links</name>
<open>1</open>
<NetworkLink>
<name>View Centered Placemark</name>
<open>1</open>
<refreshVisibility>0</refreshVisibility>
<flyToView>1</flyToView>
<Link>
<href>http://127.0.0.1:56781/network.kml</href>
<refreshMode>onInterval</refreshMode>
<refreshInterval>1</refreshInterval>
<viewRefreshTime>1</viewRefreshTime>
</Link>
</NetworkLink>
</Folder>
</kml>