Skip to content

Commit 2c3641d

Browse files
committed
ConfigHWCompass: change result display
1 parent d92fe3c commit 2c3641d

File tree

2 files changed

+41
-11
lines changed

2 files changed

+41
-11
lines changed

GCSViews/ConfigurationView/ConfigHWCompass.cs

Lines changed: 40 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -391,6 +391,9 @@ private void BUT_OBmagcalstart_Click(object sender, EventArgs e)
391391
{
392392
MainV2.comPort.doCommand(MAVLink.MAV_CMD.DO_START_MAG_CAL, 0, 0, 1, 0, 0, 0, 0);
393393

394+
mprog.Clear();
395+
mrep.Clear();
396+
394397
packetsub1 = MainV2.comPort.SubscribeToPacketType(MAVLink.MAVLINK_MSG_ID.MAG_CAL_PROGRESS, ReceviedPacket);
395398
packetsub2 = MainV2.comPort.SubscribeToPacketType(MAVLink.MAVLINK_MSG_ID.MAG_CAL_REPORT, ReceviedPacket);
396399

@@ -421,32 +424,59 @@ private void BUT_OBmagcalcancel_Click(object sender, EventArgs e)
421424

422425
private void timer1_Tick(object sender, EventArgs e)
423426
{
427+
lbl_obmagresult.Clear();
428+
int compasscount = 0;
429+
int completecount = 0;
424430
lock (mprog)
425431
{
432+
// somewhere to save our %
433+
Dictionary<byte,byte> status = new Dictionary<byte, byte>();
426434
foreach (var item in mprog)
427435
{
428-
lbl_obmagresult.AppendText("id:" + item.compass_id + " " + item.completion_pct.ToString() + "% " +
429-
"\n");
430-
}
436+
status[item.compass_id] = item.completion_pct;
437+
}
431438

432-
mprog.Clear();
439+
// message for user
440+
string message = "";
441+
foreach (var item in status)
442+
{
443+
message += "id:" + item.Key + " " + item.Value.ToString() + "% ";
444+
compasscount++;
445+
}
446+
lbl_obmagresult.AppendText(message + "\n");
433447
}
434448

435449
lock (mrep)
436-
{
450+
{
451+
// somewhere to save our answer
452+
Dictionary<byte, MAVLink.mavlink_mag_cal_report_t> status = new Dictionary<byte, MAVLink.mavlink_mag_cal_report_t>();
437453
foreach (var item in mrep)
438454
{
439455
if (item.compass_id == 0 && item.ofs_x == 0)
440456
continue;
441457

442-
lbl_obmagresult.AppendText("id:" + item.compass_id + " x:" + item.ofs_x + " y:" + item.ofs_y + " z:" +
443-
item.ofs_z + " fit:" + item.fitness + "\n");
458+
status[item.compass_id] = item;
459+
}
460+
461+
// message for user
462+
string message = "";
463+
foreach (var item in status.Values)
464+
{
465+
lbl_obmagresult.AppendText("id:" + item.compass_id + " x:" + item.ofs_x.ToString("0.0") + " y:" + item.ofs_y.ToString("0.0") + " z:" +
466+
item.ofs_z.ToString("0.0") + " fit:" + item.fitness.ToString("0.0") + " " + (MAVLink.MAG_CAL_STATUS)item.cal_status + "\n");
467+
468+
if (item.autosaved == 1)
469+
{
470+
completecount++;
471+
BUT_OBmagcalcancel.Enabled = false;
472+
BUT_OBmagcalaccept.Enabled = false;
473+
timer1.Interval = 1000;
474+
}
444475
}
445476

446-
mrep.Clear();
477+
if (compasscount == completecount && compasscount != 0)
478+
timer1.Stop();
447479
}
448-
449-
lbl_obmagresult.SelectionStart = lbl_obmagresult.Text.Length - 1;
450480
}
451481

452482
private void buttonQuickPixhawk_Click(object sender, EventArgs e)

MagCalib.cs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -661,7 +661,7 @@ static void prd_DoWork(object sender, ProgressWorkerEventArgs e, object passdata
661661

662662
bool ellipsoid = false;
663663

664-
if (MainV2.comPort.MAV.param.ContainsKey("MAG_DIA"))
664+
if (MainV2.comPort.MAV.param.ContainsKey("COMPASS_DIA_X"))
665665
{
666666
ellipsoid = true;
667667
}

0 commit comments

Comments
 (0)