APM Planner 1.1.57

fix antenna tracker issue with saved settings
add pretyping to config list
add rawlogs
modify mavlink log graph interface. 2 x yaxis & roll,pitch,yaw now in degs
update dataflash log format - thanks randy
update google earth interface refresh to 0.3 sec
This commit is contained in:
Michael Oborne 2012-03-26 18:21:49 +08:00
parent cf1a6f8ab8
commit aea780e5ea
15 changed files with 624 additions and 53 deletions

View File

@ -110,8 +110,8 @@
// TRK_pantrim
//
this.TRK_pantrim.Location = new System.Drawing.Point(153, 81);
this.TRK_pantrim.Maximum = 90;
this.TRK_pantrim.Minimum = -90;
this.TRK_pantrim.Maximum = 360;
this.TRK_pantrim.Minimum = -360;
this.TRK_pantrim.Name = "TRK_pantrim";
this.TRK_pantrim.Size = new System.Drawing.Size(375, 45);
this.TRK_pantrim.TabIndex = 5;
@ -124,7 +124,7 @@
this.TXT_panrange.Name = "TXT_panrange";
this.TXT_panrange.Size = new System.Drawing.Size(64, 20);
this.TXT_panrange.TabIndex = 4;
this.TXT_panrange.Text = "180";
this.TXT_panrange.Text = "360";
this.TXT_panrange.TextChanged += new System.EventHandler(this.TXT_panrange_TextChanged);
//
// label3
@ -175,8 +175,8 @@
// TRK_tilttrim
//
this.TRK_tilttrim.Location = new System.Drawing.Point(153, 157);
this.TRK_tilttrim.Maximum = 45;
this.TRK_tilttrim.Minimum = -45;
this.TRK_tilttrim.Maximum = 180;
this.TRK_tilttrim.Minimum = -180;
this.TRK_tilttrim.Name = "TRK_tilttrim";
this.TRK_tilttrim.Size = new System.Drawing.Size(375, 45);
this.TRK_tilttrim.TabIndex = 7;

View File

@ -59,6 +59,7 @@ namespace System.Windows.Forms
Width = textSize.Width + 50,
Height = textSize.Height + 100,
TopMost = true,
TopLevel = true
};
Rectangle screenRectangle = msgBoxFrm.RectangleToScreen(msgBoxFrm.ClientRectangle);

View File

@ -141,6 +141,8 @@
this.RLL2SRV_P = new System.Windows.Forms.NumericUpDown();
this.label52 = new System.Windows.Forms.Label();
this.TabAC = new System.Windows.Forms.TabPage();
this.myLabel4 = new ArdupilotMega.MyLabel();
this.myLabel3 = new ArdupilotMega.MyLabel();
this.TUNE_LOW = new System.Windows.Forms.NumericUpDown();
this.TUNE_HIGH = new System.Windows.Forms.NumericUpDown();
this.myLabel2 = new ArdupilotMega.MyLabel();
@ -289,8 +291,6 @@
this.BUT_load = new ArdupilotMega.MyButton();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.BUT_compare = new ArdupilotMega.MyButton();
this.myLabel3 = new ArdupilotMega.MyLabel();
this.myLabel4 = new ArdupilotMega.MyLabel();
((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit();
this.ConfigTabs.SuspendLayout();
this.TabAP.SuspendLayout();
@ -437,6 +437,8 @@
this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2;
this.Params.RowHeadersVisible = false;
this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged);
this.Params.KeyDown += new System.Windows.Forms.KeyEventHandler(this.Params_KeyDown);
this.Params.KeyPress += new System.Windows.Forms.KeyPressEventHandler(this.Params_KeyPress);
//
// Command
//
@ -1118,6 +1120,18 @@
resources.ApplyResources(this.TabAC, "TabAC");
this.TabAC.Name = "TabAC";
//
// myLabel4
//
resources.ApplyResources(this.myLabel4, "myLabel4");
this.myLabel4.Name = "myLabel4";
this.myLabel4.resize = false;
//
// myLabel3
//
resources.ApplyResources(this.myLabel3, "myLabel3");
this.myLabel3.Name = "myLabel3";
this.myLabel3.resize = false;
//
// TUNE_LOW
//
resources.ApplyResources(this.TUNE_LOW, "TUNE_LOW");
@ -2159,18 +2173,6 @@
this.BUT_compare.UseVisualStyleBackColor = true;
this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click);
//
// myLabel3
//
resources.ApplyResources(this.myLabel3, "myLabel3");
this.myLabel3.Name = "myLabel3";
this.myLabel3.resize = false;
//
// myLabel4
//
resources.ApplyResources(this.myLabel4, "myLabel4");
this.myLabel4.Name = "myLabel4";
this.myLabel4.resize = false;
//
// Configuration
//
resources.ApplyResources(this, "$this");

