autotest: switch QuadPlane mission to full OBC2016 mission in Dalby

This commit is contained in:
Andrew Tridgell 2016-01-09 16:50:17 +11:00
parent eec1b95f69
commit 62b6057249
2 changed files with 36 additions and 23 deletions

View File

@ -1,18 +1,20 @@
QGC WPL 110
0 1 0 16 0.000000 0.000000 0.000000 0.000000 -27.275917 151.288956 343.380005 1
1 0 3 22 10.000000 0.000000 0.000000 0.000000 -27.272867 151.290298 20.000000 1
2 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.272703 151.298172 100.000000 1
3 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.277561 151.337250 100.000000 1
4 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.281748 151.335953 100.000000 1
5 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.275724 151.289932 100.000000 1
6 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.297457 151.285629 100.000000 1
7 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.308109 151.354279 100.000000 1
8 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.332256 151.376282 100.000000 1
9 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.308224 151.354538 100.000000 1
10 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.297340 151.285370 100.000000 1
11 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.275724 151.289932 100.000000 1
12 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.281631 151.335953 100.000000 1
13 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.277679 151.337128 100.000000 1
14 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.272585 151.298294 100.000000 1
15 1 3 16 0.000000 0.000000 0.000000 0.000000 -27.271421 151.290482 30.000000 1
16 0 3 21 0.000000 0.000000 0.000000 0.000000 -27.274094 151.290100 0.000000 1
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -27.274094 151.290100 343.100006 1
1 0 3 84 0.000000 0.000000 0.000000 0.000000 -27.272867 151.290298 10.000000 1
2 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.272703 151.298172 100.000000 1
3 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.277561 151.337250 100.000000 1
4 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.281748 151.335953 100.000000 1
5 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.275724 151.289932 100.000000 1
6 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.297457 151.285629 100.000000 1
7 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.308109 151.354279 100.000000 1
8 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.331802 151.375610 40.529999 1
9 0 10 85 0.000000 0.000000 0.000000 0.000000 -27.332270 151.375854 0.000000 1
10 0 10 84 0.000000 0.000000 0.000000 0.000000 -27.332270 151.375854 40.000000 1
11 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.308224 151.354538 100.000000 1
12 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.297340 151.285370 100.000000 1
13 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.275724 151.289932 100.000000 1
14 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.281631 151.335953 100.000000 1
15 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.277679 151.337128 100.000000 1
16 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.272585 151.298294 100.000000 1
17 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.271421 151.290482 30.000000 1
18 0 10 85 0.000000 0.000000 0.000000 0.000000 -27.274094 151.290100 0.000000 1

View File

@ -9,22 +9,31 @@ import random
testdir=os.path.dirname(os.path.realpath(__file__))
#HOME_LOCATION='-27.274439,151.290064,343,8.7'
HOME_LOCATION='-35.362938,149.165085,585,354'
HOME_LOCATION='-27.274439,151.290064,343,8.7'
MISSION='ArduPlane-Missions/Dalby-OBC2016.txt'
FENCE='ArduPlane-Missions/Dalby-OBC2016-fence.txt'
WIND="0,180,0.2" # speed,direction,variance
homeloc = None
def fly_mission(mavproxy, mav, filename, height_accuracy=-1):
def fly_mission(mavproxy, mav, filename, fence, height_accuracy=-1):
'''fly a mission from a file'''
print("Flying mission %s" % filename)
mavproxy.send('wp load %s\n' % filename)
mavproxy.expect('Flight plan received')
mavproxy.send('fence load %s\n' % fence)
mavproxy.send('wp list\n')
mavproxy.expect('Requesting [0-9]+ waypoints')
mavproxy.send('mode AUTO\n')
wait_mode(mav, 'AUTO')
if not wait_waypoint(mav, 1, 12, max_dist=60):
if not wait_waypoint(mav, 1, 9, max_dist=60):
return False
mavproxy.expect('DISARMED')
# wait for blood sample here
mavproxy.send('wp set 10\n')
mavproxy.send('arm throttle\n')
mavproxy.expect('ARMED')
if not wait_waypoint(mav, 10, 18, max_dist=60):
return False
mavproxy.expect('DISARMED')
print("Mission OK")
@ -45,7 +54,7 @@ def fly_QuadPlane(viewerip=None, map=False):
if map:
options += ' --map'
sil = util.start_SIL('ArduPlane', model='quadplane', wipe=True, home=HOME_LOCATION, speedup=10,
sil = util.start_SIL('ArduPlane', model='quadplane', wipe=True, home=HOME_LOCATION, speedup=20,
defaults_file=os.path.join(testdir, 'quadplane.parm'))
mavproxy = util.start_MAVProxy_SIL('QuadPlane', options=options)
mavproxy.expect('Telemetry log: (\S+)')
@ -98,7 +107,9 @@ def fly_QuadPlane(viewerip=None, map=False):
mavproxy.send('arm throttle\n')
mavproxy.expect('ARMED')
if not fly_mission(mavproxy, mav, os.path.join(testdir, "ArduPlane-Missions/CMAC-VTOL-ccw.txt")):
if not fly_mission(mavproxy, mav,
os.path.join(testdir, "ArduPlane-Missions/Dalby-OBC2016.txt"),
os.path.join(testdir, "ArduPlane-Missions/Dalby-OBC2016-fence.txt")):
print("Failed mission")
failed = True
if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/QuadPlane-log.bin")):