autotest: tweak the rover mission a bit

This commit is contained in:
Andrew Tridgell 2012-11-29 20:53:10 +11:00
parent cc52b39c06
commit 099a2abaed
2 changed files with 5 additions and 4 deletions

View File

@ -12,3 +12,4 @@ FLTMODE3 11
FLTMODE4 10
FLTMODE5 2
FLTMODE6 0
RLL2SRV_P 0.6

View File

@ -30,6 +30,7 @@ def drive_left_circuit(mavproxy, mav):
print("Starting leg %u" % i)
if not wait_distance(mav, 50, accuracy=7):
return False
mavproxy.send('rc 3 1500\n')
print("Circuit complete")
return True
@ -39,7 +40,6 @@ def drive_RTL(mavproxy, mav):
mavproxy.send('switch 3\n')
if not wait_location(mav, homeloc, accuracy=22, timeout=90):
return False
mavproxy.expect('Reached home')
print("RTL Complete")
return True
@ -145,12 +145,12 @@ def drive_APMrover2(viewerip=None):
if not drive_left_circuit(mavproxy, mav):
print("Failed left circuit")
failed = True
if not drive_RTL(mavproxy, mav):
print("Failed RTL")
failed = True
if not drive_mission(mavproxy, mav, os.path.join(testdir, "rover1.txt")):
print("Failed mission")
failed = True
if not drive_RTL(mavproxy, mav):
print("Failed RTL")
failed = True
except pexpect.TIMEOUT, e:
print("Failed with timeout")
failed = True