mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
autotest: tweak wait-for-gps-health
show how long we had to wait, ensure we don't work with stale data
This commit is contained in:
parent
0918ddc05a
commit
219a13e45f
@ -7201,7 +7201,7 @@ class AutoTest(ABC):
|
||||
|
||||
def wait_gps_sys_status_not_present_or_enabled_and_healthy(self, timeout=30):
|
||||
self.progress("Waiting for GPS health")
|
||||
tstart = self.get_sim_time_cached()
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
now = self.get_sim_time_cached()
|
||||
if now - tstart > timeout:
|
||||
@ -7221,7 +7221,8 @@ class AutoTest(ABC):
|
||||
if (not (m.onboard_control_sensors_health & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):
|
||||
self.progress("GPS not healthy")
|
||||
continue
|
||||
self.progress("GPS healthy")
|
||||
self.progress("GPS healthy after %f/%f seconds" %
|
||||
((now - tstart), timeout))
|
||||
return
|
||||
|
||||
def assert_sensor_state(self, sensor, present=True, enabled=True, healthy=True, verbose=False):
|
||||
|
Loading…
Reference in New Issue
Block a user