This commit is contained in:
Jason Short 2012-01-10 23:42:18 -08:00
parent e2830ca147
commit d11eaa9265

View File

@ -168,7 +168,7 @@ def fly_RTL(mavproxy, mav, side=60):
print("# Enter RTL") print("# Enter RTL")
mavproxy.send('switch 3\n') mavproxy.send('switch 3\n')
tstart = time.time() tstart = time.time()
while time.time() < tstart + 120: while time.time() < tstart + 200:
m = mav.recv_match(type='VFR_HUD', blocking=True) m = mav.recv_match(type='VFR_HUD', blocking=True)
pos = current_location(mav) pos = current_location(mav)
#delta = get_distance(start, pos) #delta = get_distance(start, pos)
@ -208,7 +208,7 @@ def fly_simple(mavproxy, mav, side=60, timeout=120):
'''fly Simple, flying N then E''' '''fly Simple, flying N then E'''
mavproxy.send('switch 6\n') mavproxy.send('switch 6\n')
wait_mode(mav, 'STABILIZE') wait_mode(mav, 'STABILIZE')
mavproxy.send('rc 3 1450\n') mavproxy.send('rc 3 1440\n')
tstart = time.time() tstart = time.time()
failed = False failed = False
@ -246,7 +246,7 @@ def land(mavproxy, mav, timeout=60):
mavproxy.send('switch 2\n') mavproxy.send('switch 2\n')
wait_mode(mav, 'LAND') wait_mode(mav, 'LAND')
print("Entered Landing Mode") print("Entered Landing Mode")
ret = wait_altitude(mav, -5, 5) ret = wait_altitude(mav, -5, 1)
print("LANDING: ok= %s" % ret) print("LANDING: ok= %s" % ret)
return ret return ret
@ -437,8 +437,8 @@ def fly_ArduCopter(viewerip=None):
failed = True failed = True
# Loiter for 30 seconds # Loiter for 30 seconds
print("# Loiter for 30 seconds") print("# Loiter for 45 seconds")
if not loiter(mavproxy, mav, 30): if not loiter(mavproxy, mav, 45):
print("loiter failed") print("loiter failed")
failed = True failed = True