mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: print mag cal progress messages when testing mag cal
This commit is contained in:
parent
79098d1d10
commit
05be2ac8c9
@ -7534,6 +7534,7 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
else:
|
else:
|
||||||
continue
|
continue
|
||||||
if m is not None:
|
if m is not None:
|
||||||
|
self.progress("Mag CAL progress: %s" % str(m))
|
||||||
cid = m.compass_id
|
cid = m.compass_id
|
||||||
new_pct = int(m.completion_pct)
|
new_pct = int(m.completion_pct)
|
||||||
if new_pct != reached_pct[cid]:
|
if new_pct != reached_pct[cid]:
|
||||||
@ -7599,6 +7600,7 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
self.progress("All Mag report failure")
|
self.progress("All Mag report failure")
|
||||||
break
|
break
|
||||||
if m is not None and m.get_type() == "MAG_CAL_PROGRESS":
|
if m is not None and m.get_type() == "MAG_CAL_PROGRESS":
|
||||||
|
self.progress("Mag CAL progress: %s" % str(m))
|
||||||
cid = m.compass_id
|
cid = m.compass_id
|
||||||
new_pct = int(m.completion_pct)
|
new_pct = int(m.completion_pct)
|
||||||
if new_pct != reached_pct[cid]:
|
if new_pct != reached_pct[cid]:
|
||||||
|
Loading…
Reference in New Issue
Block a user