Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
89 changes: 71 additions & 18 deletions GCSViews/ConfigurationView/ConfigHWCompass.cs
Original file line number Diff line number Diff line change
Expand Up @@ -419,6 +419,9 @@ private void linkLabel1_LinkClicked_1(object sender, LinkLabelLinkClickedEventAr

private List<MAVLink.MAVLinkMessage> mprog = new List<MAVLink.MAVLinkMessage>();
private List<MAVLink.MAVLinkMessage> mrep = new List<MAVLink.MAVLinkMessage>();
private Dictionary<byte, MAVLink.MAG_CAL_STATUS> lastFailureStatus = new Dictionary<byte, MAVLink.MAG_CAL_STATUS>();
private HashSet<byte> _startedCompasses = new HashSet<byte>();
private HashSet<byte> _autosavedCompasses = new HashSet<byte>();

private bool ReceviedPacket(MAVLink.MAVLinkMessage packet)
{
Expand Down Expand Up @@ -465,6 +468,9 @@ private void BUT_OBmagcalstart_Click(object sender, EventArgs e)

mprog.Clear();
mrep.Clear();
lastFailureStatus.Clear();
_startedCompasses.Clear();
_autosavedCompasses.Clear();
horizontalProgressBar1.Value = 0;
horizontalProgressBar2.Value = 0;
horizontalProgressBar3.Value = 0;
Expand Down Expand Up @@ -534,19 +540,23 @@ private void timer1_Tick(object sender, EventArgs e)

try
{
if (item.Key == 0)
horizontalProgressBar1.Value = obj.completion_pct;
if (item.Key == 1)
horizontalProgressBar2.Value = obj.completion_pct;
if (item.Key == 2)
horizontalProgressBar3.Value = obj.completion_pct;
if (!_autosavedCompasses.Contains(item.Key))
{
if (item.Key == 0)
horizontalProgressBar1.Value = obj.completion_pct;
if (item.Key == 1)
horizontalProgressBar2.Value = obj.completion_pct;
if (item.Key == 2)
horizontalProgressBar3.Value = obj.completion_pct;
}
}
catch { }

message += "id:" + item.Key + " " + obj.completion_pct.ToString() + "% ";
_startedCompasses.Add(item.Key);
compasscount++;
}
lbl_obmagresult.AppendText(message + "\n");
lbl_obmagresult.AppendText(message + Environment.NewLine);
}

lock (mrep)
Expand All @@ -557,49 +567,92 @@ private void timer1_Tick(object sender, EventArgs e)
{
var obj = (MAVLink.mavlink_mag_cal_report_t)item.data;

if (obj.compass_id == 0 && obj.ofs_x == 0)
if (obj.compass_id == 0 && obj.ofs_x == 0 && obj.ofs_y == 0 && obj.ofs_z == 0
&& obj.cal_status == (byte)MAVLink.MAG_CAL_STATUS.MAG_CAL_NOT_STARTED)
continue;

status[obj.compass_id] = item;
}

// message for user
var failedCompassIds = new List<byte>();
foreach (var item in status.Values)
{
var obj = (MAVLink.mavlink_mag_cal_report_t)item.data;

lbl_obmagresult.AppendText("id:" + obj.compass_id + " x:" + obj.ofs_x.ToString("0.0") + " y:" +
obj.ofs_y.ToString("0.0") + " z:" +
obj.ofs_z.ToString("0.0") + " fit:" + obj.fitness.ToString("0.0") + " " +
(MAVLink.MAG_CAL_STATUS)obj.cal_status + "\n");
(MAVLink.MAG_CAL_STATUS)obj.cal_status + Environment.NewLine);

try
{
if (obj.compass_id == 0)
horizontalProgressBar1.Value = 100;
if (obj.compass_id == 1)
horizontalProgressBar2.Value = 100;
if (obj.compass_id == 2)
horizontalProgressBar3.Value = 100;
if (obj.autosaved == 1)
{
if (obj.compass_id == 0)
horizontalProgressBar1.Value = 100;
if (obj.compass_id == 1)
horizontalProgressBar2.Value = 100;
if (obj.compass_id == 2)
horizontalProgressBar3.Value = 100;
}
}
catch
{
}

