From 6439528d6aa453e816bc60cf930bf69929924c3d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 13:44:21 +1100 Subject: [PATCH] autotest: augment tests for running the prearm checks --- Tools/autotest/arduplane.py | 21 +++++++++++---------- Tools/autotest/vehicle_test_suite.py | 3 --- 2 files changed, 11 insertions(+), 13 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 50cac72819..a580e70d5e 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -191,16 +191,17 @@ class AutoTestPlane(vehicle_test_suite.TestSuite): self.context_collect("STATUSTEXT") tstart = self.get_sim_time() success = False - while not success: - if self.get_sim_time_cached() - tstart > 60: - raise NotAchievedException("Did not get correct failure reason") - self.run_cmd_run_prearms() - try: - self.wait_statustext(".*AHRS: not using configured AHRS type.*", timeout=1, check_context=True, regex=True) - success = True - continue - except AutoTestTimeoutException: - pass + for run_cmd in self.run_cmd, self.run_cmd_int: + while not success: + if self.get_sim_time_cached() - tstart > 60: + raise NotAchievedException("Did not get correct failure reason") + run_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS) + try: + self.wait_statustext(".*AHRS: not using configured AHRS type.*", timeout=1, check_context=True, regex=True) + success = True + continue + except AutoTestTimeoutException: + pass self.set_parameter("SIM_GPS_DISABLE", 0) self.wait_ready_to_arm() diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 427ebb5bb6..4128980250 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -1898,9 +1898,6 @@ class TestSuite(ABC): p1=1, # reboot autopilot ) - def run_cmd_run_prearms(self): - self.run_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS) - def run_cmd_enable_high_latency(self, new_state, run_cmd=None): if run_cmd is None: run_cmd = self.run_cmd