Tools: autotest: fix no-gps switch-to-location test

This commit is contained in:
Peter Barker 2019-03-21 11:15:11 +11:00 committed by Peter Barker
parent 1e2cf4bb60
commit 16476332b2
2 changed files with 10 additions and 1 deletions

View File

@ -2753,6 +2753,13 @@ class AutoTestCopter(AutoTest):
self.set_parameter("GPS_TYPE", 0) self.set_parameter("GPS_TYPE", 0)
self.reboot_sitl() self.reboot_sitl()
self.change_mode('STABILIZE') self.change_mode('STABILIZE')
self.wait_ekf_flags((mavutil.mavlink.ESTIMATOR_ATTITUDE |
mavutil.mavlink.ESTIMATOR_VELOCITY_VERT |
mavutil.mavlink.ESTIMATOR_POS_VERT_ABS |
mavutil.mavlink.ESTIMATOR_CONST_POS_MODE |
mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_REL),
0,
timeout=120)
self.arm_vehicle() self.arm_vehicle()
self.mavproxy.send("mode LOITER\n") self.mavproxy.send("mode LOITER\n")
self.mavproxy.expect("requires position") self.mavproxy.expect("requires position")

View File

@ -1664,7 +1664,6 @@ class AutoTest(ABC):
if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10): if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10):
return True return True
tstart = self.get_sim_time()
# all of these must be set for arming to happen: # all of these must be set for arming to happen:
required_value = (mavutil.mavlink.EKF_ATTITUDE | required_value = (mavutil.mavlink.EKF_ATTITUDE |
mavutil.mavlink.ESTIMATOR_VELOCITY_HORIZ | mavutil.mavlink.ESTIMATOR_VELOCITY_HORIZ |
@ -1679,9 +1678,12 @@ class AutoTest(ABC):
mavutil.mavlink.ESTIMATOR_POS_VERT_ABS | mavutil.mavlink.ESTIMATOR_POS_VERT_ABS |
mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_ABS) mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_ABS)
error_bits |= mavutil.mavlink.ESTIMATOR_GPS_GLITCH error_bits |= mavutil.mavlink.ESTIMATOR_GPS_GLITCH
self.wait_ekf_flags(required_value, error_bits, timeout=timeout)
def wait_ekf_flags(self, required_value, error_bits, timeout=30):
self.progress("Waiting for EKF value %u" % required_value) self.progress("Waiting for EKF value %u" % required_value)
last_print_time = 0 last_print_time = 0
tstart = self.get_sim_time()
while timeout is None or self.get_sim_time_cached() < tstart + timeout: while timeout is None or self.get_sim_time_cached() < tstart + timeout:
m = self.mav.recv_match(type='EKF_STATUS_REPORT', blocking=True) m = self.mav.recv_match(type='EKF_STATUS_REPORT', blocking=True)
current = m.flags current = m.flags