diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index fb2fafeb16..4f8cc063e8 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -4983,7 +4983,7 @@ 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] < 99: + if reached_pct[m.compass_id] < 98: raise NotAchievedException("Mag calibration report SUCCESS without 100%% completion") report_get[m.compass_id] = 1 else: