mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
APM Planner 1.1.47
fix Updater
This commit is contained in:
parent
c2fa44d24e
commit
0087d0533a
@ -86,7 +86,7 @@
|
|||||||
<SignManifests>false</SignManifests>
|
<SignManifests>false</SignManifests>
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
<PropertyGroup>
|
<PropertyGroup>
|
||||||
<SignAssembly>true</SignAssembly>
|
<SignAssembly>false</SignAssembly>
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
<PropertyGroup />
|
<PropertyGroup />
|
||||||
<PropertyGroup>
|
<PropertyGroup>
|
||||||
@ -118,6 +118,10 @@
|
|||||||
<ApplicationManifest>Properties\app.manifest</ApplicationManifest>
|
<ApplicationManifest>Properties\app.manifest</ApplicationManifest>
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
<ItemGroup>
|
<ItemGroup>
|
||||||
|
<Reference Include="alglibnet2, Version=0.0.0.0, Culture=neutral, processorArchitecture=MSIL">
|
||||||
|
<SpecificVersion>False</SpecificVersion>
|
||||||
|
<HintPath>Lib\alglibnet2.dll</HintPath>
|
||||||
|
</Reference>
|
||||||
<Reference Include="BSE.Windows.Forms">
|
<Reference Include="BSE.Windows.Forms">
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\BSE.Windows.Forms.dll</HintPath>
|
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\BSE.Windows.Forms.dll</HintPath>
|
||||||
</Reference>
|
</Reference>
|
||||||
|
@ -4,6 +4,7 @@ using System.Linq;
|
|||||||
using System.Text;
|
using System.Text;
|
||||||
using System.Windows.Forms;
|
using System.Windows.Forms;
|
||||||
using System.IO;
|
using System.IO;
|
||||||
|
using System.Collections;
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
@ -14,34 +15,12 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
public static void doWork()
|
public static void doWork()
|
||||||
{
|
{
|
||||||
/*
|
|
||||||
double[,] x = new double[,] { { -1 }, { -0.8 }, { -0.6 }, { -0.4 }, { -0.2 }, { 0 }, { 0.2 }, { 0.4 }, { 0.6 }, { 0.8 }, { 1.0 } };
|
|
||||||
double[] y = new double[] { 0.223130, 0.382893, 0.582748, 0.786628, 0.941765, 1.000000, 0.941765, 0.786628, 0.582748, 0.382893, 0.223130 };
|
|
||||||
double[] c = new double[] { 0.3 };
|
|
||||||
double epsf = 0;
|
|
||||||
double epsx = 0.000001;
|
|
||||||
int maxits = 0;
|
|
||||||
int info;
|
|
||||||
alglib.lsfitstate state;
|
|
||||||
alglib.lsfitreport rep;
|
|
||||||
double diffstep = 0.0001;
|
|
||||||
|
|
||||||
//
|
|
||||||
// Fitting without weights
|
|
||||||
//
|
|
||||||
alglib.lsfitcreatef(x, y, c, diffstep, out state);
|
|
||||||
alglib.lsfitsetcond(state, epsf, epsx, maxits);
|
|
||||||
alglib.lsfitfit(state, function_cx_1_func, null, null);
|
|
||||||
alglib.lsfitresults(state, out info, out c, out rep);
|
|
||||||
System.Console.WriteLine("{0}", info); // EXPECTED: 2
|
|
||||||
System.Console.WriteLine("{0}", alglib.ap.format(c, 1)); // EXPECTED: [1.5]
|
|
||||||
*/
|
|
||||||
|
|
||||||
// based of tridge's work
|
// based of tridge's work
|
||||||
|
|
||||||
Tuple<float, float, float> offset = new Tuple<float, float, float>(0, 0, 0);
|
Tuple<float, float, float> offset = new Tuple<float, float, float>(0, 0, 0);
|
||||||
List<Tuple<float, float, float>> data = new List<Tuple<float, float, float>>();
|
List<Tuple<float, float, float>> data = new List<Tuple<float, float, float>>();
|
||||||
|
|
||||||
|
Hashtable filter = new Hashtable();
|
||||||
|
|
||||||
OpenFileDialog openFileDialog1 = new OpenFileDialog();
|
OpenFileDialog openFileDialog1 = new OpenFileDialog();
|
||||||
openFileDialog1.Filter = "*.tlog|*.tlog";
|
openFileDialog1.Filter = "*.tlog|*.tlog";
|
||||||
@ -54,6 +33,8 @@ namespace ArdupilotMega
|
|||||||
}
|
}
|
||||||
catch { } // incase dir doesnt exist
|
catch { } // incase dir doesnt exist
|
||||||
|
|
||||||
|
openFileDialog1.FileName = @"C:\Users\hog\Downloads\2012-02-05.log";
|
||||||
|
|
||||||
if (openFileDialog1.ShowDialog() == DialogResult.OK)
|
if (openFileDialog1.ShowDialog() == DialogResult.OK)
|
||||||
{
|
{
|
||||||
foreach (string logfile in openFileDialog1.FileNames)
|
foreach (string logfile in openFileDialog1.FileNames)
|
||||||
@ -74,65 +55,97 @@ namespace ArdupilotMega
|
|||||||
//progressBar1.Refresh();
|
//progressBar1.Refresh();
|
||||||
//Application.DoEvents();
|
//Application.DoEvents();
|
||||||
|
|
||||||
byte[] packet = mine.readPacket();
|
byte[] packetraw = mine.readPacket();
|
||||||
|
|
||||||
var pack = mine.DebugPacket(packet);
|
var packet = mine.DebugPacket(packetraw);
|
||||||
|
|
||||||
if (pack.GetType() == typeof(MAVLink.__mavlink_sensor_offsets_t))
|
if (packet == null)
|
||||||
|
continue;
|
||||||
|
|
||||||
|
if (packet.GetType() == typeof(MAVLink.__mavlink_sensor_offsets_t))
|
||||||
{
|
{
|
||||||
offset = new Tuple<float,float,float>(
|
offset = new Tuple<float,float,float>(
|
||||||
((MAVLink.__mavlink_sensor_offsets_t)pack).mag_ofs_x,
|
((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_x,
|
||||||
((MAVLink.__mavlink_sensor_offsets_t)pack).mag_ofs_y,
|
((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_y,
|
||||||
((MAVLink.__mavlink_sensor_offsets_t)pack).mag_ofs_z);
|
((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_z);
|
||||||
}
|
}
|
||||||
else if (pack.GetType() == typeof(MAVLink.__mavlink_raw_imu_t))
|
else if (packet.GetType() == typeof(MAVLink.__mavlink_raw_imu_t))
|
||||||
{
|
{
|
||||||
|
int div = 20;
|
||||||
|
|
||||||
|
string item = (int)(((MAVLink.__mavlink_raw_imu_t)packet).xmag / div) + "," +
|
||||||
|
(int)(((MAVLink.__mavlink_raw_imu_t)packet).ymag / div) + "," +
|
||||||
|
(int)(((MAVLink.__mavlink_raw_imu_t)packet).zmag / div);
|
||||||
|
|
||||||
|
if (filter.ContainsKey(item))
|
||||||
|
{
|
||||||
|
filter[item] = (int)filter[item] + 1;
|
||||||
|
|
||||||
|
if ((int)filter[item] > 3)
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
filter[item] = 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
data.Add(new Tuple<float, float, float>(
|
data.Add(new Tuple<float, float, float>(
|
||||||
((MAVLink.__mavlink_raw_imu_t)pack).xmag - offset.Item1,
|
((MAVLink.__mavlink_raw_imu_t)packet).xmag - offset.Item1,
|
||||||
((MAVLink.__mavlink_raw_imu_t)pack).ymag - offset.Item2,
|
((MAVLink.__mavlink_raw_imu_t)packet).ymag - offset.Item2,
|
||||||
((MAVLink.__mavlink_raw_imu_t)pack).zmag - offset.Item3));
|
((MAVLink.__mavlink_raw_imu_t)packet).zmag - offset.Item3));
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Console.WriteLine("Extracted " + data.Count + " data points");
|
||||||
|
Console.WriteLine("Current offset: " + offset);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//progressBar1.Value = 100;
|
|
||||||
|
|
||||||
mine.logreadmode = false;
|
mine.logreadmode = false;
|
||||||
mine.logplaybackfile.Close();
|
mine.logplaybackfile.Close();
|
||||||
mine.logplaybackfile = null;
|
mine.logplaybackfile = null;
|
||||||
|
|
||||||
|
double[] x = new double[] { 0, 0, 0, 0 };
|
||||||
|
double epsg = 0.0000000001;
|
||||||
|
double epsf = 0;
|
||||||
|
double epsx = 0;
|
||||||
|
int maxits = 0;
|
||||||
|
alglib.minlmstate state;
|
||||||
|
alglib.minlmreport rep;
|
||||||
|
|
||||||
|
alglib.minlmcreatev(data.Count, x, 100, out state);
|
||||||
|
alglib.minlmsetcond(state, epsg, epsf, epsx, maxits);
|
||||||
|
alglib.minlmoptimize(state, sphere_error, null, data);
|
||||||
|
alglib.minlmresults(state, out x, out rep);
|
||||||
|
|
||||||
|
System.Console.WriteLine("{0}", rep.terminationtype); // EXPECTED: 4
|
||||||
|
System.Console.WriteLine("{0}", alglib.ap.format(x, 2)); // EXPECTED: [-3,+3]
|
||||||
|
//System.Console.ReadLine();
|
||||||
|
|
||||||
|
|
||||||
|
// return;
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
public static List<double> sphere_error(double[,] p, double[] data)
|
public static void sphere_error(double[] xi, double[] fi, object obj)
|
||||||
{
|
{
|
||||||
double xofs = p[0, 0];
|
double xofs = xi[0];
|
||||||
double yofs = p[0, 1];
|
double yofs = xi[1];
|
||||||
double zofs = p[0, 2];
|
double zofs = xi[2];
|
||||||
double r = p[0, 3];
|
double r = xi[3];
|
||||||
List<double> ret = new List<double>();
|
int a = 0;
|
||||||
foreach (var d in data)
|
foreach (var d in (List<Tuple<float, float, float>>)obj)
|
||||||
{
|
{
|
||||||
//double x, y, z = d;
|
double x = d.Item1;
|
||||||
//double err = r - Math.Sqrt(Math.Pow((x + xofs), 2) + Math.Pow((y + yofs), 2) + Math.Pow((z + zofs), 2));
|
double y = d.Item2;
|
||||||
//ret.Add(err);
|
double z = d.Item3;
|
||||||
|
double err = r - Math.Sqrt(Math.Pow((x + xofs), 2) + Math.Pow((y + yofs), 2) + Math.Pow((z + zofs), 2));
|
||||||
|
fi[a] = err;
|
||||||
|
a++;
|
||||||
}
|
}
|
||||||
return ret;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public static void function_cx_1_func(double[] c, double[] x, ref double func, object obj)
|
|
||||||
{
|
|
||||||
// this callback calculates f(c,x)=exp(-c0*sqr(x0))
|
|
||||||
// where x is a position on X-axis and c is adjustable parameter
|
|
||||||
func = System.Math.Exp(-c[0] * x[0] * x[0]);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -22,6 +22,7 @@ using System.Threading;
|
|||||||
using System.Net.Sockets;
|
using System.Net.Sockets;
|
||||||
using IronPython.Hosting;
|
using IronPython.Hosting;
|
||||||
using log4net;
|
using log4net;
|
||||||
|
using ArdupilotMega.Controls;
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
@ -1629,12 +1630,12 @@ namespace ArdupilotMega
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
public static void updatecheck(Label loadinglabel)
|
public static void updatecheck(ProgressReporterDialogue frmProgressReporter)
|
||||||
{
|
{
|
||||||
var baseurl = ConfigurationManager.AppSettings["UpdateLocation"];
|
var baseurl = ConfigurationManager.AppSettings["UpdateLocation"];
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
bool update = updatecheck(loadinglabel, baseurl, "");
|
bool update = updatecheck(frmProgressReporter, baseurl, "");
|
||||||
var process = new Process();
|
var process = new Process();
|
||||||
string exePath = Path.GetDirectoryName(Application.ExecutablePath);
|
string exePath = Path.GetDirectoryName(Application.ExecutablePath);
|
||||||
if (MONO)
|
if (MONO)
|
||||||
@ -1659,17 +1660,20 @@ namespace ArdupilotMega
|
|||||||
log.Error("Exception during update", ex);
|
log.Error("Exception during update", ex);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (loadinglabel != null)
|
if (frmProgressReporter != null)
|
||||||
UpdateLabel(loadinglabel, "Starting Updater");
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Starting Updater");
|
||||||
log.Info("Starting new process: " + process.StartInfo.FileName + " with " + process.StartInfo.Arguments);
|
log.Info("Starting new process: " + process.StartInfo.FileName + " with " + process.StartInfo.Arguments);
|
||||||
process.Start();
|
process.Start();
|
||||||
log.Info("Quitting existing process");
|
log.Info("Quitting existing process");
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
Application.Exit();
|
MainV2.instance.BeginInvoke((MethodInvoker)delegate() {
|
||||||
|
Application.Exit();
|
||||||
|
});
|
||||||
}
|
}
|
||||||
catch
|
catch
|
||||||
{
|
{
|
||||||
|
Application.Exit();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch (Exception ex)
|
catch (Exception ex)
|
||||||
@ -1719,10 +1723,25 @@ namespace ArdupilotMega
|
|||||||
{
|
{
|
||||||
var fi = new FileInfo(path);
|
var fi = new FileInfo(path);
|
||||||
|
|
||||||
log.Info(response.Headers[HttpResponseHeader.ETag]);
|
string CurrentEtag = "";
|
||||||
|
|
||||||
if (fi.Length != response.ContentLength) // && response.Headers[HttpResponseHeader.ETag] != "0")
|
if (File.Exists(path + ".etag"))
|
||||||
{
|
{
|
||||||
|
using (Stream fs = File.OpenRead(path + ".etag"))
|
||||||
|
{
|
||||||
|
using (StreamReader sr = new StreamReader(fs))
|
||||||
|
{
|
||||||
|
CurrentEtag = sr.ReadLine();
|
||||||
|
sr.Close();
|
||||||
|
}
|
||||||
|
fs.Close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (fi.Length != response.ContentLength && response.Headers[HttpResponseHeader.ETag] != CurrentEtag)
|
||||||
|
{
|
||||||
|
log.Debug("New file Check: " + fi.Length + " vs " + response.ContentLength + " " + response.Headers[HttpResponseHeader.ETag] + " vs " + CurrentEtag);
|
||||||
|
|
||||||
using (var sw = new StreamWriter(path + ".etag"))
|
using (var sw = new StreamWriter(path + ".etag"))
|
||||||
{
|
{
|
||||||
sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
||||||
@ -1757,46 +1776,28 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
public static void DoUpdate()
|
public static void DoUpdate()
|
||||||
{
|
{
|
||||||
var loading = new Form
|
ProgressReporterDialogue frmProgressReporter = new ProgressReporterDialogue()
|
||||||
{
|
{
|
||||||
|
Text = "Check for Updates",
|
||||||
Width = 400,
|
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen
|
||||||
Height = 150,
|
|
||||||
StartPosition = FormStartPosition.CenterScreen,
|
|
||||||
TopMost = true,
|
|
||||||
MinimizeBox = false,
|
|
||||||
MaximizeBox = false
|
|
||||||
};
|
};
|
||||||
var resources = new ComponentResourceManager(typeof(MainV2));
|
|
||||||
loading.Icon = ((Icon)(resources.GetObject("$this.Icon")));
|
|
||||||
|
|
||||||
var loadinglabel = new Label
|
MainV2.fixtheme(frmProgressReporter);
|
||||||
{
|
|
||||||
Location = new System.Drawing.Point(50, 40),
|
|
||||||
Name = "load",
|
|
||||||
AutoSize = true,
|
|
||||||
Text = "Checking...",
|
|
||||||
Size = new System.Drawing.Size(100, 20)
|
|
||||||
};
|
|
||||||
|
|
||||||
loading.Controls.Add(loadinglabel);
|
frmProgressReporter.DoWork += new Controls.ProgressReporterDialogue.DoWorkEventHandler(frmProgressReporter_DoWork);
|
||||||
loading.Show();
|
|
||||||
|
|
||||||
try
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Checking for Updates");
|
||||||
{
|
|
||||||
MainV2.updatecheck(loadinglabel);
|
frmProgressReporter.RunBackgroundOperationAsync();
|
||||||
}
|
|
||||||
catch (Exception ex)
|
|
||||||
{
|
|
||||||
log.Error("Error in updatecheck", ex);
|
|
||||||
}
|
|
||||||
//);
|
|
||||||
//t12.Name = "Update check thread";
|
|
||||||
//t12.Start();
|
|
||||||
//MainV2.threads.Add(t12);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
private static bool updatecheck(Label loadinglabel, string baseurl, string subdir)
|
static void frmProgressReporter_DoWork(object sender, Controls.ProgressWorkerEventArgs e)
|
||||||
|
{
|
||||||
|
((ProgressReporterDialogue)sender).UpdateProgressAndStatus(-1, "Getting Base URL");
|
||||||
|
MainV2.updatecheck((ProgressReporterDialogue)sender);
|
||||||
|
}
|
||||||
|
|
||||||
|
private static bool updatecheck(ProgressReporterDialogue frmProgressReporter, string baseurl, string subdir)
|
||||||
{
|
{
|
||||||
bool update = false;
|
bool update = false;
|
||||||
List<string> files = new List<string>();
|
List<string> files = new List<string>();
|
||||||
@ -1845,17 +1846,23 @@ namespace ArdupilotMega
|
|||||||
Directory.CreateDirectory(dir);
|
Directory.CreateDirectory(dir);
|
||||||
foreach (string file in files)
|
foreach (string file in files)
|
||||||
{
|
{
|
||||||
|
if (frmProgressReporter.doWorkArgs.CancelRequested)
|
||||||
|
{
|
||||||
|
frmProgressReporter.doWorkArgs.CancelAcknowledged = true;
|
||||||
|
throw new Exception("Cancel");
|
||||||
|
}
|
||||||
|
|
||||||
if (file.Equals("/"))
|
if (file.Equals("/"))
|
||||||
{
|
{
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
if (file.EndsWith("/"))
|
if (file.EndsWith("/"))
|
||||||
{
|
{
|
||||||
update = updatecheck(loadinglabel, baseurl + file, subdir.Replace('/', Path.DirectorySeparatorChar) + file) && update;
|
update = updatecheck(frmProgressReporter, baseurl + file, subdir.Replace('/', Path.DirectorySeparatorChar) + file) && update;
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
if (loadinglabel != null)
|
if (frmProgressReporter != null)
|
||||||
UpdateLabel(loadinglabel, "Checking " + file);
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Checking " + file);
|
||||||
|
|
||||||
string path = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + subdir + file;
|
string path = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + subdir + file;
|
||||||
|
|
||||||
@ -1876,26 +1883,44 @@ namespace ArdupilotMega
|
|||||||
//dataStream = response.GetResponseStream();
|
//dataStream = response.GetResponseStream();
|
||||||
// Open the stream using a StreamReader for easy access.
|
// Open the stream using a StreamReader for easy access.
|
||||||
|
|
||||||
bool getfile = false;
|
bool updateThisFile = false;
|
||||||
|
|
||||||
if (File.Exists(path))
|
if (File.Exists(path))
|
||||||
{
|
{
|
||||||
FileInfo fi = new FileInfo(path);
|
FileInfo fi = new FileInfo(path);
|
||||||
|
|
||||||
log.Info(response.Headers[HttpResponseHeader.ETag]);
|
//log.Info(response.Headers[HttpResponseHeader.ETag]);
|
||||||
|
string CurrentEtag = "";
|
||||||
|
|
||||||
if (fi.Length != response.ContentLength) // && response.Headers[HttpResponseHeader.ETag] != "0")
|
if (File.Exists(path + ".etag"))
|
||||||
{
|
{
|
||||||
StreamWriter sw = new StreamWriter(path + ".etag");
|
using (Stream fs = File.OpenRead(path + ".etag"))
|
||||||
sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
{
|
||||||
sw.Close();
|
using (StreamReader sr = new StreamReader(fs))
|
||||||
getfile = true;
|
{
|
||||||
|
CurrentEtag = sr.ReadLine();
|
||||||
|
sr.Close();
|
||||||
|
}
|
||||||
|
fs.Close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (fi.Length != response.ContentLength && response.Headers[HttpResponseHeader.ETag] != CurrentEtag)
|
||||||
|
{
|
||||||
|
log.Debug("New file Check: " + fi.Length + " vs " + response.ContentLength + " " + response.Headers[HttpResponseHeader.ETag] + " vs " + CurrentEtag);
|
||||||
|
|
||||||
|
using (StreamWriter sw = new StreamWriter(path + ".etag"))
|
||||||
|
{
|
||||||
|
sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
||||||
|
sw.Close();
|
||||||
|
}
|
||||||
|
updateThisFile = true;
|
||||||
log.Info("NEW FILE " + file);
|
log.Info("NEW FILE " + file);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
getfile = true;
|
updateThisFile = true;
|
||||||
log.Info("NEW FILE " + file);
|
log.Info("NEW FILE " + file);
|
||||||
// get it
|
// get it
|
||||||
}
|
}
|
||||||
@ -1904,7 +1929,7 @@ namespace ArdupilotMega
|
|||||||
//dataStream.Close();
|
//dataStream.Close();
|
||||||
response.Close();
|
response.Close();
|
||||||
|
|
||||||
if (getfile)
|
if (updateThisFile)
|
||||||
{
|
{
|
||||||
if (!update)
|
if (!update)
|
||||||
{
|
{
|
||||||
@ -1918,16 +1943,21 @@ namespace ArdupilotMega
|
|||||||
// return;
|
// return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (loadinglabel != null)
|
if (frmProgressReporter != null)
|
||||||
UpdateLabel(loadinglabel, "Getting " + file);
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Getting " + file);
|
||||||
|
|
||||||
// from head
|
// from head
|
||||||
long bytes = response.ContentLength;
|
long bytes = response.ContentLength;
|
||||||
|
|
||||||
// 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 = HttpWebRequest.Create(baseurl + file);
|
||||||
// Set the Method property of the request to POST.
|
// Set the Method property of the request to POST.
|
||||||
request.Method = "GET";
|
request.Method = "GET";
|
||||||
|
|
||||||
|
((HttpWebRequest)request).AutomaticDecompression = DecompressionMethods.GZip | DecompressionMethods.Deflate;
|
||||||
|
|
||||||
|
request.Headers.Add("Accept-Encoding", "gzip,deflate");
|
||||||
|
|
||||||
// Get the response.
|
// Get the response.
|
||||||
response = request.GetResponse();
|
response = request.GetResponse();
|
||||||
// Display the status.
|
// Display the status.
|
||||||
@ -1951,8 +1981,8 @@ namespace ArdupilotMega
|
|||||||
{
|
{
|
||||||
if (dt.Second != DateTime.Now.Second)
|
if (dt.Second != DateTime.Now.Second)
|
||||||
{
|
{
|
||||||
if (loadinglabel != null)
|
if (frmProgressReporter != null)
|
||||||
UpdateLabel(loadinglabel, "Getting " + file + ": " + (((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%"); //+ Math.Abs(bytes) + " bytes");
|
frmProgressReporter.UpdateProgressAndStatus((int)(((double)(contlen - bytes) / (double)contlen) * 100), "Getting " + file + ": " + (((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%"); //+ Math.Abs(bytes) + " bytes");
|
||||||
dt = DateTime.Now;
|
dt = DateTime.Now;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -1978,11 +2008,6 @@ namespace ArdupilotMega
|
|||||||
return update;
|
return update;
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
private void toolStripMenuItem3_Click(object sender, EventArgs e)
|
|
||||||
{
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
|
protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
|
||||||
|
10
Tools/ArdupilotMegaPlanner/MavlinkLog.Designer.cs
generated
10
Tools/ArdupilotMegaPlanner/MavlinkLog.Designer.cs
generated
@ -32,6 +32,7 @@
|
|||||||
this.BUT_redokml = new ArdupilotMega.MyButton();
|
this.BUT_redokml = new ArdupilotMega.MyButton();
|
||||||
this.progressBar1 = new System.Windows.Forms.ProgressBar();
|
this.progressBar1 = new System.Windows.Forms.ProgressBar();
|
||||||
this.BUT_humanreadable = new ArdupilotMega.MyButton();
|
this.BUT_humanreadable = new ArdupilotMega.MyButton();
|
||||||
|
this.BUT_graphmavlog = new ArdupilotMega.MyButton();
|
||||||
this.SuspendLayout();
|
this.SuspendLayout();
|
||||||
//
|
//
|
||||||
// BUT_redokml
|
// BUT_redokml
|
||||||
@ -53,10 +54,18 @@
|
|||||||
this.BUT_humanreadable.UseVisualStyleBackColor = true;
|
this.BUT_humanreadable.UseVisualStyleBackColor = true;
|
||||||
this.BUT_humanreadable.Click += new System.EventHandler(this.BUT_humanreadable_Click);
|
this.BUT_humanreadable.Click += new System.EventHandler(this.BUT_humanreadable_Click);
|
||||||
//
|
//
|
||||||
|
// BUT_graphmavlog
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.BUT_graphmavlog, "BUT_graphmavlog");
|
||||||
|
this.BUT_graphmavlog.Name = "BUT_graphmavlog";
|
||||||
|
this.BUT_graphmavlog.UseVisualStyleBackColor = true;
|
||||||
|
this.BUT_graphmavlog.Click += new System.EventHandler(this.BUT_graphmavlog_Click);
|
||||||
|
//
|
||||||
// MavlinkLog
|
// MavlinkLog
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this, "$this");
|
resources.ApplyResources(this, "$this");
|
||||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||||
|
this.Controls.Add(this.BUT_graphmavlog);
|
||||||
this.Controls.Add(this.BUT_humanreadable);
|
this.Controls.Add(this.BUT_humanreadable);
|
||||||
this.Controls.Add(this.progressBar1);
|
this.Controls.Add(this.progressBar1);
|
||||||
this.Controls.Add(this.BUT_redokml);
|
this.Controls.Add(this.BUT_redokml);
|
||||||
@ -71,5 +80,6 @@
|
|||||||
private MyButton BUT_redokml;
|
private MyButton BUT_redokml;
|
||||||
private System.Windows.Forms.ProgressBar progressBar1;
|
private System.Windows.Forms.ProgressBar progressBar1;
|
||||||
private MyButton BUT_humanreadable;
|
private MyButton BUT_humanreadable;
|
||||||
|
private MyButton BUT_graphmavlog;
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -512,5 +512,88 @@ namespace ArdupilotMega
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private void BUT_graphmavlog_Click(object sender, EventArgs e)
|
||||||
|
{
|
||||||
|
OpenFileDialog openFileDialog1 = new OpenFileDialog();
|
||||||
|
openFileDialog1.Filter = "*.tlog|*.tlog";
|
||||||
|
openFileDialog1.FilterIndex = 2;
|
||||||
|
openFileDialog1.RestoreDirectory = true;
|
||||||
|
openFileDialog1.Multiselect = true;
|
||||||
|
try
|
||||||
|
{
|
||||||
|
openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar;
|
||||||
|
}
|
||||||
|
catch { } // incase dir doesnt exist
|
||||||
|
|
||||||
|
if (openFileDialog1.ShowDialog() == DialogResult.OK)
|
||||||
|
{
|
||||||
|
foreach (string logfile in openFileDialog1.FileNames)
|
||||||
|
{
|
||||||
|
|
||||||
|
MAVLink mine = new MAVLink();
|
||||||
|
mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read));
|
||||||
|
mine.logreadmode = true;
|
||||||
|
|
||||||
|
mine.packets.Initialize(); // clear
|
||||||
|
|
||||||
|
CurrentState cs = new CurrentState();
|
||||||
|
|
||||||
|
float oldlatlngalt = 0;
|
||||||
|
|
||||||
|
DateTime appui = DateTime.Now;
|
||||||
|
|
||||||
|
while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
|
||||||
|
{
|
||||||
|
// bar moves to 50 % in this step
|
||||||
|
progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f / 2.0f);
|
||||||
|
progressBar1.Invalidate();
|
||||||
|
progressBar1.Refresh();
|
||||||
|
|
||||||
|
byte[] packet = mine.readPacket();
|
||||||
|
|
||||||
|
cs.datetime = mine.lastlogread;
|
||||||
|
|
||||||
|
cs.UpdateCurrentSettings(null, true, mine);
|
||||||
|
|
||||||
|
if (appui != DateTime.Now)
|
||||||
|
{
|
||||||
|
// cant do entire app as mixes with flightdata timer
|
||||||
|
this.Refresh();
|
||||||
|
appui = DateTime.Now;
|
||||||
|
}
|
||||||
|
|
||||||
|
try
|
||||||
|
{
|
||||||
|
if (MainV2.talk != null)
|
||||||
|
MainV2.talk.SpeakAsyncCancelAll();
|
||||||
|
}
|
||||||
|
catch { } // ignore because of this Exception System.PlatformNotSupportedException: No voice installed on the system or none available with the current security setting.
|
||||||
|
|
||||||
|
if ((float)(cs.lat + cs.lng) != oldlatlngalt
|
||||||
|
&& cs.lat != 0 && cs.lng != 0)
|
||||||
|
{
|
||||||
|
Console.WriteLine(cs.lat + " " + cs.lng + " " + cs.alt + " lah " + (float)(cs.lat + cs.lng) + "!=" + oldlatlngalt);
|
||||||
|
CurrentState cs2 = (CurrentState)cs.Clone();
|
||||||
|
|
||||||
|
flightdata.Add(cs2);
|
||||||
|
|
||||||
|
oldlatlngalt = (cs.lat + cs.lng);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
mine.logreadmode = false;
|
||||||
|
mine.logplaybackfile.Close();
|
||||||
|
mine.logplaybackfile = null;
|
||||||
|
|
||||||
|
Application.DoEvents();
|
||||||
|
|
||||||
|
//writeKML(logfile + ".kml");
|
||||||
|
|
||||||
|
progressBar1.Value = 100;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -135,19 +135,19 @@
|
|||||||
<value>BUT_redokml</value>
|
<value>BUT_redokml</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_redokml.Type" xml:space="preserve">
|
<data name=">>BUT_redokml.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=null</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_redokml.Parent" xml:space="preserve">
|
<data name=">>BUT_redokml.Parent" xml:space="preserve">
|
||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_redokml.ZOrder" xml:space="preserve">
|
<data name=">>BUT_redokml.ZOrder" xml:space="preserve">
|
||||||
<value>2</value>
|
<value>3</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="progressBar1.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="progressBar1.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>10, 42</value>
|
<value>10, 42</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="progressBar1.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="progressBar1.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>313, 26</value>
|
<value>432, 26</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="progressBar1.TabIndex" type="System.Int32, mscorlib">
|
<data name="progressBar1.TabIndex" type="System.Int32, mscorlib">
|
||||||
<value>9</value>
|
<value>9</value>
|
||||||
@ -162,7 +162,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>progressBar1.ZOrder" xml:space="preserve">
|
<data name=">>progressBar1.ZOrder" xml:space="preserve">
|
||||||
<value>1</value>
|
<value>2</value>
|
||||||
</data>
|
</data>
|
||||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||||
<data name="BUT_humanreadable.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_humanreadable.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
@ -184,12 +184,39 @@
|
|||||||
<value>BUT_humanreadable</value>
|
<value>BUT_humanreadable</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_humanreadable.Type" xml:space="preserve">
|
<data name=">>BUT_humanreadable.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=null</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_humanreadable.Parent" xml:space="preserve">
|
<data name=">>BUT_humanreadable.Parent" xml:space="preserve">
|
||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_humanreadable.ZOrder" xml:space="preserve">
|
<data name=">>BUT_humanreadable.ZOrder" xml:space="preserve">
|
||||||
|
<value>1</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_graphmavlog.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
|
<value>NoControl</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_graphmavlog.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>289, 13</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_graphmavlog.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>116, 23</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_graphmavlog.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>11</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_graphmavlog.Text" xml:space="preserve">
|
||||||
|
<value>Graph Log</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_graphmavlog.Name" xml:space="preserve">
|
||||||
|
<value>BUT_graphmavlog</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_graphmavlog.Type" xml:space="preserve">
|
||||||
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_graphmavlog.Parent" xml:space="preserve">
|
||||||
|
<value>$this</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_graphmavlog.ZOrder" xml:space="preserve">
|
||||||
<value>0</value>
|
<value>0</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||||
@ -199,7 +226,7 @@
|
|||||||
<value>6, 13</value>
|
<value>6, 13</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="$this.ClientSize" type="System.Drawing.Size, System.Drawing">
|
<data name="$this.ClientSize" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>335, 82</value>
|
<value>456, 82</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
<data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||||
<value>
|
<value>
|
||||||
|
@ -21,8 +21,11 @@ namespace ArdupilotMega
|
|||||||
[STAThread]
|
[STAThread]
|
||||||
static void Main()
|
static void Main()
|
||||||
{
|
{
|
||||||
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
|
|
||||||
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
|
Application.EnableVisualStyles();
|
||||||
|
XmlConfigurator.Configure();
|
||||||
|
log.Info("******************* Logging Configured *******************");
|
||||||
|
Application.SetCompatibleTextRenderingDefault(false);
|
||||||
|
|
||||||
Application.ThreadException += Application_ThreadException;
|
Application.ThreadException += Application_ThreadException;
|
||||||
|
|
||||||
@ -36,10 +39,6 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
//Common.linearRegression();
|
//Common.linearRegression();
|
||||||
|
|
||||||
Application.EnableVisualStyles();
|
|
||||||
XmlConfigurator.Configure();
|
|
||||||
log.Info("******************* Logging Configured *******************");
|
|
||||||
Application.SetCompatibleTextRenderingDefault(false);
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
Thread.CurrentThread.Name = "Base Thread";
|
Thread.CurrentThread.Name = "Base Thread";
|
||||||
|
@ -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.46")]
|
[assembly: AssemblyFileVersion("1.1.47")]
|
||||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||||
|
@ -29,6 +29,7 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
scope.SetVariable("cs", MainV2.cs);
|
scope.SetVariable("cs", MainV2.cs);
|
||||||
scope.SetVariable("Script", this);
|
scope.SetVariable("Script", this);
|
||||||
|
scope.SetVariable("mavutil", this);
|
||||||
|
|
||||||
engine.CreateScriptSourceFromString("print 'hello world from python'").Execute(scope);
|
engine.CreateScriptSourceFromString("print 'hello world from python'").Execute(scope);
|
||||||
engine.CreateScriptSourceFromString("print cs.roll").Execute(scope);
|
engine.CreateScriptSourceFromString("print cs.roll").Execute(scope);
|
||||||
@ -54,8 +55,22 @@ namespace ArdupilotMega
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public object mavlink_connection(string device, int baud = 115200, int source_system = 255,
|
||||||
|
bool write = false, bool append = false,
|
||||||
|
bool robust_parsing = true, bool notimestamps = false, bool input = true)
|
||||||
|
{
|
||||||
|
|
||||||
public void Sleep(int ms) {
|
return null;
|
||||||
|
}
|
||||||
|
|
||||||
|
public object recv_match(string condition = null, string type = null, bool blocking = false)
|
||||||
|
{
|
||||||
|
|
||||||
|
return null;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void Sleep(int ms)
|
||||||
|
{
|
||||||
System.Threading.Thread.Sleep(ms);
|
System.Threading.Thread.Sleep(ms);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -104,7 +119,8 @@ namespace ArdupilotMega
|
|||||||
public bool WaitFor(string message, int timeout)
|
public bool WaitFor(string message, int timeout)
|
||||||
{
|
{
|
||||||
int timein = 0;
|
int timein = 0;
|
||||||
while (!MainV2.cs.message.Contains(message)) {
|
while (!MainV2.cs.message.Contains(message))
|
||||||
|
{
|
||||||
System.Threading.Thread.Sleep(5);
|
System.Threading.Thread.Sleep(5);
|
||||||
timein += 5;
|
timein += 5;
|
||||||
if (timein > timeout)
|
if (timein > timeout)
|
||||||
@ -114,7 +130,7 @@ namespace ArdupilotMega
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
public bool SendRC(int channel, ushort pwm,bool sendnow)
|
public bool SendRC(int channel, ushort pwm, bool sendnow)
|
||||||
{
|
{
|
||||||
switch (channel)
|
switch (channel)
|
||||||
{
|
{
|
||||||
|
@ -26,16 +26,18 @@ namespace Updater
|
|||||||
|
|
||||||
string path = Path.GetDirectoryName(Application.ExecutablePath);
|
string path = Path.GetDirectoryName(Application.ExecutablePath);
|
||||||
|
|
||||||
UpdateFiles(path);
|
// give 4 seconds grace
|
||||||
|
System.Threading.Thread.Sleep(5000);
|
||||||
|
|
||||||
//if (!UpdateFiles(path))
|
//UpdateFiles(path);
|
||||||
|
|
||||||
|
if (!UpdateFiles(path))
|
||||||
{
|
{
|
||||||
// this fails on mac
|
Console.WriteLine("Update failed, please try it later.");
|
||||||
//Console.WriteLine("Update failed, please try it later.");
|
Console.WriteLine("Press any key to continue.");
|
||||||
//Console.WriteLine("Press any key to continue.");
|
Console.ReadKey();
|
||||||
//Console.ReadKey();
|
|
||||||
}
|
}
|
||||||
//else
|
else
|
||||||
{
|
{
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
|
@ -19,7 +19,7 @@
|
|||||||
<appender name="RollingFile" type="log4net.Appender.RollingFileAppender">
|
<appender name="RollingFile" type="log4net.Appender.RollingFileAppender">
|
||||||
<file value="ArdupilotPlanner.log" />
|
<file value="ArdupilotPlanner.log" />
|
||||||
<appendToFile value="true" />
|
<appendToFile value="true" />
|
||||||
<maximumFileSize value="100KB" />
|
<maximumFileSize value="500KB" />
|
||||||
<maxSizeRollBackups value="2" />
|
<maxSizeRollBackups value="2" />
|
||||||
<layout type="log4net.Layout.PatternLayout">
|
<layout type="log4net.Layout.PatternLayout">
|
||||||
<conversionPattern value="%date %5level %logger - %message (%file:%line) [%thread]%newline" />
|
<conversionPattern value="%date %5level %logger - %message (%file:%line) [%thread]%newline" />
|
||||||
|
@ -1 +1,2 @@
|
|||||||
*.pdb
|
*.pdb
|
||||||
|
*.etag
|
@ -19,7 +19,7 @@
|
|||||||
<appender name="RollingFile" type="log4net.Appender.RollingFileAppender">
|
<appender name="RollingFile" type="log4net.Appender.RollingFileAppender">
|
||||||
<file value="ArdupilotPlanner.log" />
|
<file value="ArdupilotPlanner.log" />
|
||||||
<appendToFile value="true" />
|
<appendToFile value="true" />
|
||||||
<maximumFileSize value="100KB" />
|
<maximumFileSize value="500KB" />
|
||||||
<maxSizeRollBackups value="2" />
|
<maxSizeRollBackups value="2" />
|
||||||
<layout type="log4net.Layout.PatternLayout">
|
<layout type="log4net.Layout.PatternLayout">
|
||||||
<conversionPattern value="%date %5level %logger - %message (%file:%line) [%thread]%newline" />
|
<conversionPattern value="%date %5level %logger - %message (%file:%line) [%thread]%newline" />
|
||||||
|
Binary file not shown.
Loading…
Reference in New Issue
Block a user