View File

@ -1190,13 +1190,45 @@ namespace ArdupilotMega.GCSViews
BUT_load_Click(BUT_load, null);
return true;
}
if (Params.Focused)
{
if (keyData >= Keys.A && keyData <= Keys.Z)
{
int row = FindRowIndex(0, keyData.ToString());
Params.FirstDisplayedScrollingRowIndex = row;
Params.ClearSelection();
Params[1, row].Selected = true;
}
}
return base.ProcessCmdKey(ref msg, keyData);
}
int FindRowIndex(int col, string startswith)
{
foreach (DataGridViewRow row in Params.Rows)
{
if (row.Cells[col].Value.ToString().StartsWith(startswith))
{
return row.Index;
}
}
return 0;
}
private void CMB_ratesensors_SelectedIndexChanged(object sender, EventArgs e)
{
MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
MainV2.cs.ratesensors = byte.Parse(((ComboBox)sender).Text);
}
private void Params_KeyDown(object sender, KeyEventArgs e)
{
}
private void Params_KeyPress(object sender, KeyPressEventArgs e)
{
}
}
}

View File

@ -101,6 +101,7 @@ namespace ArdupilotMega
public DateTime lastlogread = DateTime.MinValue;
public BinaryReader logplaybackfile = null;
public BinaryWriter logfile = null;
public BinaryWriter rawlogfile = null;
int bps1 = 0;
int bps2 = 0;
@ -2009,7 +2010,11 @@ namespace ArdupilotMega
System.Threading.Thread.Sleep(1);
}
if (BaseStream.IsOpen)
{
temp[count] = (byte)BaseStream.ReadByte();
if (rawlogfile != null)
rawlogfile.Write(temp[count]);
}
}
}
catch (Exception e) { log.Info("MAVLink readpacket read error: " + e.Message); break; }
@ -2066,6 +2071,11 @@ namespace ArdupilotMega
if (BaseStream.IsOpen)
{
int read = BaseStream.Read(temp, 6, length - 4);
if (rawlogfile != null)
{
rawlogfile.Write(temp, 0, read);
rawlogfile.BaseStream.Flush();
}
}
}
//Console.WriteLine("data " + read + " " + length + " aval " + this.BytesToRead);

View File

@ -456,6 +456,9 @@ namespace ArdupilotMega
if (comPort.logfile != null)
comPort.logfile.Close();
if (comPort.rawlogfile != null)
comPort.rawlogfile.Close();
comPort.BaseStream.DtrEnable = false;
comPort.Close();
}
@ -502,10 +505,15 @@ namespace ArdupilotMega
if (comPort.logfile != null)
comPort.logfile.Close();
if (comPort.rawlogfile != null)
comPort.rawlogfile.Close();
try
{
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
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, FileAccess.ReadWrite, FileShare.Read));
comPort.rawlogfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".rlog", FileMode.CreateNew, FileAccess.ReadWrite, FileShare.Read));
}
catch { CustomMessageBox.Show("Failed to create log - wont log this session"); } // soft fail
@ -1885,6 +1893,9 @@ namespace ArdupilotMega
comPort.logreadmode = false;
if (comPort.logfile != null)
comPort.logfile.Close();
if (comPort.rawlogfile != null)
comPort.rawlogfile.Close();
}
catch { }

View File

