2012-03-01 09:27:03 -04:00
|
|
|
|
using System;
|
|
|
|
|
using System.Collections.Generic;
|
|
|
|
|
using System.Linq;
|
|
|
|
|
using System.Text;
|
|
|
|
|
using System.Windows.Forms;
|
|
|
|
|
using System.IO;
|
2012-03-03 03:42:41 -04:00
|
|
|
|
using System.Collections;
|
2012-03-01 09:27:03 -04:00
|
|
|
|
|
|
|
|
|
namespace ArdupilotMega
|
|
|
|
|
{
|
|
|
|
|
public class MagCalib
|
|
|
|
|
{
|
|
|
|
|
|
|
|
|
|
//alglib.lsfit.
|
|
|
|
|
|
|
|
|
|
public static void doWork()
|
|
|
|
|
{
|
|
|
|
|
// based of tridge's work
|
|
|
|
|
|
|
|
|
|
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>>();
|
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
Hashtable filter = new Hashtable();
|
2012-03-01 09:27:03 -04:00
|
|
|
|
|
|
|
|
|
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
|
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
openFileDialog1.FileName = @"C:\Users\hog\Downloads\2012-02-05.log";
|
|
|
|
|
|
2012-03-01 09:27:03 -04:00
|
|
|
|
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
|
|
|
|
|
|
|
|
|
|
// gather data
|
|
|
|
|
while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
|
|
|
|
|
{
|
|
|
|
|
// bar moves to 100 % in this step
|
|
|
|
|
//progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f / 1.0f);
|
|
|
|
|
|
|
|
|
|
//progressBar1.Refresh();
|
|
|
|
|
//Application.DoEvents();
|
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
byte[] packetraw = mine.readPacket();
|
|
|
|
|
|
|
|
|
|
var packet = mine.DebugPacket(packetraw);
|
2012-03-01 09:27:03 -04:00
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
if (packet == null)
|
|
|
|
|
continue;
|
2012-03-01 09:27:03 -04:00
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
if (packet.GetType() == typeof(MAVLink.__mavlink_sensor_offsets_t))
|
2012-03-01 09:27:03 -04:00
|
|
|
|
{
|
|
|
|
|
offset = new Tuple<float,float,float>(
|
2012-03-03 03:42:41 -04:00
|
|
|
|
((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_x,
|
|
|
|
|
((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_y,
|
|
|
|
|
((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_z);
|
2012-03-01 09:27:03 -04:00
|
|
|
|
}
|
2012-03-03 03:42:41 -04:00
|
|
|
|
else if (packet.GetType() == typeof(MAVLink.__mavlink_raw_imu_t))
|
2012-03-01 09:27:03 -04:00
|
|
|
|
{
|
2012-03-03 03:42:41 -04:00
|
|
|
|
int div = 20;
|
2012-03-01 09:27:03 -04:00
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
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);
|
2012-03-01 09:27:03 -04:00
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
if (filter.ContainsKey(item))
|
|
|
|
|
{
|
|
|
|
|
filter[item] = (int)filter[item] + 1;
|
2012-03-01 09:27:03 -04:00
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
if ((int)filter[item] > 3)
|
|
|
|
|
continue;
|
|
|
|
|
}
|
|
|
|
|
else
|
|
|
|
|
{
|
|
|
|
|
filter[item] = 1;
|
|
|
|
|
}
|
|
|
|
|
|
2012-03-01 09:27:03 -04:00
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
data.Add(new Tuple<float, float, float>(
|
|
|
|
|
((MAVLink.__mavlink_raw_imu_t)packet).xmag - offset.Item1,
|
|
|
|
|
((MAVLink.__mavlink_raw_imu_t)packet).ymag - offset.Item2,
|
|
|
|
|
((MAVLink.__mavlink_raw_imu_t)packet).zmag - offset.Item3));
|
|
|
|
|
}
|
2012-03-01 09:27:03 -04:00
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
}
|
2012-03-01 09:27:03 -04:00
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
Console.WriteLine("Extracted " + data.Count + " data points");
|
|
|
|
|
Console.WriteLine("Current offset: " + offset);
|
2012-03-01 09:27:03 -04:00
|
|
|
|
|
|
|
|
|
mine.logreadmode = false;
|
|
|
|
|
mine.logplaybackfile.Close();
|
|
|
|
|
mine.logplaybackfile = null;
|
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
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;
|
|
|
|
|
|
|
|
|
|
|
2012-03-01 09:27:03 -04:00
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2012-03-03 03:42:41 -04:00
|
|
|
|
public static void sphere_error(double[] xi, double[] fi, object obj)
|
2012-03-01 09:27:03 -04:00
|
|
|
|
{
|
2012-03-03 03:42:41 -04:00
|
|
|
|
double xofs = xi[0];
|
|
|
|
|
double yofs = xi[1];
|
|
|
|
|
double zofs = xi[2];
|
|
|
|
|
double r = xi[3];
|
|
|
|
|
int a = 0;
|
|
|
|
|
foreach (var d in (List<Tuple<float, float, float>>)obj)
|
2012-03-01 09:27:03 -04:00
|
|
|
|
{
|
2012-03-03 03:42:41 -04:00
|
|
|
|
double x = d.Item1;
|
|
|
|
|
double y = d.Item2;
|
|
|
|
|
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++;
|
2012-03-01 09:27:03 -04:00
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|