From 3e882fcad8d7b5e2fd681832769fb115bec2d534 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 11 Sep 2020 10:01:30 +1000 Subject: [PATCH] autotest: loosen mag-percent-complete threshold to 95% So 98% wasn't loose enough... --- Tools/autotest/common.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 813b60da76..15ecfade4c 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -4989,8 +4989,9 @@ Also, ignores heartbeats not from our target system''' for param_name in param_names: self.progress("%s=%f" % (param_name, self.get_parameter(param_name))) if m.cal_status == mavutil.mavlink.MAG_CAL_SUCCESS: - if reached_pct[m.compass_id] < 98: - raise NotAchievedException("Mag calibration report SUCCESS without 100%% completion") + threshold = 95 + if reached_pct[m.compass_id] < threshold: + raise NotAchievedException("Mag calibration report SUCCESS without >=%f%% completion (got %f%%)" % (threshold, reached_pct[m.compass_id])) report_get[m.compass_id] = 1 else: raise NotAchievedException(