public static void SaveOffsets2(double[] ofs)
{
if (MainV2.comPort.MAV.param.ContainsKey("COMPASS_OFS2_X") && MainV2.comPort.BaseStream.IsOpen)
{
try
{
// disable learning
MainV2.comPort.setParam("COMPASS_LEARN", 0);
if (
!MainV2.comPort.SetSensorOffsets(MAVLinkInterface.sensoroffsetsenum.second_magnetometer,
(float) ofs[0], (float) ofs[1], (float) ofs[2]))
{
// set values
MainV2.comPort.setParam("COMPASS_OFS2_X", (float) ofs[0]);
MainV2.comPort.setParam("COMPASS_OFS2_Y", (float) ofs[1]);
MainV2.comPort.setParam("COMPASS_OFS2_Z", (float) ofs[2]);
}
else
{
// Need to reload these params into the param list if SetSensorOffsets() was used
MainV2.comPort.GetParam("COMPASS_OFS2_X");
MainV2.comPort.GetParam("COMPASS_OFS2_Y");
MainV2.comPort.GetParam("COMPASS_OFS2_Z");
}
if (ofs.Length > 3)
{
// ellipsoid
}
}
catch
{
CustomMessageBox.Show("Setting new offsets for compass #2 failed");
return;
}
CustomMessageBox.Show(
"New offsets for compass #2 are " + ofs[0].ToString("0") + " " + ofs[1].ToString("0") + " " +
ofs[2].ToString("0") + "\nThese have been saved for you.", "New Mag Offsets");
}
else
{
CustomMessageBox.Show(
"New offsets for compass #2 are " + ofs[0].ToString("0") + " " + ofs[1].ToString("0") + " " +
ofs[2].ToString("0") + "\n\nPlease write these down for manual entry", "New Mag Offsets");
}
}