diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 00ab7550de..2fc589e533 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -2717,6 +2717,7 @@ function''' "INS_GYR_CAL": 1, }) self.reboot_sitl() + self.delay_sim_time(5) self.progress("Running accelcal") self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0, 0, 0, 0, 4, 0, 0, diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index c9871d1ce2..45ab7d594e 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -10866,6 +10866,7 @@ switch value''' def ahrstrim(self): self.start_subtest("Attitude Correctness") self.ahrstrim_attitude_correctness() + self.delay_sim_time(5) self.start_subtest("Preflight Calibration") self.ahrstrim_preflight_cal()