mirror of https://github.com/ArduPilot/ardupilot
APM Planner 1.1.5
fix bat % overflow fix tlog > kml for ac modify georef image
This commit is contained in:
parent
958693ee5e
commit
ae1c6ebde3
|
@ -82,7 +82,7 @@ namespace ArdupilotMega
|
|||
ManagementObjectSearcher searcher = new ManagementObjectSearcher(query);
|
||||
foreach (ManagementObject obj2 in searcher.Get())
|
||||
{
|
||||
Console.WriteLine("Dependant : " + obj2["Dependent"]);
|
||||
//Console.WriteLine("Dependant : " + obj2["Dependent"]);
|
||||
|
||||
if (obj2["Dependent"].ToString().Contains(@"USB\\VID_2341&PID_0010"))
|
||||
{
|
||||
|
|
|
@ -145,6 +145,9 @@
|
|||
<Reference Include="KMLib">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\kml-library\KmlTestbed\bin\Release\KMLib.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="MetaDataExtractor">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\MetaDataExtractorCSharp240d\bin\Release\MetaDataExtractor.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="Microsoft.DirectX, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<HintPath>..\..\..\..\..\..\..\Windows\Microsoft.NET\DirectX for Managed Code\1.0.2902.0\Microsoft.DirectX.dll</HintPath>
|
||||
|
|
|
@ -11,6 +11,6 @@
|
|||
<UpdateUrlHistory />
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<ReferencePath>C:\Users\hog\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\;C:\Users\hog\Desktop\DIYDrones\myquad\sharpkml\SharpKml\bin\Release\</ReferencePath>
|
||||
<ReferencePath>C:\Users\hog\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\;C:\Users\hog\Desktop\DIYDrones\myquad\sharpkml\SharpKml\bin\Release\;C:\Users\hog\Desktop\DIYDrones\myquad\MetaDataExtractorCSharp240d\bin\Release\</ReferencePath>
|
||||
</PropertyGroup>
|
||||
</Project>
|
|
@ -129,7 +129,7 @@ namespace ArdupilotMega
|
|||
//battery
|
||||
public float battery_voltage { get { return _battery_voltage; } set { _battery_voltage = value / 1000; } }
|
||||
private float _battery_voltage;
|
||||
public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 1000; } }
|
||||
public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 1000; if (_battery_remaining < 0) _battery_remaining = 0; } }
|
||||
private float _battery_remaining;
|
||||
|
||||
// HIL
|
||||
|
|
|
@ -123,7 +123,7 @@
|
|||
</data>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<data name="pictureBoxAPM.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>45, -9</value>
|
||||
<value>7, -9</value>
|
||||
</data>
|
||||
<data name="pictureBoxAPM.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>190, 190</value>
|
||||
|
@ -151,7 +151,7 @@
|
|||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="pictureBoxAPMHIL.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>45, 184</value>
|
||||
<value>7, 184</value>
|
||||
</data>
|
||||
<data name="pictureBoxAPMHIL.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>190, 190</value>
|
||||
|
@ -340,7 +340,7 @@
|
|||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="lbl_AP.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>42, 168</value>
|
||||
<value>4, 168</value>
|
||||
</data>
|
||||
<data name="lbl_AP.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>190, 13</value>
|
||||
|
@ -400,7 +400,7 @@
|
|||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="lbl_APHil.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>42, 361</value>
|
||||
<value>4, 361</value>
|
||||
</data>
|
||||
<data name="lbl_APHil.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>190, 13</value>
|
||||
|
@ -679,7 +679,7 @@
|
|||
<value>BUT_setup</value>
|
||||
</data>
|
||||
<data name=">>BUT_setup.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||
</data>
|
||||
<data name=">>BUT_setup.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
|
@ -700,6 +700,6 @@
|
|||
<value>Firmware</value>
|
||||
</data>
|
||||
<data name=">>$this.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
||||
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||
</data>
|
||||
</root>
|
|
@ -8,8 +8,8 @@
|
|||
{
|
||||
this.components = new System.ComponentModel.Container();
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightData));
|
||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle4 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||
this.contextMenuStrip1 = new System.Windows.Forms.ContextMenuStrip(this.components);
|
||||
this.goHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
|
||||
this.pointCameraHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
|
||||
|
@ -1213,8 +1213,8 @@
|
|||
//
|
||||
// dataGridViewImageColumn1
|
||||
//
|
||||
dataGridViewCellStyle3.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
|
||||
this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle3;
|
||||
dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
|
||||
this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle1;
|
||||
resources.ApplyResources(this.dataGridViewImageColumn1, "dataGridViewImageColumn1");
|
||||
this.dataGridViewImageColumn1.Image = global::ArdupilotMega.Properties.Resources.up;
|
||||
this.dataGridViewImageColumn1.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
|
||||
|
@ -1222,8 +1222,8 @@
|
|||
//
|
||||
// dataGridViewImageColumn2
|
||||
//
|
||||
dataGridViewCellStyle4.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
|
||||
this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle4;
|
||||
dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
|
||||
this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle2;
|
||||
resources.ApplyResources(this.dataGridViewImageColumn2, "dataGridViewImageColumn2");
|
||||
this.dataGridViewImageColumn2.Image = global::ArdupilotMega.Properties.Resources.down;
|
||||
this.dataGridViewImageColumn2.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
|
||||
|
|
|
@ -1078,6 +1078,11 @@ namespace ArdupilotMega.GCSViews
|
|||
|
||||
private void BUT_log2kml_Click(object sender, EventArgs e)
|
||||
{
|
||||
if (DialogResult.Cancel == Common.MessageShowAgain("Tlog to KML Firmware Version", "When converting logs, ensure your Firmware version is set correctly.\n(Near your com port selection.)"))
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
Form frm = new MavlinkLog();
|
||||
MainV2.fixtheme(frm);
|
||||
frm.ShowDialog();
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -2609,7 +2609,7 @@ namespace ArdupilotMega.GCSViews
|
|||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Please Connect/wait for lock, and click here to set your home to your current location");
|
||||
MessageBox.Show("If you're at the field, connect to your APM and wait for GPS lock. Then click 'Home Location' link to set home to your location");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -2865,7 +2865,7 @@ namespace ArdupilotMega.GCSViews
|
|||
|
||||
private void BUT_zoomto_Click(object sender, EventArgs e)
|
||||
{
|
||||
string place = "Perth, Australia";
|
||||
string place = "Perth Airport, Australia";
|
||||
if (DialogResult.OK == Common.InputBox("Location", "Enter your location", ref place))
|
||||
{
|
||||
|
||||
|
@ -2932,6 +2932,9 @@ namespace ArdupilotMega.GCSViews
|
|||
{
|
||||
routes.Markers.Clear();
|
||||
|
||||
if (MainV2.cs.lat == 0 || MainV2.cs.lng == 0)
|
||||
return;
|
||||
|
||||
PointLatLng currentloc = new PointLatLng(MainV2.cs.lat, MainV2.cs.lng);
|
||||
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
|
||||
|
|
|
@ -2073,7 +2073,7 @@ namespace ArdupilotMega
|
|||
|
||||
if (bpstime.Second != DateTime.Now.Second && !logreadmode)
|
||||
{
|
||||
Console.WriteLine("bps {0} loss {1} left {2} mem {3}", bps1, synclost, BaseStream.BytesToRead, System.GC.GetTotalMemory(false));
|
||||
Console.Write("bps {0} loss {1} left {2} mem {3} \n", bps1, synclost, BaseStream.BytesToRead, System.GC.GetTotalMemory(false));
|
||||
bps2 = bps1; // prev sec
|
||||
bps1 = 0; // current sec
|
||||
bpstime = DateTime.Now;
|
||||
|
|
|
@ -39,12 +39,22 @@ namespace ArdupilotMega
|
|||
|
||||
private void writeKML(string filename)
|
||||
{
|
||||
SharpKml.Dom.AltitudeMode altmode = SharpKml.Dom.AltitudeMode.Absolute;
|
||||
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
|
||||
{
|
||||
altmode = SharpKml.Dom.AltitudeMode.Absolute;
|
||||
}
|
||||
else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
|
||||
{
|
||||
altmode = SharpKml.Dom.AltitudeMode.RelativeToGround;
|
||||
}
|
||||
|
||||
Color[] colours = { Color.Red, Color.Orange, Color.Yellow, Color.Green, Color.Blue, Color.Indigo, Color.Violet, Color.Pink };
|
||||
|
||||
Document kml = new Document();
|
||||
|
||||
Tour tour = new Tour();
|
||||
tour.Name = "First Person View";
|
||||
Tour tour = new Tour() { Name = "First Person View" };
|
||||
Playlist tourplaylist = new Playlist();
|
||||
|
||||
AddNamespace(kml, "gx", "http://www.google.com/kml/ext/2.2");
|
||||
|
@ -64,10 +74,12 @@ namespace ArdupilotMega
|
|||
Style stylet = new Style();
|
||||
stylet.Id = "track";
|
||||
SharpKml.Dom.IconStyle ico = new SharpKml.Dom.IconStyle();
|
||||
LabelStyle lst = new LabelStyle();
|
||||
lst.Scale = 0;
|
||||
stylet.Icon = ico;
|
||||
ico.Icon = new IconStyle.IconLink(new Uri("http://earth.google.com/images/kml-icons/track-directional/track-none.png"));
|
||||
stylet.Icon.Scale = 0.5;
|
||||
//stylet.Label.Scale = 0;
|
||||
stylet.Label = lst;
|
||||
|
||||
kml.AddStyle(stylet);
|
||||
|
||||
|
@ -110,7 +122,7 @@ namespace ArdupilotMega
|
|||
c++;
|
||||
|
||||
LineString ls = new LineString();
|
||||
ls.AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute;
|
||||
ls.AltitudeMode = altmode;
|
||||
ls.Extrude = true;
|
||||
|
||||
ls.Coordinates = coords;
|
||||
|
@ -154,7 +166,7 @@ namespace ArdupilotMega
|
|||
|
||||
flyto.Mode = FlyToMode.Smooth;
|
||||
SharpKml.Dom.Camera cam = new SharpKml.Dom.Camera();
|
||||
cam.AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute;
|
||||
cam.AltitudeMode = altmode;
|
||||
cam.Latitude = cs.lat;
|
||||
cam.Longitude = cs.lng;
|
||||
cam.Altitude = cs.alt;
|
||||
|
@ -203,7 +215,7 @@ namespace ArdupilotMega
|
|||
Model model = new Model();
|
||||
model.Location = loc;
|
||||
model.Orientation = ori;
|
||||
model.AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute;
|
||||
model.AltitudeMode = altmode;
|
||||
model.Scale = sca;
|
||||
|
||||
try
|
||||
|
@ -236,7 +248,7 @@ namespace ArdupilotMega
|
|||
Placemark pmt = new Placemark();
|
||||
|
||||
SharpKml.Dom.Point pnt = new SharpKml.Dom.Point();
|
||||
pnt.AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute;
|
||||
pnt.AltitudeMode = altmode;
|
||||
pnt.Coordinate = new Vector(cs.lat,cs.lng,cs.alt);
|
||||
|
||||
pmt.Name = "" + a;
|
||||
|
|
|
@ -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.4")]
|
||||
[assembly: AssemblyFileVersion("1.1.5")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
|
|
@ -6,6 +6,8 @@ using System.Drawing;
|
|||
using System.Drawing.Imaging;
|
||||
using System.IO;
|
||||
using System.Windows.Forms;
|
||||
using com.drew.imaging.jpg;
|
||||
using com.drew.metadata;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
|
@ -21,6 +23,7 @@ namespace ArdupilotMega
|
|||
private FolderBrowserDialog folderBrowserDialog1;
|
||||
private Label label1;
|
||||
private TextBox TXT_outputlog;
|
||||
private MyButton BUT_estoffset;
|
||||
|
||||
internal georefimage() {
|
||||
InitializeComponent();
|
||||
|
@ -32,6 +35,38 @@ namespace ArdupilotMega
|
|||
|
||||
try
|
||||
{
|
||||
|
||||
Metadata lcMetadata = null;
|
||||
try
|
||||
{
|
||||
FileInfo lcImgFile = new FileInfo(fn);
|
||||
// Loading all meta data
|
||||
lcMetadata = JpegMetadataReader.ReadMetadata(lcImgFile);
|
||||
}
|
||||
catch (JpegProcessingException e)
|
||||
{
|
||||
Console.Error.WriteLine(e.Message);
|
||||
return dtaken;
|
||||
}
|
||||
|
||||
foreach (AbstractDirectory lcDirectory in lcMetadata)
|
||||
{
|
||||
|
||||
if (lcDirectory.ContainsTag(0x9003))
|
||||
{
|
||||
dtaken = lcDirectory.GetDate(0x9003);
|
||||
Console.WriteLine("does " + lcDirectory.GetTagName(0x9003) + " " + dtaken);
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
////// old method, works, just slow
|
||||
/*
|
||||
Image myImage = Image.FromFile(fn);
|
||||
PropertyItem propItem = myImage.GetPropertyItem(36867); // 36867 // 306
|
||||
|
||||
|
@ -44,6 +79,7 @@ namespace ArdupilotMega
|
|||
dtaken = DateTime.Parse(sdate);
|
||||
|
||||
myImage.Dispose();
|
||||
*/
|
||||
}
|
||||
catch { }
|
||||
|
||||
|
@ -81,7 +117,7 @@ namespace ArdupilotMega
|
|||
return list;
|
||||
}
|
||||
|
||||
public void dowork(string logFile, string dirWithImages, float offsetseconds)
|
||||
public void dowork(string logFile, string dirWithImages, float offsetseconds,bool dooffset)
|
||||
{
|
||||
DateTime localmin = DateTime.MaxValue;
|
||||
DateTime localmax = DateTime.MinValue;
|
||||
|
@ -104,6 +140,7 @@ namespace ArdupilotMega
|
|||
sw.WriteLine("#name utc longitude latitude height");
|
||||
|
||||
int first = 0;
|
||||
int matchs = 0;
|
||||
|
||||
foreach (string file in files)
|
||||
{
|
||||
|
@ -133,7 +170,7 @@ namespace ArdupilotMega
|
|||
|
||||
foreach (string[] arr in list)
|
||||
{
|
||||
Application.DoEvents();
|
||||
//Application.DoEvents();
|
||||
|
||||
DateTime crap = startTime.AddMilliseconds(int.Parse(arr[1])).AddSeconds(offsetseconds);
|
||||
|
||||
|
@ -144,15 +181,20 @@ namespace ArdupilotMega
|
|||
|
||||
TXT_outputlog.AppendText("offset should be about " + (dt -crap).TotalSeconds + "\r\n");
|
||||
|
||||
if (dooffset)
|
||||
return;
|
||||
|
||||
first++;
|
||||
}
|
||||
|
||||
Console.Write("ph " + dt + " log " + crap + " \r");
|
||||
//Console.Write("ph " + dt + " log " + crap + " \r");
|
||||
|
||||
if (dt.Equals(crap))
|
||||
{
|
||||
TXT_outputlog.AppendText("MATCH Photo " + Path.GetFileNameWithoutExtension(file) + " " + dt + "\r\n");
|
||||
|
||||
matchs++;
|
||||
|
||||
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();
|
||||
|
@ -170,7 +212,7 @@ namespace ArdupilotMega
|
|||
sw2.Close();
|
||||
sw.Close();
|
||||
|
||||
MessageBox.Show("Done");
|
||||
MessageBox.Show("Done " + matchs + " matchs");
|
||||
|
||||
}
|
||||
|
||||
|
@ -186,6 +228,7 @@ namespace ArdupilotMega
|
|||
this.folderBrowserDialog1 = new System.Windows.Forms.FolderBrowserDialog();
|
||||
this.TXT_outputlog = new System.Windows.Forms.TextBox();
|
||||
this.label1 = new System.Windows.Forms.Label();
|
||||
this.BUT_estoffset = new ArdupilotMega.MyButton();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// openFileDialog1
|
||||
|
@ -268,9 +311,20 @@ namespace ArdupilotMega
|
|||
this.label1.TabIndex = 7;
|
||||
this.label1.Text = "Seconds offset";
|
||||
//
|
||||
// BUT_estoffset
|
||||
//
|
||||
this.BUT_estoffset.Location = new System.Drawing.Point(286, 67);
|
||||
this.BUT_estoffset.Name = "BUT_estoffset";
|
||||
this.BUT_estoffset.Size = new System.Drawing.Size(75, 23);
|
||||
this.BUT_estoffset.TabIndex = 8;
|
||||
this.BUT_estoffset.Text = "Estimate Offset";
|
||||
this.BUT_estoffset.UseVisualStyleBackColor = true;
|
||||
this.BUT_estoffset.Click += new System.EventHandler(this.BUT_estoffset_Click);
|
||||
//
|
||||
// georefimage
|
||||
//
|
||||
this.ClientSize = new System.Drawing.Size(453, 299);
|
||||
this.Controls.Add(this.BUT_estoffset);
|
||||
this.Controls.Add(this.label1);
|
||||
this.Controls.Add(this.TXT_outputlog);
|
||||
this.Controls.Add(this.BUT_doit);
|
||||
|
@ -319,10 +373,15 @@ namespace ArdupilotMega
|
|||
BUT_doit.Enabled = false;
|
||||
try
|
||||
{
|
||||
dowork(TXT_logfile.Text, TXT_jpgdir.Text, seconds);
|
||||
dowork(TXT_logfile.Text, TXT_jpgdir.Text, seconds, false);
|
||||
}
|
||||
catch { }
|
||||
BUT_doit.Enabled = true;
|
||||
}
|
||||
|
||||
private void BUT_estoffset_Click(object sender, EventArgs e)
|
||||
{
|
||||
dowork(TXT_logfile.Text, TXT_jpgdir.Text, 0, true);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue