autotest: loosen time constraint on mavlink messages in magcal

Saw an error where we didn't get one of these in 5 seconds.

That sounds like too much.  But we'll loosen the constrain anyway
This commit is contained in:
Peter Barker 2021-02-09 14:33:55 +11:00 committed by Peter Barker
parent bd8384b322
commit 4324d66c13
1 changed files with 1 additions and 1 deletions

View File

@ -5930,7 +5930,7 @@ Also, ignores heartbeats not from our target system'''
while True:
if self.get_sim_time_cached() - tstart > timeout:
raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")
m = self.mav.recv_match(type=["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], blocking=True, timeout=5)
m = self.mav.recv_match(type=["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], blocking=True, timeout=10)
if m.get_type() == "MAG_CAL_REPORT":
if report_get[m.compass_id] == 0:
self.progress("Report: %s" % str(m))