if ((MAVLink.MAG_CAL_STATUS)obj.cal_status != MAVLink.MAG_CAL_STATUS.MAG_CAL_SUCCESS)
var calStatus = (MAVLink.MAG_CAL_STATUS)obj.cal_status;
// Assumption: autosaved==1 is only ever set by firmware on SUCCESS.
// The calStatus>SUCCESS branch below always runs after the autosaved
// block, so if that assumption ever breaks the bar would be reset to
// 0/red while completecount still increments — guard here if needed.
if (calStatus > MAVLink.MAG_CAL_STATUS.MAG_CAL_SUCCESS)
{
//CustomMessageBox.Show(Strings.CommandFailed);
lastFailureStatus[obj.compass_id] = calStatus;
failedCompassIds.Add(obj.compass_id);
// purge stale progress so the old 99% can't overwrite the reset
lock (mprog)
{
mprog.RemoveAll(m => ((MAVLink.mavlink_mag_cal_progress_t)m.data).compass_id == obj.compass_id);
}
// reset bar so the user sees the retry starting from 0
try
{
if (obj.compass_id == 0) horizontalProgressBar1.Value = 0;
if (obj.compass_id == 1) horizontalProgressBar2.Value = 0;
if (obj.compass_id == 2) horizontalProgressBar3.Value = 0;
}
catch { }
}
else if (calStatus == MAVLink.MAG_CAL_STATUS.MAG_CAL_SUCCESS)
lastFailureStatus.Remove(obj.compass_id);
// running/waiting states leave lastFailureStatus unchanged so the
// previous failure reason stays visible while calibration retries

if (obj.autosaved == 1)
{
_autosavedCompasses.Add(obj.compass_id);
completecount++;
timer1.Interval = 1000;
}
}

// consume failure reports so they don't re-fire next tick and kill retry progress
// (lastFailureStatus preserves the message for display)
if (failedCompassIds.Count > 0)
mrep.RemoveAll(m => failedCompassIds.Contains(((MAVLink.mavlink_mag_cal_report_t)m.data).compass_id));
}

// show last known failure reason per compass (persists across firmware auto-restarts)
if (lastFailureStatus.Count > 0)
{
string failures = "";
foreach (var kv in lastFailureStatus)
failures += "Mag " + kv.Key + ": " + kv.Value.ToString() + Environment.NewLine;
lbl_obmagresult.AppendText(failures);
}

if (compasscount == completecount && compasscount != 0)
if (_startedCompasses.Count > 0 && completecount == _startedCompasses.Count)
{
BUT_OBmagcalcancel.Enabled = false;
BUT_OBmagcalaccept.Enabled = false;
Expand Down
107 changes: 80 additions & 27 deletions GCSViews/ConfigurationView/ConfigHWCompass2.cs
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,9 @@ public partial class ConfigHWCompass2 : MyUserControl, IActivate, IDeactivate

private List<MAVLink.MAVLinkMessage> mprog = new List<MAVLink.MAVLinkMessage>();
private List<MAVLink.MAVLinkMessage> mrep = new List<MAVLink.MAVLinkMessage>();
private Dictionary<byte, MAVLink.MAG_CAL_STATUS> lastFailureStatus = new Dictionary<byte, MAVLink.MAG_CAL_STATUS>();
private HashSet<byte> _startedCompasses = new HashSet<byte>();
private HashSet<byte> _autosavedCompasses = new HashSet<byte>();

private int packetsub1;
private int packetsub2;
Expand Down Expand Up @@ -281,6 +284,9 @@ private void BUT_OBmagcalstart_Click(object sender, EventArgs e)

mprog.Clear();
mrep.Clear();
lastFailureStatus.Clear();
_startedCompasses.Clear();
_autosavedCompasses.Clear();
horizontalProgressBar1.Value = 0;
horizontalProgressBar2.Value = 0;
horizontalProgressBar3.Value = 0;
Expand Down Expand Up @@ -378,19 +384,23 @@ private void timer1_Tick(object sender, EventArgs e)

try
{
if (item.Key == 0)
horizontalProgressBar1.Value = obj.completion_pct;
if (item.Key == 1)
horizontalProgressBar2.Value = obj.completion_pct;
if (item.Key == 2)
horizontalProgressBar3.Value = obj.completion_pct;
if (!_autosavedCompasses.Contains(item.Key))
{
if (item.Key == 0)
horizontalProgressBar1.Value = obj.completion_pct;
if (item.Key == 1)
horizontalProgressBar2.Value = obj.completion_pct;
if (item.Key == 2)
horizontalProgressBar3.Value = obj.completion_pct;
}
}
catch { }

message += "id:" + item.Key + " " + obj.completion_pct.ToString() + "% ";
_startedCompasses.Add(item.Key);
compasscount++;
}
lbl_obmagresult.AppendText(message + "\r\n");
lbl_obmagresult.AppendText(message + Environment.NewLine);
}

