mirror of https://github.com/ArduPilot/ardupilot
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:
parent
d6a8440ef2
commit
bfab9f52e9
|
@ -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" />
|
||||||
|
|
|
@ -14,7 +14,7 @@ using System.Net;
|
||||||
using System.Text.RegularExpressions;
|
using System.Text.RegularExpressions;
|
||||||
using System.Web;
|
using System.Web;
|
||||||
using System.Diagnostics;
|
using System.Diagnostics;
|
||||||
using System.Runtime.InteropServices;
|
using System.Runtime.InteropServices;
|
||||||
using System.Speech.Synthesis;
|
using System.Speech.Synthesis;
|
||||||
using System.Globalization;
|
using System.Globalization;
|
||||||
using System.Threading;
|
using System.Threading;
|
||||||
|
@ -172,7 +172,7 @@ namespace ArdupilotMega
|
||||||
if (MainV2.config["CHK_GDIPlus"] != null)
|
if (MainV2.config["CHK_GDIPlus"] != null)
|
||||||
GCSViews.FlightData.myhud.UseOpenGL = !bool.Parse(MainV2.config["CHK_GDIPlus"].ToString());
|
GCSViews.FlightData.myhud.UseOpenGL = !bool.Parse(MainV2.config["CHK_GDIPlus"].ToString());
|
||||||
|
|
||||||
changeunits();
|
changeunits();
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
|
@ -254,7 +254,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (MONO)
|
if (MONO)
|
||||||
{
|
{
|
||||||
devs = Directory.GetFiles("/dev/","*ACM*");
|
devs = Directory.GetFiles("/dev/", "*ACM*");
|
||||||
}
|
}
|
||||||
|
|
||||||
string[] ports = SerialPort.GetPortNames();
|
string[] ports = SerialPort.GetPortNames();
|
||||||
|
@ -701,7 +701,7 @@ namespace ArdupilotMega
|
||||||
comPort.logfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm-ss") + ".tlog", FileMode.CreateNew));
|
comPort.logfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm-ss") + ".tlog", FileMode.CreateNew));
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Failed to create log - wont log this session"); } // soft fail
|
catch { MessageBox.Show("Failed to create log - wont log this session"); } // soft fail
|
||||||
|
|
||||||
comPort.BaseStream.PortName = CMB_serialport.Text;
|
comPort.BaseStream.PortName = CMB_serialport.Text;
|
||||||
comPort.Open(true);
|
comPort.Open(true);
|
||||||
|
|
||||||
|
@ -1123,7 +1123,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (heatbeatsend.Second != DateTime.Now.Second)
|
if (heatbeatsend.Second != DateTime.Now.Second)
|
||||||
{
|
{
|
||||||
// Console.WriteLine("remote lost {0}", cs.packetdropremote);
|
// Console.WriteLine("remote lost {0}", cs.packetdropremote);
|
||||||
|
|
||||||
MAVLink.__mavlink_heartbeat_t htb = new MAVLink.__mavlink_heartbeat_t();
|
MAVLink.__mavlink_heartbeat_t htb = new MAVLink.__mavlink_heartbeat_t();
|
||||||
|
|
||||||
|
@ -1325,7 +1325,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (url.Contains("websocket"))
|
if (url.Contains("websocket"))
|
||||||
{
|
{
|
||||||
using (var writer = new StreamWriter(stream,Encoding.Default))
|
using (var writer = new StreamWriter(stream, Encoding.Default))
|
||||||
{
|
{
|
||||||
writer.WriteLine("HTTP/1.1 101 WebSocket Protocol Handshake");
|
writer.WriteLine("HTTP/1.1 101 WebSocket Protocol Handshake");
|
||||||
writer.WriteLine("Upgrade: WebSocket");
|
writer.WriteLine("Upgrade: WebSocket");
|
||||||
|
@ -1336,7 +1336,7 @@ namespace ArdupilotMega
|
||||||
int end = head.IndexOf('\r', start);
|
int end = head.IndexOf('\r', start);
|
||||||
if (end == -1)
|
if (end == -1)
|
||||||
end = head.IndexOf('\n', start);
|
end = head.IndexOf('\n', start);
|
||||||
string accept = ComputeWebSocketHandshakeSecurityHash09(head.Substring(start,end-start));
|
string accept = ComputeWebSocketHandshakeSecurityHash09(head.Substring(start, end - start));
|
||||||
|
|
||||||
writer.WriteLine("Sec-WebSocket-Accept: " + accept);
|
writer.WriteLine("Sec-WebSocket-Accept: " + accept);
|
||||||
|
|
||||||
|
@ -1369,14 +1369,98 @@ namespace ArdupilotMega
|
||||||
packet[i++] = (byte)ch;
|
packet[i++] = (byte)ch;
|
||||||
}
|
}
|
||||||
|
|
||||||
stream.Write(packet,0,i);
|
stream.Write(packet, 0, i);
|
||||||
|
|
||||||
//break;
|
//break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
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)
|
||||||
|
@ -1524,7 +1608,7 @@ namespace ArdupilotMega
|
||||||
catch (Exception ex) { MessageBox.Show("Update Failed " + ex.Message); }
|
catch (Exception ex) { MessageBox.Show("Update Failed " + ex.Message); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private static void updatelabel(Label loadinglabel,string text)
|
private static void updatelabel(Label loadinglabel, string text)
|
||||||
{
|
{
|
||||||
MainV2.instance.Invoke((MethodInvoker)delegate
|
MainV2.instance.Invoke((MethodInvoker)delegate
|
||||||
{
|
{
|
||||||
|
@ -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)
|
||||||
|
@ -1657,7 +1741,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (loadinglabel != null)
|
if (loadinglabel != null)
|
||||||
updatelabel(loadinglabel,"Getting " + file);
|
updatelabel(loadinglabel, "Getting " + file);
|
||||||
|
|
||||||
// Create a request using a URL that can receive a post.
|
// Create a request using a URL that can receive a post.
|
||||||
request = WebRequest.Create(baseurl + file);
|
request = WebRequest.Create(baseurl + file);
|
||||||
|
@ -1689,7 +1773,7 @@ namespace ArdupilotMega
|
||||||
if (dt.Second != DateTime.Now.Second)
|
if (dt.Second != DateTime.Now.Second)
|
||||||
{
|
{
|
||||||
if (loadinglabel != null)
|
if (loadinglabel != null)
|
||||||
updatelabel(loadinglabel,"Getting " + file + ": " + Math.Abs(bytes) + " bytes");//(((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%";
|
updatelabel(loadinglabel, "Getting " + file + ": " + Math.Abs(bytes) + " bytes");//(((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%";
|
||||||
dt = DateTime.Now;
|
dt = DateTime.Now;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -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;
|
||||||
}
|
}
|
||||||
|
|
|
@ -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("")]
|
||||||
|
|
|
@ -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>
|
Loading…
Reference in New Issue