@ -36,9 +36,15 @@ namespace ArdupilotMega
List<string> selection = new List<string>();
Hashtable data = new Hashtable();
public MavlinkLog()
{
InitializeComponent();
zg1.GraphPane.YAxis.Title.IsVisible = false;
zg1.GraphPane.Title.IsVisible = true;
zg1.GraphPane.Title.Text = "Mavlink Log Graph";
}
private void writeKML(string filename)
@ -549,7 +555,7 @@ namespace ArdupilotMega
zg1.GraphPane.CurveList.Clear();
GetLogFileData(zg1, openFileDialog1.FileName, fields);
//GetLogFileData(zg1, openFileDialog1.FileName, fields);
try
{
@ -587,19 +593,10 @@ namespace ArdupilotMega
Random rand = new Random();
int step = 0;
// setup display and arrays
// setup arrays
for (int a = 0; a < lookforfields.Count; a++)
{
lists[a] = new PointPairList();
LineItem myCurve;
int colorvalue = ColourValues[step % ColourValues.Length];
step++;
myCurve = zg1.GraphPane.AddCurve(lookforfields[a].Replace("__mavlink_", ""), lists[a], Color.FromArgb(unchecked( colorvalue + (int)0xff000000)), SymbolType.None);
}
{
@ -694,6 +691,35 @@ namespace ArdupilotMega
progressBar1.Value = 100;
}
int step = 0;
zg1.GraphPane.AddY2Axis("PWM");
zg1.GraphPane.AddY2Axis("Angle");
//zg1.GraphPane.XAxis.Title.Text = "Seconds";
// setup display and arrays
for (int a = 0; a < lookforfields.Count; a++)
{
LineItem myCurve;
int colorvalue = ColourValues[step % ColourValues.Length];
step++;
myCurve = zg1.GraphPane.AddCurve(lookforfields[a].Replace("__mavlink_", ""), lists[a], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None);
double xMin, xMax, yMin, yMax;
myCurve.GetRange(out xMin, out xMax, out yMin, out yMax, true, false, zg1.GraphPane);
if (yMin > 900 && yMax < 2100)
{
myCurve.IsY2Axis = true;
myCurve.YAxisIndex = 0;
zg1.GraphPane.Y2Axis.IsVisible = true;
}
}
}
private List<string> GetLogFileValidFields(string logfile)
@ -702,22 +728,35 @@ namespace ArdupilotMega
Hashtable seenIt = new Hashtable();
selection = new List<string>();
List<string> options = new List<string>();
this.data.Clear();
colorStep = 0;
{
MAVLink mine = new MAVLink();
mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read));
mine.logreadmode = true;
MAVLink MavlinkInterface = new MAVLink();
MavlinkInterface.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read));
MavlinkInterface.logreadmode = true;
mine.packets.Initialize(); // clear
MavlinkInterface.packets.Initialize(); // clear
while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
// to get first packet time
MavlinkInterface.readPacket();
DateTime startlogtime = MavlinkInterface.lastlogread;
while (MavlinkInterface.logplaybackfile.BaseStream.Position < MavlinkInterface.logplaybackfile.BaseStream.Length)
{
progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f);
this.Refresh();
progressBar1.Value = (int)((float)MavlinkInterface.logplaybackfile.BaseStream.Position / (float)MavlinkInterface.logplaybackfile.BaseStream.Length * 100.0f);
progressBar1.Refresh();
byte[] packet = mine.readPacket();
byte[] packet = MavlinkInterface.readPacket();
object data = mine.DebugPacket(packet, false);
object data = MavlinkInterface.DebugPacket(packet, false);
Type test = data.GetType();
@ -735,18 +774,59 @@ namespace ArdupilotMega
{
if (!seenIt.ContainsKey(field.DeclaringType.Name + "." + field.Name))
{
AddDataOption(selectform, field.Name + " " + field.DeclaringType.Name);
seenIt[field.DeclaringType.Name + "." + field.Name] = 1;
//AddDataOption(selectform, field.Name + " " + field.DeclaringType.Name);
options.Add(field.DeclaringType.Name + "." + field.Name);
}
if (!this.data.ContainsKey(field.Name + " " + field.DeclaringType.Name))
this.data[field.Name + " " + field.DeclaringType.Name] = new PointPairList();
PointPairList list = ((PointPairList)this.data[field.Name + " " + field.DeclaringType.Name]);
object value = fieldValue;
// seconds scale
double time = (MavlinkInterface.lastlogread - startlogtime).TotalMilliseconds / 1000.0;
if (value.GetType() == typeof(Single))
{
list.Add(time, (Single)field.GetValue(data));
}
else if (value.GetType() == typeof(short))
{
list.Add(time, (short)field.GetValue(data));
}
else if (value.GetType() == typeof(ushort))
{
list.Add(time, (ushort)field.GetValue(data));
}
else if (value.GetType() == typeof(byte))
{
list.Add(time, (byte)field.GetValue(data));
}
else if (value.GetType() == typeof(Int32))
{
list.Add(time, (Int32)field.GetValue(data));
}
}
}
}
mine.logreadmode = false;
mine.logplaybackfile.Close();
mine.logplaybackfile = null;
MavlinkInterface.logreadmode = false;
MavlinkInterface.logplaybackfile.Close();
MavlinkInterface.logplaybackfile = null;
selectform.ShowDialog();
// custom sort based on packet name
//options.Sort(delegate(string c1, string c2) { return String.Compare(c1.Substring(0,c1.IndexOf('.')),c2.Substring(0,c2.IndexOf('.')));});
// this needs sorting
foreach (string item in options)
{
var items = item.Split('.');
AddDataOption(selectform, items[1] + " " + items[0]);
}
selectform.Show();
progressBar1.Value = 100;
@ -784,17 +864,70 @@ namespace ArdupilotMega
}
}
int colorStep = 0;
void chk_box_CheckedChanged(object sender, EventArgs e)
{
if (((CheckBox)sender).Checked)
{
selection.Add(((CheckBox)sender).Name);
LineItem myCurve;
int colorvalue = ColourValues[colorStep % ColourValues.Length];
colorStep++;
myCurve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name.Replace("__mavlink_", ""), (PointPairList)data[((CheckBox)sender).Name], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None);
myCurve.Tag = ((CheckBox)sender).Name;
if (myCurve.Tag.ToString() == "roll __mavlink_attitude_t" ||
myCurve.Tag.ToString() == "pitch __mavlink_attitude_t" ||
myCurve.Tag.ToString() == "yaw __mavlink_attitude_t")
{
PointPairList ppl = new PointPairList((PointPairList)data[((CheckBox)sender).Name]);
for (int a = 0; a < ppl.Count; a++)
{
ppl[a].Y = ppl[a].Y * (180.0 / Math.PI);
}
myCurve.Points = ppl;
}
double xMin, xMax, yMin, yMax;
myCurve.GetRange(out xMin, out xMax, out yMin, out yMax, true, false, zg1.GraphPane);
if (yMin > 900 && yMax < 2100 && yMin < 2100)
{
myCurve.IsY2Axis = true;
myCurve.YAxisIndex = 0;
zg1.GraphPane.Y2Axis.IsVisible = true;
}
}
else
{
selection.Remove(((CheckBox)sender).Name);
foreach (var item in zg1.GraphPane.CurveList)
{
if (item.Tag == ((CheckBox)sender).Name)
{
zg1.GraphPane.CurveList.Remove(item);
break;
}
}
}
try
{
// fix new line types
ThemeManager.ApplyThemeTo(this);
zg1.Invalidate();
zg1.AxisChange();
}
catch { }
}
int x = 10;
int y = 10;
@ -806,7 +939,8 @@ namespace ArdupilotMega
Name = "select",
Width = 50,
Height = 500,
Text = "Graph This"
Text = "Graph This",
TopLevel = true
};
x = 10;

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

