autotest: augment tests for running the prearm checks

This commit is contained in:
Peter Barker 2023-10-31 13:44:21 +11:00 committed by Andrew Tridgell
parent e162e74c0c
commit 6439528d6a
2 changed files with 11 additions and 13 deletions

View File

@ -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()

View File

@ -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