autotest: adjust Plane EKF check for new configured-backend check

This commit is contained in:
Peter Barker 2022-07-28 11:06:40 +10:00 committed by Peter Barker
parent e89f4ea599
commit 82bc2a7d85
2 changed files with 22 additions and 6 deletions

View File

@ -160,12 +160,11 @@ class AutoTestPlane(AutoTest):
timeout=180)
self.progress("RTL Complete")
def test_need_ekf_to_arm(self):
"""Loiter where we are."""
def NeedEKFToArm(self):
"""Ensure the EKF must be healthy for the vehicle to arm."""
self.progress("Ensuring we need EKF to be healthy to arm")
self.wait_ready_to_arm()
self.set_parameter("SIM_GPS_DISABLE", 1)
self.context_collect("STATUSTEXT")
self.reboot_sitl()
tstart = self.get_sim_time()
success = False
while not success:
@ -173,7 +172,7 @@ class AutoTestPlane(AutoTest):
raise NotAchievedException("Did not get correct failure reason")
self.send_mavlink_arm_command()
try:
self.wait_statustext(".*(AHRS not healthy|AHRS: Not healthy).*", timeout=1, check_context=True, regex=True)
self.wait_statustext(".*AHRS: not using configured AHRS type.*", timeout=1, check_context=True, regex=True)
success = True
continue
except AutoTestTimeoutException:
@ -181,6 +180,9 @@ class AutoTestPlane(AutoTest):
if self.armed():
raise NotAchievedException("Armed unexpectedly")
self.set_parameter("SIM_GPS_DISABLE", 0)
self.wait_ready_to_arm()
def fly_LOITER(self, num_circles=4):
"""Loiter where we are."""
self.progress("Testing LOITER for %u turns" % num_circles)
@ -3807,7 +3809,7 @@ function'''
("NeedEKFToArm",
"Ensure we need EKF to be healthy to arm",
self.test_need_ekf_to_arm),
self.NeedEKFToArm),
("ThrottleFailsafeFence",
"Fly fence survives throttle failsafe",

View File

@ -1836,6 +1836,17 @@ class AutoTest(ABC):
0,
0)
def run_cmd_run_prearms(self):
self.run_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS,
0,
0,
0,
0,
0,
0,
0,
0)
def run_cmd_enable_high_latency(self, new_state):
p1 = 0
if new_state:
@ -6591,6 +6602,9 @@ class AutoTest(ABC):
if self.sensor_has_state(sensor, present=present, enabled=enabled, healthy=healthy, verbose=verbose):
break
def wait_not_ready_to_arm(self):
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, True, True, False)
def wait_prearm_sys_status_healthy(self, timeout=60):
self.do_timesync_roundtrip()
tstart = self.get_sim_time()