autotest: wait for VFR_HUD to be non-zero on startup

This commit is contained in:
Andrew Tridgell 2012-06-04 14:55:40 +10:00
parent 0f0cbce22f
commit 70669434a2
1 changed files with 1 additions and 0 deletions

View File

@ -293,6 +293,7 @@ def fly_ArduPlane(viewerip=None):
print("Setting up RC parameters")
setup_rc(mavproxy)
print("Waiting for GPS fix")
mav.recv_match(condition='VFR_HUD.alt>0', blocking=True)
mav.wait_gps_fix()
homeloc = mav.location()
print("Home location: %s" % homeloc)