static void prd_DoWork(object sender, ProgressWorkerEventArgs e, object passdata = null)
{
// turn learning off
MainV2.comPort.setParam("COMPASS_LEARN", 0);
bool havecompass2 = false;
//compass2 get mag2 offsets
if (MainV2.comPort.MAV.param.ContainsKey("COMPASS_OFS2_X"))
{
//com2ofsx = MainV2.comPort.GetParam("COMPASS_OFS2_X");
//com2ofsy = MainV2.comPort.GetParam("COMPASS_OFS2_Y");
//com2ofsz = MainV2.comPort.GetParam("COMPASS_OFS2_Z");
MainV2.comPort.setParam("COMPASS_OFS2_X", 0);
MainV2.comPort.setParam("COMPASS_OFS2_Y", 0);
MainV2.comPort.setParam("COMPASS_OFS2_Z", 0);
havecompass2 = true;
}
// old method
float minx = 0;
float maxx = 0;
float miny = 0;
float maxy = 0;
float minz = 0;
float maxz = 0;
// backup current rate and set to 10 hz
byte backupratesens = MainV2.comPort.MAV.cs.ratesensors;
MainV2.comPort.MAV.cs.ratesensors = 10;
MainV2.comPort.requestDatastream(MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.comPort.MAV.cs.ratesensors); // mag captures at 10 hz
var sub = MainV2.comPort.SubscribeToPacketType(MAVLink.MAVLINK_MSG_ID.RAW_IMU, ReceviedPacket);
var sub2 = MainV2.comPort.SubscribeToPacketType(MAVLink.MAVLINK_MSG_ID.SCALED_IMU2, ReceviedPacket);
string extramsg = "";
((ProgressReporterSphere)sender).sphere1.Clear();
((ProgressReporterSphere)sender).sphere2.Clear();
int lastcount = 0;
DateTime lastlsq = DateTime.MinValue;
DateTime lastlsq2 = DateTime.MinValue;
HIL.Vector3 centre = new HIL.Vector3();
while (true)
{
// slow down execution
System.Threading.Thread.Sleep(20);
((ProgressReporterDialogue)sender).UpdateProgressAndStatus(-1, "Got " + datacompass1.Count + " Samples " + extramsg);
if (e.CancelRequested)
{
// restore old sensor rate
MainV2.comPort.MAV.cs.ratesensors = backupratesens;
MainV2.comPort.requestDatastream(MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.comPort.MAV.cs.ratesensors);
e.CancelAcknowledged = false;
e.CancelRequested = false;
break;
}
if (datacompass1.Count == 0)
{
continue;
}
// dont use dup data
if (lastcount == datacompass1.Count)
{
continue;
}
lastcount = datacompass1.Count;
float rawmx = datacompass1[datacompass1.Count - 1].Item1;
float rawmy = datacompass1[datacompass1.Count - 1].Item2;
float rawmz = datacompass1[datacompass1.Count - 1].Item3;
// for old method
setMinorMax(rawmx, ref minx, ref maxx);
setMinorMax(rawmy, ref miny, ref maxy);
setMinorMax(rawmz, ref minz, ref maxz);
// get the current estimated centerpoint
//new HIL.Vector3((float)-((maxx + minx) / 2), (float)-((maxy + miny) / 2), (float)-((maxz + minz) / 2));
// run lsq every second when more than 100 datapoints
if (datacompass1.Count > 100 && lastlsq.Second != DateTime.Now.Second)
{
lastlsq = DateTime.Now;
lock (datacompass1)
{
var lsq = MagCalib.LeastSq(datacompass1, false);
// simple validation
if (Math.Abs(lsq[0]) < 999)
{
centre = new HIL.Vector3(lsq[0], lsq[1], lsq[2]);
log.Info("new centre " + centre.ToString());
((ProgressReporterSphere)sender).sphere1.CenterPoint = new OpenTK.Vector3((float)centre.x, (float)centre.y, (float)centre.z);
}
}
}
// run lsq every second when more than 100 datapoints
if (datacompass2.Count > 100 && lastlsq2.Second != DateTime.Now.Second)
{
lastlsq2 = DateTime.Now;
lock (datacompass2)
{
var lsq = MagCalib.LeastSq(datacompass2, false);
// simple validation
if (Math.Abs(lsq[0]) < 999)
{
HIL.Vector3 centre2 = new HIL.Vector3(lsq[0], lsq[1], lsq[2]);
log.Info("new centre2 " + centre2.ToString());
((ProgressReporterSphere)sender).sphere2.CenterPoint = new OpenTK.Vector3((float)centre2.x, (float)centre2.y, (float)centre2.z);
}
}
}
// add to sphere with center correction
((ProgressReporterSphere)sender).sphere1.AddPoint(new OpenTK.Vector3(rawmx, rawmy, rawmz));
((ProgressReporterSphere)sender).sphere1.AimClear();
if (havecompass2 && datacompass2.Count > 0)
{
float raw2mx = datacompass2[datacompass2.Count - 1].Item1;
float raw2my = datacompass2[datacompass2.Count - 1].Item2;
float raw2mz = datacompass2[datacompass2.Count - 1].Item3;
((ProgressReporterSphere)sender).sphere2.AddPoint(new OpenTK.Vector3(raw2mx, raw2my, raw2mz));
((ProgressReporterSphere)sender).sphere2.AimClear();
}
HIL.Vector3 point;
point = new HIL.Vector3(rawmx, rawmy, rawmz) + centre;
//find the mean radius
float radius = 0;
for (int i = 0; i < datacompass1.Count; i++)
{
point = new HIL.Vector3(datacompass1[i].Item1, datacompass1[i].Item2, datacompass1[i].Item3);
radius += (float)(point + centre).length();
}
radius /= datacompass1.Count;
//test that we can find one point near a set of points all around the sphere surface
string displayresult = "";
int factor = 3; // 4 point check 16 points
float max_distance = radius / 3; //pretty generouse
for (int j = 0; j <= factor; j++)
{
double theta = (Math.PI * (j + 0)) / factor;
for (int i = 0; i <= factor; i++)
{
double phi = (2 * Math.PI * i) / factor;
HIL.Vector3 point_sphere = new HIL.Vector3(
(float)(Math.Sin(theta) * Math.Cos(phi) * radius),
(float)(Math.Sin(theta) * Math.Sin(phi) * radius),
(float)(Math.Cos(theta) * radius)) - centre;
//log.DebugFormat("magcalib check - {0} {1} dist {2}", theta * rad2deg, phi * rad2deg, max_distance);
bool found = false;
for (int k = 0; k < datacompass1.Count; k++)
{
point = new HIL.Vector3(datacompass1[k].Item1, datacompass1[k].Item2, datacompass1[k].Item3);
double d = (point_sphere - point).length();
if (d < max_distance)
{
found = true;
break;
}
}
// draw them all
//((ProgressReporterSphere)sender).sphere1.AimFor(new OpenTK.Vector3((float)point_sphere.x, (float)point_sphere.y, (float)point_sphere.z));
if (!found)
{
displayresult = "more data needed " + (theta * rad2deg).ToString("0") + " " + (phi * rad2deg).ToString("0");
((ProgressReporterSphere)sender).sphere1.AimFor(new OpenTK.Vector3((float)point_sphere.x, (float)point_sphere.y, (float)point_sphere.z));
//j = factor;
//break;
}
}
}
extramsg = displayresult;
}
MainV2.comPort.UnSubscribeToPacketType(sub);
MainV2.comPort.UnSubscribeToPacketType(sub2);
if (minx > 0 && maxx > 0 || minx < 0 && maxx < 0 || miny > 0 && maxy > 0 || miny < 0 && maxy < 0 || minz > 0 && maxz > 0 || minz < 0 && maxz < 0)
{
e.ErrorMessage = "Bad compass raw values. Check for magnetic interferance.";
ans = null;
ans2 = null;
return;
}
// restore old sensor rate
MainV2.comPort.MAV.cs.ratesensors = backupratesens;
MainV2.comPort.requestDatastream(MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.comPort.MAV.cs.ratesensors);
if (extramsg != "")
{
if (CustomMessageBox.Show("You are missing data points. do you want to run the calibration anyway?", "run anyway", MessageBoxButtons.YesNo) == DialogResult.No)
{
e.CancelAcknowledged = true;
e.CancelRequested = true;
ans = null;
ans2 = null;
return;
}
}
// remove outlyers
RemoveOutliers(ref datacompass1);
if (havecompass2 && datacompass2.Count > 0)
{
RemoveOutliers(ref datacompass2);
}
if (datacompass1.Count < 10)
{
e.ErrorMessage = "Log does not contain enough data";
ans = null;
ans2 = null;
return;
}
bool ellipsoid = false;
if (MainV2.comPort.MAV.param.ContainsKey("MAG_DIA"))
{
ellipsoid = true;
}
log.Info("Compass 1");
ans = MagCalib.LeastSq(datacompass1, ellipsoid);
if (havecompass2 && datacompass2.Count > 0)
{
log.Info("Compass 2");
ans2 = MagCalib.LeastSq(datacompass2, ellipsoid);
}
}