View File

@ -123,12 +123,17 @@ namespace ArdupilotMega
zg1.GraphPane.XAxis.MinorTic.Color = Color.White;
zg1.GraphPane.YAxis.MajorTic.Color = Color.White;
zg1.GraphPane.YAxis.MinorTic.Color = Color.White;
zg1.GraphPane.Y2Axis.MajorTic.Color = Color.White;
zg1.GraphPane.Y2Axis.MinorTic.Color = Color.White;
zg1.GraphPane.XAxis.MajorGrid.Color = Color.White;
zg1.GraphPane.YAxis.MajorGrid.Color = Color.White;
zg1.GraphPane.Y2Axis.MajorGrid.Color = Color.White;
zg1.GraphPane.YAxis.Scale.FontSpec.FontColor = Color.White;
zg1.GraphPane.YAxis.Title.FontSpec.FontColor = Color.White;
zg1.GraphPane.Y2Axis.Title.FontSpec.FontColor = Color.White;
zg1.GraphPane.Y2Axis.Scale.FontSpec.FontColor = Color.White;
zg1.GraphPane.XAxis.Scale.FontSpec.FontColor = Color.White;
zg1.GraphPane.XAxis.Title.FontSpec.FontColor = Color.White;

View File

@ -93,6 +93,190 @@
<F1>FlightMode</F1>
<F2>Thr Cruise</F2>
</MOD>
<PID-1>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-1>
<PID-2>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-2>
<PID-3>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-3>
<PID-4>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-4>
<PID-5>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-5>
<PID-6>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-6>
<PID-7>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-7>
<PID-8>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-8>
<PID-9>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-9>
<PID-10>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-10>
<PID-11>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-11>
<PID-12>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-12>
<PID-13>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-13>
<PID-14>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-14>
<PID-15>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-15>
<PID-16>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-16>
<PID-17>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-17>
<PID-18>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-18>
<PID-19>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-19>
<PID-20>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-20>
<PID-21>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-21>
<PID-22>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-22>
<PID-23>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-23>
</AC2>
<!-- -->
<APM>

