mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
autotest: added a timeout check
There was 1 while loop in the arducopter.py autotest that didn't have a timeout check and of course we tripped over it.
This commit is contained in:
parent
461eff25d5
commit
fd0a442c92
@ -617,6 +617,10 @@ def fly_gps_glitch_auto_test(mavproxy, mav, timeout=30, max_distance=100):
|
|||||||
pos = mav.location()
|
pos = mav.location()
|
||||||
dist_to_home = get_distance(HOME, pos)
|
dist_to_home = get_distance(HOME, pos)
|
||||||
while dist_to_home > 5:
|
while dist_to_home > 5:
|
||||||
|
if get_sim_time(mav) > (tstart + timeout):
|
||||||
|
print("GPS Glitch testing failed - exceeded timeout %u seconds" % timeout)
|
||||||
|
ret = False
|
||||||
|
break
|
||||||
m = mav.recv_match(type='VFR_HUD', blocking=True)
|
m = mav.recv_match(type='VFR_HUD', blocking=True)
|
||||||
pos = mav.location()
|
pos = mav.location()
|
||||||
dist_to_home = get_distance(HOME, pos)
|
dist_to_home = get_distance(HOME, pos)
|
||||||
|
Loading…
Reference in New Issue
Block a user