lock (mrep)
Expand All @@ -401,60 +411,103 @@ private void timer1_Tick(object sender, EventArgs e)
{
var obj = (MAVLink.mavlink_mag_cal_report_t)item.data;

if (obj.compass_id == 0 && obj.ofs_x == 0)
if (obj.compass_id == 0 && obj.ofs_x == 0 && obj.ofs_y == 0 && obj.ofs_z == 0
&& obj.cal_status == (byte)MAVLink.MAG_CAL_STATUS.MAG_CAL_NOT_STARTED)
continue;

status[obj.compass_id] = item;
}

// message for user
var failedCompassIds = new List<byte>();
foreach (var item in status.Values)
{
var obj = (MAVLink.mavlink_mag_cal_report_t)item.data;

lbl_obmagresult.AppendText("id:" + obj.compass_id + " x:" + obj.ofs_x.ToString("0.0") + " y:" +
obj.ofs_y.ToString("0.0") + " z:" +
obj.ofs_z.ToString("0.0") + " fit:" + obj.fitness.ToString("0.0") + " " +
(MAVLink.MAG_CAL_STATUS)obj.cal_status + "\n");
(MAVLink.MAG_CAL_STATUS)obj.cal_status + Environment.NewLine);

try
{
if (obj.compass_id == 0)
{
horizontalProgressBar1.Value = 100;
pictureBox1.BackColor = Color.Green;
}

if (obj.compass_id == 1)
{
horizontalProgressBar2.Value = 100;
pictureBox2.BackColor = Color.Green;
}

if (obj.compass_id == 2)
if (obj.autosaved == 1)
{
horizontalProgressBar3.Value = 100;
pictureBox3.BackColor = Color.Green;
if (obj.compass_id == 0)
{
horizontalProgressBar1.Value = 100;
pictureBox1.BackColor = Color.Green;
}

if (obj.compass_id == 1)
{
horizontalProgressBar2.Value = 100;
pictureBox2.BackColor = Color.Green;
}

if (obj.compass_id == 2)
{
horizontalProgressBar3.Value = 100;
pictureBox3.BackColor = Color.Green;
}
}
}
catch
{
}

if ((MAVLink.MAG_CAL_STATUS)obj.cal_status != MAVLink.MAG_CAL_STATUS.MAG_CAL_SUCCESS)
var calStatus = (MAVLink.MAG_CAL_STATUS)obj.cal_status;
// Assumption: autosaved==1 is only ever set by firmware on SUCCESS.
// The calStatus>SUCCESS branch below always runs after the autosaved
// block, so if that assumption ever breaks the bar would be reset to
// 0/red while completecount still increments — guard here if needed.
if (calStatus > MAVLink.MAG_CAL_STATUS.MAG_CAL_SUCCESS)
{
//CustomMessageBox.Show(Strings.CommandFailed);
lastFailureStatus[obj.compass_id] = calStatus;
failedCompassIds.Add(obj.compass_id);
// purge stale progress so the old 99% can't overwrite the reset
lock (mprog)
{
mprog.RemoveAll(m => ((MAVLink.mavlink_mag_cal_progress_t)m.data).compass_id == obj.compass_id);
}
// reset bar so the user sees the retry starting from 0
try
{
if (obj.compass_id == 0) { horizontalProgressBar1.Value = 0; pictureBox1.BackColor = Color.Red; }
if (obj.compass_id == 1) { horizontalProgressBar2.Value = 0; pictureBox2.BackColor = Color.Red; }
if (obj.compass_id == 2) { horizontalProgressBar3.Value = 0; pictureBox3.BackColor = Color.Red; }
}
catch { }
}
else if (calStatus == MAVLink.MAG_CAL_STATUS.MAG_CAL_SUCCESS)
lastFailureStatus.Remove(obj.compass_id);
// running/waiting states leave lastFailureStatus unchanged so the
// previous failure reason stays visible while calibration retries

if (obj.autosaved == 1)
{
_autosavedCompasses.Add(obj.compass_id);
completecount++;
timer1.Interval = 1000;
}
}

// consume failure reports so they don't re-fire next tick and kill retry progress
// (lastFailureStatus preserves the message for display)
if (failedCompassIds.Count > 0)
mrep.RemoveAll(m => failedCompassIds.Contains(((MAVLink.mavlink_mag_cal_report_t)m.data).compass_id));
}

// show last known failure reason per compass (persists across firmware auto-restarts)
if (lastFailureStatus.Count > 0)
{
string failures = "";
foreach (var kv in lastFailureStatus)
failures += "Mag " + kv.Key + ": " + kv.Value.ToString() + Environment.NewLine;
lbl_obmagresult.AppendText(failures);
}

if (compasscount == completecount && compasscount != 0)
if (_startedCompasses.Count > 0 && completecount == _startedCompasses.Count)
{
BUT_OBmagcalcancel.Enabled = false;
BUT_OBmagcalaccept.Enabled = false;
Expand Down
Loading