View File

@ -11,8 +11,8 @@
<Link>
<href>http://127.0.0.1:56781/network.kml</href>
<refreshMode>onInterval</refreshMode>
<refreshInterval>1</refreshInterval>
<viewRefreshTime>1</viewRefreshTime>
<refreshInterval>0.3</refreshInterval>
<viewRefreshTime>0.3</viewRefreshTime>
</Link>
</NetworkLink>
</Folder>

View File

@ -93,6 +93,190 @@
<F1>FlightMode</F1>
<F2>Thr Cruise</F2>
</MOD>
<PID-1>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-1>
<PID-2>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-2>
<PID-3>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-3>
<PID-4>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-4>
<PID-5>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-5>
<PID-6>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-6>
<PID-7>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-7>
<PID-8>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-8>
<PID-9>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-9>
<PID-10>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-10>
<PID-11>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-11>
<PID-12>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-12>
<PID-13>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-13>
<PID-14>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-14>
<PID-15>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-15>
<PID-16>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-16>
<PID-17>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-17>
<PID-18>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-18>
<PID-19>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-19>
<PID-20>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-20>
<PID-21>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-21>
<PID-22>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-22>
<PID-23>
<F1>Err</F1>
<F2>P</F2>
<F3>I</F3>
<F4>D</F4>
<F5>Output</F5>
<F6>Gain</F6>
</PID-23>
</AC2>
<!-- -->
<APM>

View File

@ -26,7 +26,7 @@ namespace ArdupilotMega
private TextBox TXT_outputlog;
private MyButton BUT_estoffset;
int latpos = 5, lngpos = 4, altpos = 7;
int latpos = 4, lngpos = 5, altpos = 7;
internal Georefimage() {
InitializeComponent();
@ -247,17 +247,25 @@ namespace ArdupilotMega
matchs++;
SharpKml.Dom.Timestamp tstamp = new SharpKml.Dom.Timestamp();
tstamp.When = dt;
kml.AddFeature(
new Placemark()
{
Time = tstamp ,
Name = Path.GetFileNameWithoutExtension(file),
Geometry = new SharpKml.Dom.Point()
{
Coordinate = new Vector(double.Parse(arr[lngpos]), double.Parse(arr[latpos]), double.Parse(arr[altpos]))
}
}
);
sw2.WriteLine(Path.GetFileNameWithoutExtension(file) + " " + arr[lngpos] + " " + arr[latpos] + " " + arr[altpos]);
sw.WriteLine(Path.GetFileNameWithoutExtension(file) + "\t" + crap.ToString("yyyy:MM:dd HH:mm:ss") + "\t" + arr[lngpos] + "\t" + arr[latpos] + "\t" + arr[altpos]);
sw.Flush();
@ -345,7 +353,7 @@ namespace ArdupilotMega
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 = "0";
this.TXT_offsetseconds.Text = "-86158";
//
// BUT_doit
//
@ -389,7 +397,7 @@ namespace ArdupilotMega
this.BUT_estoffset.UseVisualStyleBackColor = true;
this.BUT_estoffset.Click += new System.EventHandler(this.BUT_estoffset_Click);
//
// georefimage
// Georefimage
//
this.ClientSize = new System.Drawing.Size(453, 299);
this.Controls.Add(this.BUT_estoffset);

View File

@ -11,8 +11,8 @@
<Link>
<href>http://127.0.0.1:56781/network.kml</href>
<refreshMode>onInterval</refreshMode>
<refreshInterval>1</refreshInterval>
<viewRefreshTime>1</viewRefreshTime>
<refreshInterval>0.3</refreshInterval>
<viewRefreshTime>0.3</viewRefreshTime>
</Link>
</NetworkLink>
</Folder>