Autotest: correct mavproxy unloaded map error

This commit is contained in:
Pierre Kancir 2016-08-01 14:23:53 +02:00 committed by Lucas De Marchi
parent bd8526fd68
commit 07eb170b39
2 changed files with 24 additions and 15 deletions

View File

@ -462,14 +462,16 @@ def show_gps_and_sim_positions(mavproxy, on_off):
mavproxy.send('map set showsimpos 0\n')
# fly_gps_glitch_loiter_test - fly south east in loiter and test reaction to gps glitch
def fly_gps_glitch_loiter_test(mavproxy, mav, timeout=30, max_distance=20):
def fly_gps_glitch_loiter_test(mavproxy, mav, use_map=False, timeout=30, max_distance=20):
'''hold loiter position'''
mavproxy.send('switch 5\n') # loiter mode
wait_mode(mav, 'LOITER')
# turn on simulator display of gps and actual position
if (use_map):
show_gps_and_sim_positions(mavproxy, True)
# set-up gps glitch array
glitch_lat = [0.0002996,0.0006958,0.0009431,0.0009991,0.0009444,0.0007716,0.0006221]
glitch_lon = [0.0000717,0.0000912,0.0002761,0.0002626,0.0002807,0.0002049,0.0001304]
@ -482,6 +484,7 @@ def fly_gps_glitch_loiter_test(mavproxy, mav, timeout=30, max_distance=20):
print("turn south east")
mavproxy.send('rc 4 1580\n')
if not wait_heading(mav, 150):
if (use_map):
show_gps_and_sim_positions(mavproxy, False)
return False
mavproxy.send('rc 4 1500\n')
@ -489,12 +492,14 @@ def fly_gps_glitch_loiter_test(mavproxy, mav, timeout=30, max_distance=20):
# fly forward (south east) at least 60m
mavproxy.send('rc 2 1100\n')
if not wait_distance(mav, 60):
if (use_map):
show_gps_and_sim_positions(mavproxy, False)
return False
mavproxy.send('rc 2 1500\n')
# wait for copter to slow down
if not wait_groundspeed(mav, 0, 1):
if (use_map):
show_gps_and_sim_positions(mavproxy, False)
return False
@ -543,6 +548,7 @@ def fly_gps_glitch_loiter_test(mavproxy, mav, timeout=30, max_distance=20):
glitch_current = -1
mavproxy.send('param set SIM_GPS_GLITCH_X 0\n')
mavproxy.send('param set SIM_GPS_GLITCH_Y 0\n')
if (use_map):
show_gps_and_sim_positions(mavproxy, False)
if success:
@ -552,7 +558,7 @@ def fly_gps_glitch_loiter_test(mavproxy, mav, timeout=30, max_distance=20):
return success
# fly_gps_glitch_auto_test - fly mission and test reaction to gps glitch
def fly_gps_glitch_auto_test(mavproxy, mav, timeout=120):
def fly_gps_glitch_auto_test(mavproxy, mav, use_map=False, timeout=120):
# set-up gps glitch array
glitch_lat = [0.0002996,0.0006958,0.0009431,0.0009991,0.0009444,0.0007716,0.0006221]
@ -569,6 +575,7 @@ def fly_gps_glitch_auto_test(mavproxy, mav, timeout=120):
return False
# turn on simulator display of gps and actual position
if (use_map):
show_gps_and_sim_positions(mavproxy, True)
# load the waypoint count
@ -584,6 +591,7 @@ def fly_gps_glitch_auto_test(mavproxy, mav, timeout=120):
# wait until 100m from home
if not wait_distance(mav, 100, 5, 60):
if (use_map):
show_gps_and_sim_positions(mavproxy, False)
return False
@ -632,6 +640,7 @@ def fly_gps_glitch_auto_test(mavproxy, mav, timeout=120):
print("Dist from home: %u" % dist_to_home)
# turn off simulator display of gps and actual position
if (use_map):
show_gps_and_sim_positions(mavproxy, False)
print("GPS Glitch test Auto completed: passed=%s" % ret)
@ -914,7 +923,7 @@ def setup_rc(mavproxy):
# zero throttle
mavproxy.send('rc 3 1000\n')
def fly_ArduCopter(binary, viewerip=None, map=False, valgrind=False, gdb=False):
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False):
'''fly ArduCopter in SIL
you can pass viewerip as an IP address to optionally send fg and
@ -942,7 +951,7 @@ def fly_ArduCopter(binary, viewerip=None, map=False, valgrind=False, gdb=False):
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5'
if viewerip:
options += ' --out=%s:14550' % viewerip
if map:
if use_map:
options += ' --map'
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options=options)
mavproxy.expect('Telemetry log: (\S+)')
@ -1096,7 +1105,7 @@ def fly_ArduCopter(binary, viewerip=None, map=False, valgrind=False, gdb=False):
# Fly GPS Glitch Loiter test
print("# GPS Glitch Loiter Test")
if not fly_gps_glitch_loiter_test(mavproxy, mav):
if not fly_gps_glitch_loiter_test(mavproxy, mav, use_map):
failed_test_msg = "fly_gps_glitch_loiter_test failed"
print(failed_test_msg)
failed = True
@ -1110,7 +1119,7 @@ def fly_ArduCopter(binary, viewerip=None, map=False, valgrind=False, gdb=False):
# Fly GPS Glitch test in auto mode
print("# GPS Glitch Auto Test")
if not fly_gps_glitch_auto_test(mavproxy, mav):
if not fly_gps_glitch_auto_test(mavproxy, mav, use_map):
failed_test_msg = "fly_gps_glitch_auto_test failed"
print(failed_test_msg)
failed = True

View File

@ -266,7 +266,7 @@ def run_step(step):
return get_default_params('APMrover2', binary)
if step == 'fly.ArduCopter':
return arducopter.fly_ArduCopter(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)
return arducopter.fly_ArduCopter(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)
if step == 'fly.CopterAVC':
return arducopter.fly_CopterAVC(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)