mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
autotest: improve compass test diagnostics
This commit is contained in:
parent
b69130d352
commit
f1fc61cb41
@ -4693,6 +4693,7 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
self.start_subtest("Try magcal and wait success")
|
self.start_subtest("Try magcal and wait success")
|
||||||
self.progress("Compass mask is %s" % "{0:b}".format(target_mask))
|
self.progress("Compass mask is %s" % "{0:b}".format(target_mask))
|
||||||
reset_pos_and_start_magcal(target_mask)
|
reset_pos_and_start_magcal(target_mask)
|
||||||
|
progress_count = [0] * compass_tnumber
|
||||||
reached_pct = [0] * compass_tnumber
|
reached_pct = [0] * compass_tnumber
|
||||||
report_get = [0] * compass_tnumber
|
report_get = [0] * compass_tnumber
|
||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
@ -4708,16 +4709,19 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
raise NotAchievedException("Mag calibration report SUCCESS without 100%% completion")
|
raise NotAchievedException("Mag calibration report SUCCESS without 100%% completion")
|
||||||
report_get[m.compass_id] = 1
|
report_get[m.compass_id] = 1
|
||||||
else:
|
else:
|
||||||
raise NotAchievedException("Mag calibration didn't SUCCESS")
|
raise NotAchievedException(
|
||||||
|
"Mag calibration didn't SUCCEED (cal_status=%u) (progress_count=%s)" %
|
||||||
|
(m.cal_status, progress_count[m.compass_id],))
|
||||||
if all(ele >= 1 for ele in report_get):
|
if all(ele >= 1 for ele in report_get):
|
||||||
self.progress("All Mag report SUCCESS")
|
self.progress("All Mag report SUCCESS")
|
||||||
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":
|
||||||
cid = m.compass_id
|
cid = m.compass_id
|
||||||
new_pct = int(m.completion_pct)
|
new_pct = int(m.completion_pct)
|
||||||
|
progress_count[cid] += 1
|
||||||
if new_pct != reached_pct[cid]:
|
if new_pct != reached_pct[cid]:
|
||||||
reached_pct[cid] = new_pct
|
reached_pct[cid] = new_pct
|
||||||
self.progress("Calibration progress compass ID %d: %s" % (cid, str(reached_pct[cid])))
|
self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))
|
||||||
self.mavproxy.send("sitl_stop\n")
|
self.mavproxy.send("sitl_stop\n")
|
||||||
self.mavproxy.send("sitl_attitude 0 0 0\n")
|
self.mavproxy.send("sitl_attitude 0 0 0\n")
|
||||||
self.progress("Checking that value aren't changed without acceptation")
|
self.progress("Checking that value aren't changed without acceptation")
|
||||||
|
@ -300,6 +300,8 @@ class MagcalController(CalController):
|
|||||||
if m.get_type() == 'MAG_CAL_REPORT':
|
if m.get_type() == 'MAG_CAL_REPORT':
|
||||||
# NOTE: This may be not the ideal way to handle it
|
# NOTE: This may be not the ideal way to handle it
|
||||||
if m.compass_id in self.last_progress:
|
if m.compass_id in self.last_progress:
|
||||||
|
# this is set to None so we can ensure we don't get
|
||||||
|
# progress reports for completed compasses.
|
||||||
self.last_progress[m.compass_id] = None
|
self.last_progress[m.compass_id] = None
|
||||||
if len(self.last_progress.values()) and all(progress == None for progress in self.last_progress.values()):
|
if len(self.last_progress.values()) and all(progress == None for progress in self.last_progress.values()):
|
||||||
self.stop()
|
self.stop()
|
||||||
@ -320,6 +322,8 @@ class MagcalController(CalController):
|
|||||||
return
|
return
|
||||||
|
|
||||||
last = self.last_progress[m.compass_id]
|
last = self.last_progress[m.compass_id]
|
||||||
|
if last is None:
|
||||||
|
raise Exception("Received progress message for completed compass")
|
||||||
|
|
||||||
dt = t - self.rotation_start_time
|
dt = t - self.rotation_start_time
|
||||||
if dt > self.max_full_turns * self.full_turn_time:
|
if dt > self.max_full_turns * self.full_turn_time:
|
||||||
@ -334,7 +338,7 @@ class MagcalController(CalController):
|
|||||||
m.stuck = False
|
m.stuck = False
|
||||||
|
|
||||||
for p in self.last_progress.values():
|
for p in self.last_progress.values():
|
||||||
if not p.stuck:
|
if p is not None and not p.stuck:
|
||||||
break
|
break
|
||||||
else:
|
else:
|
||||||
self.next_rotation()
|
self.next_rotation()
|
||||||
|
Loading…
Reference in New Issue
Block a user