Tools: autotest: add and use progress function

Based on work done by khancir
(https://github.com/ArduPilot/ardupilot/pull/6360)

Tools: arduplane.py change print to progress function
Tools: quadplane.py change print to progress function
Tools: ardusub.py change print to progress function
This commit is contained in:
Peter Barker 2017-11-14 15:30:31 +11:00
parent 76bb081d60
commit 2f76f83ab7
6 changed files with 395 additions and 387 deletions

View File

@ -27,7 +27,7 @@ def arm_rover(mavproxy, mav):
mavproxy.send('arm throttle\n')
mavproxy.expect('ARMED')
print("ROVER ARMED")
progress("ROVER ARMED")
return True
@ -35,7 +35,7 @@ def disarm_rover(mavproxy, mav):
mavproxy.send('disarm\n')
mavproxy.expect('DISARMED')
print("ROVER DISARMED")
progress("ROVER DISARMED")
return True
@ -45,30 +45,30 @@ def drive_left_circuit(mavproxy, mav):
wait_mode(mav, 'MANUAL')
mavproxy.send('rc 3 2000\n')
print("Driving left circuit")
progress("Driving left circuit")
# do 4 turns
for i in range(0, 4):
# hard left
print("Starting turn %u" % i)
progress("Starting turn %u" % i)
mavproxy.send('rc 1 1000\n')
if not wait_heading(mav, 270 - (90*i), accuracy=10):
return False
mavproxy.send('rc 1 1500\n')
print("Starting leg %u" % i)
progress("Starting leg %u" % i)
if not wait_distance(mav, 50, accuracy=7):
return False
mavproxy.send('rc 3 1500\n')
print("Circuit complete")
progress("Circuit complete")
return True
def drive_RTL(mavproxy, mav):
"""Drive to home."""
print("Driving home in RTL")
progress("Driving home in RTL")
mavproxy.send('switch 3\n')
if not wait_location(mav, homeloc, accuracy=22, timeout=90):
return False
print("RTL Complete")
progress("RTL Complete")
return True
@ -82,7 +82,7 @@ def setup_rc(mavproxy):
def drive_mission(mavproxy, mav, filename):
"""Drive a mission from a file."""
global homeloc
print("Driving mission %s" % filename)
progress("Driving mission %s" % filename)
mavproxy.send('wp load %s\n' % filename)
mavproxy.expect('Flight plan received')
mavproxy.send('wp list\n')
@ -93,7 +93,7 @@ def drive_mission(mavproxy, mav, filename):
if not wait_waypoint(mav, 1, 4, max_dist=5):
return False
wait_mode(mav, 'HOLD')
print("Mission OK")
progress("Mission OK")
return True
def do_get_banner(mavproxy, mav):
@ -102,12 +102,12 @@ def do_get_banner(mavproxy, mav):
while True:
m = mav.recv_match(type='STATUSTEXT', blocking=True, timeout=1)
if m is not None and "APM:Rover" in m.text:
print("banner received: %s" % (m.text))
progress("banner received: %s" % (m.text))
return True
if time.time() - start > 10:
break
print("banner not received")
progress("banner not received")
return False
@ -115,9 +115,9 @@ def do_get_autopilot_capabilities(mavproxy, mav):
mavproxy.send("long REQUEST_AUTOPILOT_CAPABILITIES 1\n")
m = mav.recv_match(type='AUTOPILOT_VERSION', blocking=True, timeout=10)
if m is None:
print("AUTOPILOT_VERSION not received")
progress("AUTOPILOT_VERSION not received")
return False
print("AUTOPILOT_VERSION received")
progress("AUTOPILOT_VERSION received")
return True;
def do_set_mode_via_command_long(mavproxy, mav):
@ -189,10 +189,10 @@ def drive_brake(mavproxy, mav):
delta = distance_without_brakes - distance_with_brakes
if delta < distance_without_brakes*0.05: # 5% isn't asking for much
print("Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)" % (distance_with_brakes, distance_without_brakes, delta))
progress("Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)" % (distance_with_brakes, distance_without_brakes, delta))
return False
else:
print("Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" % (distance_with_brakes, distance_without_brakes, delta))
progress("Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" % (distance_with_brakes, distance_without_brakes, delta))
return True
@ -219,7 +219,7 @@ def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fa
sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=speedup)
mavproxy = util.start_MAVProxy_SITL('APMrover2', options=options)
print("WAITING FOR PARAMETERS")
progress("WAITING FOR PARAMETERS")
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
@ -241,10 +241,10 @@ def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fa
mavproxy = util.start_MAVProxy_SITL('APMrover2', options=options)
mavproxy.expect('Telemetry log: (\S+)')
logfile = mavproxy.match.group(1)
print("LOGFILE %s" % logfile)
progress("LOGFILE %s" % logfile)
buildlog = util.reltopdir("../buildlogs/APMrover2-test.tlog")
print("buildlog=%s" % buildlog)
progress("buildlog=%s" % buildlog)
if os.path.exists(buildlog):
os.unlink(buildlog)
try:
@ -259,13 +259,13 @@ def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fa
expect_list_clear()
expect_list_extend([sitl, mavproxy])
print("Started simulator")
progress("Started simulator")
# get a mavlink connection going
try:
mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True)
except Exception as msg:
print("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
progress("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
raise
mav.message_hooks.append(message_hook)
mav.idle_hooks.append(idle_hook)
@ -273,54 +273,54 @@ def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fa
failed = False
e = 'None'
try:
print("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION)
progress("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION)
mav.wait_heartbeat()
print("Setting up RC parameters")
progress("Setting up RC parameters")
setup_rc(mavproxy)
print("Waiting for GPS fix")
progress("Waiting for GPS fix")
mav.wait_gps_fix()
homeloc = mav.location()
print("Home location: %s" % homeloc)
progress("Home location: %s" % homeloc)
if not arm_rover(mavproxy, mav):
print("Failed to ARM")
progress("Failed to ARM")
failed = True
if not drive_mission(mavproxy, mav, os.path.join(testdir, "rover1.txt")):
print("Failed mission")
progress("Failed mission")
failed = True
if not drive_brake(mavproxy, mav):
print("Failed brake")
progress("Failed brake")
failed = True
if not disarm_rover(mavproxy, mav):
print("Failed to DISARM")
progress("Failed to DISARM")
failed = True
if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/APMrover2-log.bin")):
print("Failed log download")
progress("Failed log download")
failed = True
# if not drive_left_circuit(mavproxy, mav):
# print("Failed left circuit")
# progress("Failed left circuit")
# failed = True
# if not drive_RTL(mavproxy, mav):
# print("Failed RTL")
# progress("Failed RTL")
# failed = True
# do not move this to be the first test. MAVProxy's dedupe
# function may bite you.
print("Getting banner")
progress("Getting banner")
if not do_get_banner(mavproxy, mav):
print("FAILED: get banner")
progress("FAILED: get banner")
failed = True
print("Getting autopilot capabilities")
progress("Getting autopilot capabilities")
if not do_get_autopilot_capabilities(mavproxy, mav):
print("FAILED: get capabilities")
progress("FAILED: get capabilities")
failed = True
print("Setting mode via MAV_COMMAND_DO_SET_MODE")
progress("Setting mode via MAV_COMMAND_DO_SET_MODE")
if not do_set_mode_via_command_long(mavproxy, mav):
failed = True
except pexpect.TIMEOUT as e:
print("Failed with timeout")
progress("Failed with timeout")
failed = True
mav.close()
@ -333,6 +333,6 @@ def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fa
shutil.copy(valgrind_log, util.reltopdir("../buildlogs/APMrover2-valgrind.log"))
if failed:
print("FAILED: %s" % e)
progress("FAILED: %s" % e)
return False
return True

File diff suppressed because it is too large Load Diff

View File

@ -58,7 +58,7 @@ def takeoff(mavproxy, mav):
# level off
mavproxy.send('rc 2 1500\n')
print("TAKEOFF COMPLETE")
progress("TAKEOFF COMPLETE")
return True
@ -70,44 +70,44 @@ def fly_left_circuit(mavproxy, mav):
if not wait_level_flight(mavproxy, mav):
return False
print("Flying left circuit")
progress("Flying left circuit")
# do 4 turns
for i in range(0, 4):
# hard left
print("Starting turn %u" % i)
progress("Starting turn %u" % i)
mavproxy.send('rc 1 1000\n')
if not wait_heading(mav, 270 - (90*i), accuracy=10):
return False
mavproxy.send('rc 1 1500\n')
print("Starting leg %u" % i)
progress("Starting leg %u" % i)
if not wait_distance(mav, 100, accuracy=20):
return False
print("Circuit complete")
progress("Circuit complete")
return True
def fly_RTL(mavproxy, mav):
"""Fly to home."""
print("Flying home in RTL")
progress("Flying home in RTL")
mavproxy.send('switch 2\n')
wait_mode(mav, 'RTL')
if not wait_location(mav, homeloc, accuracy=120,
target_altitude=homeloc.alt+100, height_accuracy=20,
timeout=180):
return False
print("RTL Complete")
progress("RTL Complete")
return True
def fly_LOITER(mavproxy, mav, num_circles=4):
"""Loiter where we are."""
print("Testing LOITER for %u turns" % num_circles)
progress("Testing LOITER for %u turns" % num_circles)
mavproxy.send('loiter\n')
wait_mode(mav, 'LOITER')
m = mav.recv_match(type='VFR_HUD', blocking=True)
initial_alt = m.alt
print("Initial altitude %u\n" % initial_alt)
progress("Initial altitude %u\n" % initial_alt)
while num_circles > 0:
if not wait_heading(mav, 0, accuracy=10, timeout=60):
@ -115,32 +115,32 @@ def fly_LOITER(mavproxy, mav, num_circles=4):
if not wait_heading(mav, 180, accuracy=10, timeout=60):
return False
num_circles -= 1
print("Loiter %u circles left" % num_circles)
progress("Loiter %u circles left" % num_circles)
m = mav.recv_match(type='VFR_HUD', blocking=True)
final_alt = m.alt
print("Final altitude %u initial %u\n" % (final_alt, initial_alt))
progress("Final altitude %u initial %u\n" % (final_alt, initial_alt))
mavproxy.send('mode FBWA\n')
wait_mode(mav, 'FBWA')
if abs(final_alt - initial_alt) > 20:
print("Failed to maintain altitude")
progress("Failed to maintain altitude")
return False
print("Completed Loiter OK")
progress("Completed Loiter OK")
return True
def fly_CIRCLE(mavproxy, mav, num_circles=1):
"""Circle where we are."""
print("Testing CIRCLE for %u turns" % num_circles)
progress("Testing CIRCLE for %u turns" % num_circles)
mavproxy.send('mode CIRCLE\n')
wait_mode(mav, 'CIRCLE')
m = mav.recv_match(type='VFR_HUD', blocking=True)
initial_alt = m.alt
print("Initial altitude %u\n" % initial_alt)
progress("Initial altitude %u\n" % initial_alt)
while num_circles > 0:
if not wait_heading(mav, 0, accuracy=10, timeout=60):
@ -148,27 +148,27 @@ def fly_CIRCLE(mavproxy, mav, num_circles=1):
if not wait_heading(mav, 180, accuracy=10, timeout=60):
return False
num_circles -= 1
print("CIRCLE %u circles left" % num_circles)
progress("CIRCLE %u circles left" % num_circles)
m = mav.recv_match(type='VFR_HUD', blocking=True)
final_alt = m.alt
print("Final altitude %u initial %u\n" % (final_alt, initial_alt))
progress("Final altitude %u initial %u\n" % (final_alt, initial_alt))
mavproxy.send('mode FBWA\n')
wait_mode(mav, 'FBWA')
if abs(final_alt - initial_alt) > 20:
print("Failed to maintain altitude")
progress("Failed to maintain altitude")
return False
print("Completed CIRCLE OK")
progress("Completed CIRCLE OK")
return True
def wait_level_flight(mavproxy, mav, accuracy=5, timeout=30):
"""Wait for level flight."""
tstart = get_sim_time(mav)
print("Waiting for level flight")
progress("Waiting for level flight")
mavproxy.send('rc 1 1500\n')
mavproxy.send('rc 2 1500\n')
mavproxy.send('rc 4 1500\n')
@ -176,11 +176,11 @@ def wait_level_flight(mavproxy, mav, accuracy=5, timeout=30):
m = mav.recv_match(type='ATTITUDE', blocking=True)
roll = math.degrees(m.roll)
pitch = math.degrees(m.pitch)
print("Roll=%.1f Pitch=%.1f" % (roll, pitch))
progress("Roll=%.1f Pitch=%.1f" % (roll, pitch))
if math.fabs(roll) <= accuracy and math.fabs(pitch) <= accuracy:
print("Attained level flight")
progress("Attained level flight")
return True
print("Failed to attain level flight")
progress("Failed to attain level flight")
return False
@ -196,7 +196,7 @@ def change_altitude(mavproxy, mav, altitude, accuracy=30):
if not wait_altitude(mav, altitude-accuracy/2, altitude+accuracy/2):
return False
mavproxy.send('rc 2 1500\n')
print("Reached target altitude at %u" % mav.messages['VFR_HUD'].alt)
progress("Reached target altitude at %u" % mav.messages['VFR_HUD'].alt)
return wait_level_flight(mavproxy, mav)
@ -212,7 +212,7 @@ def axial_left_roll(mavproxy, mav, count=1):
wait_mode(mav, 'MANUAL')
while count > 0:
print("Starting roll")
progress("Starting roll")
mavproxy.send('rc 1 1000\n')
if not wait_roll(mav, -150, accuracy=90):
mavproxy.send('rc 1 1500\n')
@ -245,7 +245,7 @@ def inside_loop(mavproxy, mav, count=1):
wait_mode(mav, 'MANUAL')
while count > 0:
print("Starting loop")
progress("Starting loop")
mavproxy.send('rc 2 1000\n')
if not wait_pitch(mav, -60, accuracy=20):
return False
@ -275,7 +275,7 @@ def test_stabilize(mavproxy, mav, count=1):
count = 1
while count > 0:
print("Starting roll")
progress("Starting roll")
mavproxy.send('rc 1 2000\n')
if not wait_roll(mav, -150, accuracy=90):
return False
@ -310,7 +310,7 @@ def test_acro(mavproxy, mav, count=1):
count = 1
while count > 0:
print("Starting roll")
progress("Starting roll")
mavproxy.send('rc 1 1000\n')
if not wait_roll(mav, -150, accuracy=90):
return False
@ -332,7 +332,7 @@ def test_acro(mavproxy, mav, count=1):
count = 2
while count > 0:
print("Starting loop")
progress("Starting loop")
mavproxy.send('rc 2 1000\n')
if not wait_pitch(mav, -60, accuracy=20):
return False
@ -364,48 +364,48 @@ def test_FBWB(mavproxy, mav, count=1, mode='FBWB'):
m = mav.recv_match(type='VFR_HUD', blocking=True)
initial_alt = m.alt
print("Initial altitude %u\n" % initial_alt)
progress("Initial altitude %u\n" % initial_alt)
print("Flying right circuit")
progress("Flying right circuit")
# do 4 turns
for i in range(0, 4):
# hard left
print("Starting turn %u" % i)
progress("Starting turn %u" % i)
mavproxy.send('rc 1 1800\n')
if not wait_heading(mav, 0 + (90*i), accuracy=20, timeout=60):
mavproxy.send('rc 1 1500\n')
return False
mavproxy.send('rc 1 1500\n')
print("Starting leg %u" % i)
progress("Starting leg %u" % i)
if not wait_distance(mav, 100, accuracy=20):
return False
print("Circuit complete")
progress("Circuit complete")
print("Flying rudder left circuit")
progress("Flying rudder left circuit")
# do 4 turns
for i in range(0, 4):
# hard left
print("Starting turn %u" % i)
progress("Starting turn %u" % i)
mavproxy.send('rc 4 1900\n')
if not wait_heading(mav, 360 - (90*i), accuracy=20, timeout=60):
mavproxy.send('rc 4 1500\n')
return False
mavproxy.send('rc 4 1500\n')
print("Starting leg %u" % i)
progress("Starting leg %u" % i)
if not wait_distance(mav, 100, accuracy=20):
return False
print("Circuit complete")
progress("Circuit complete")
m = mav.recv_match(type='VFR_HUD', blocking=True)
final_alt = m.alt
print("Final altitude %u initial %u\n" % (final_alt, initial_alt))
progress("Final altitude %u initial %u\n" % (final_alt, initial_alt))
# back to FBWA
mavproxy.send('mode FBWA\n')
wait_mode(mav, 'FBWA')
if abs(final_alt - initial_alt) > 20:
print("Failed to maintain altitude")
progress("Failed to maintain altitude")
return False
return wait_level_flight(mavproxy, mav)
@ -422,7 +422,7 @@ def setup_rc(mavproxy):
def fly_mission(mavproxy, mav, filename, height_accuracy=-1, target_altitude=None):
"""Fly a mission from a file."""
global homeloc
print("Flying mission %s" % filename)
progress("Flying mission %s" % filename)
mavproxy.send('wp load %s\n' % filename)
mavproxy.expect('Flight plan received')
mavproxy.send('wp list\n')
@ -434,7 +434,7 @@ def fly_mission(mavproxy, mav, filename, height_accuracy=-1, target_altitude=Non
if not wait_groundspeed(mav, 0, 0.5, timeout=60):
return False
mavproxy.expect("Auto disarmed")
print("Mission OK")
progress("Mission OK")
return True
@ -458,10 +458,10 @@ def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
mavproxy = util.start_MAVProxy_SITL('ArduPlane', options=options)
mavproxy.expect('Telemetry log: (\S+)')
logfile = mavproxy.match.group(1)
print("LOGFILE %s" % logfile)
progress("LOGFILE %s" % logfile)
buildlog = util.reltopdir("../buildlogs/ArduPlane-test.tlog")
print("buildlog=%s" % buildlog)
progress("buildlog=%s" % buildlog)
if os.path.exists(buildlog):
os.unlink(buildlog)
try:
@ -476,13 +476,13 @@ def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
expect_list_clear()
expect_list_extend([sitl, mavproxy])
print("Started simulator")
progress("Started simulator")
# get a mavlink connection going
try:
mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True)
except Exception as msg:
print("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
progress("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
raise
mav.message_hooks.append(message_hook)
mav.idle_hooks.append(idle_hook)
@ -491,72 +491,72 @@ def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
fail_list = []
e = 'None'
try:
print("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION)
progress("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION)
mav.wait_heartbeat()
print("Setting up RC parameters")
progress("Setting up RC parameters")
setup_rc(mavproxy)
print("Waiting for GPS fix")
progress("Waiting for GPS fix")
mav.recv_match(condition='VFR_HUD.alt>10', blocking=True)
mav.wait_gps_fix()
while mav.location().alt < 10:
mav.wait_gps_fix()
homeloc = mav.location()
print("Home location: %s" % homeloc)
progress("Home location: %s" % homeloc)
if not takeoff(mavproxy, mav):
print("Failed takeoff")
progress("Failed takeoff")
failed = True
fail_list.append("takeoff")
if not fly_left_circuit(mavproxy, mav):
print("Failed left circuit")
progress("Failed left circuit")
failed = True
fail_list.append("left_circuit")
if not axial_left_roll(mavproxy, mav, 1):
print("Failed left roll")
progress("Failed left roll")
failed = True
fail_list.append("left_roll")
if not inside_loop(mavproxy, mav):
print("Failed inside loop")
progress("Failed inside loop")
failed = True
fail_list.append("inside_loop")
if not test_stabilize(mavproxy, mav):
print("Failed stabilize test")
progress("Failed stabilize test")
failed = True
fail_list.append("stabilize")
if not test_acro(mavproxy, mav):
print("Failed ACRO test")
progress("Failed ACRO test")
failed = True
fail_list.append("acro")
if not test_FBWB(mavproxy, mav):
print("Failed FBWB test")
progress("Failed FBWB test")
failed = True
fail_list.append("fbwb")
if not test_FBWB(mavproxy, mav, mode='CRUISE'):
print("Failed CRUISE test")
progress("Failed CRUISE test")
failed = True
fail_list.append("cruise")
if not fly_RTL(mavproxy, mav):
print("Failed RTL")
progress("Failed RTL")
failed = True
fail_list.append("RTL")
if not fly_LOITER(mavproxy, mav):
print("Failed LOITER")
progress("Failed LOITER")
failed = True
fail_list.append("LOITER")
if not fly_CIRCLE(mavproxy, mav):
print("Failed CIRCLE")
progress("Failed CIRCLE")
failed = True
fail_list.append("LOITER")
if not fly_mission(mavproxy, mav, os.path.join(testdir, "ap1.txt"), height_accuracy = 10,
target_altitude=homeloc.alt+100):
print("Failed mission")
progress("Failed mission")
failed = True
fail_list.append("mission")
if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/ArduPlane-log.bin")):
print("Failed log download")
progress("Failed log download")
failed = True
fail_list.append("log_download")
except pexpect.TIMEOUT as e:
print("Failed with timeout")
progress("Failed with timeout")
failed = True
fail_list.append("timeout")
@ -570,6 +570,7 @@ def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
shutil.copy(valgrind_log, util.reltopdir("../buildlogs/ArduPlane-valgrind.log"))
if failed:
print("FAILED: %s" % e, fail_list)
progress("FAILED: %s" % e)
progress("Fail list: %s" % fail_list)
return False
return True

View File

@ -26,7 +26,7 @@ def arm_sub(mavproxy, mav):
mavproxy.send('arm throttle\n')
mavproxy.expect('ARMED')
print("SUB ARMED")
progress("SUB ARMED")
return True
def dive_manual(mavproxy, mav):
@ -65,19 +65,19 @@ def dive_manual(mavproxy, mav):
# wait for disarm
mav.motors_disarmed_wait()
print("Manual dive OK")
progress("Manual dive OK")
return True
def dive_mission(mavproxy, mav, filename):
print("Executing mission %s" % filename)
progress("Executing mission %s" % filename)
mavproxy.send('wp load %s\n' % filename)
mavproxy.expect('Flight plan received')
mavproxy.send('wp list\n')
mavproxy.expect('Saved [0-9]+ waypoints')
if not arm_sub(mavproxy, mav):
print("Failed to ARM")
progress("Failed to ARM")
return False
mavproxy.send('mode auto\n')
@ -91,7 +91,7 @@ def dive_mission(mavproxy, mav, filename):
# wait for disarm
mav.motors_disarmed_wait()
print("Mission OK")
progress("Mission OK")
return True
def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False, speedup=10):
@ -127,10 +127,10 @@ def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False
mavproxy = util.start_MAVProxy_SITL('ArduSub', options=options)
mavproxy.expect('Telemetry log: (\S+)')
logfile = mavproxy.match.group(1)
print("LOGFILE %s" % logfile)
progress("LOGFILE %s" % logfile)
buildlog = util.reltopdir("../buildlogs/ArduSub-test.tlog")
print("buildlog=%s" % buildlog)
progress("buildlog=%s" % buildlog)
if os.path.exists(buildlog):
os.unlink(buildlog)
try:
@ -145,13 +145,13 @@ def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False
expect_list_clear()
expect_list_extend([sitl, mavproxy])
print("Started simulator")
progress("Started simulator")
# get a mavlink connection going
try:
mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True)
except Exception as msg:
print("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
progress("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
raise
mav.message_hooks.append(message_hook)
mav.idle_hooks.append(idle_hook)
@ -159,30 +159,30 @@ def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False
failed = False
e = 'None'
try:
print("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION)
progress("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION)
mav.wait_heartbeat()
print("Waiting for GPS fix")
progress("Waiting for GPS fix")
mav.wait_gps_fix()
# wait for EKF and GPS checks to pass
mavproxy.expect('IMU0 is using GPS')
homeloc = mav.location()
print("Home location: %s" % homeloc)
progress("Home location: %s" % homeloc)
if not arm_sub(mavproxy, mav):
print("Failed to ARM")
progress("Failed to ARM")
failed = True
if not dive_manual(mavproxy, mav):
print("Failed manual dive")
progress("Failed manual dive")
failed = True
if not dive_mission(mavproxy, mav, os.path.join(testdir, "sub_mission.txt")):
print("Failed auto mission")
progress("Failed auto mission")
failed = True
if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/ArduSub-log.bin")):
print("Failed log download")
progress("Failed log download")
failed = True
except pexpect.TIMEOUT as e:
print("Failed with timeout")
progress("Failed with timeout")
failed = True
mav.close()
@ -195,6 +195,6 @@ def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False
shutil.copy(valgrind_log, util.reltopdir("../buildlogs/APMrover2-valgrind.log"))
if failed:
print("FAILED: %s" % e)
progress("FAILED: %s" % e)
return False
return True

View File

@ -22,16 +22,16 @@ def wait_ekf_happy(mav, timeout=30):
tstart = get_sim_time(mav)
required_value = 831
print("Waiting for EKF value %u" % (required_value))
progress("Waiting for EKF value %u" % (required_value))
while timeout is None or get_sim_time(mav) < tstart + timeout:
m = mav.recv_match(type='EKF_STATUS_REPORT', blocking=True)
current = m.flags
if (tstart - get_sim_time(mav)) % 5 == 0:
print("Wait EKF.flags: required:%u current:%u" % (required_value, current))
progress("Wait EKF.flags: required:%u current:%u" % (required_value, current))
if current == required_value:
print("EKF Flags OK")
progress("EKF Flags OK")
return
print("Failed to get EKF.flags=%u" % required_value)
progress("Failed to get EKF.flags=%u" % required_value)
raise AutoTestTimeoutException()
def expect_list_clear():
@ -68,6 +68,13 @@ def expect_callback(e):
util.pexpect_drain(p)
'''
SIM UTILITIES
'''
def progress(text):
"""Display autotest progress text."""
print("AUTOTEST: " + text)
def get_distance(loc1, loc2):
"""Get ground distance between two locations."""
dlat = loc2.lat - loc1.lat
@ -105,7 +112,7 @@ def set_parameter(mavproxy, name ,value):
if float(returned_value) == float(value):
# yes, exactly equal.
break
print("Param fetch returned incorrect value (%s) vs (%s)" % (returned_value, value))
progress("Param fetch returned incorrect value (%s) vs (%s)" % (returned_value, value))
def get_parameter(mavproxy, name):
mavproxy.send("param fetch %s\n" % (name))
@ -118,75 +125,75 @@ def wait_altitude(mav, alt_min, alt_max, timeout=30):
previous_alt = 0
tstart = get_sim_time(mav)
print("Waiting for altitude between %u and %u" % (alt_min, alt_max))
progress("Waiting for altitude between %u and %u" % (alt_min, alt_max))
while get_sim_time(mav) < tstart + timeout:
m = mav.recv_match(type='VFR_HUD', blocking=True)
climb_rate = m.alt - previous_alt
previous_alt = m.alt
print("Wait Altitude: Cur:%u, min_alt:%u, climb_rate: %u" % (m.alt, alt_min, climb_rate))
progress("Wait Altitude: Cur:%u, min_alt:%u, climb_rate: %u" % (m.alt, alt_min, climb_rate))
if m.alt >= alt_min and m.alt <= alt_max:
print("Altitude OK")
progress("Altitude OK")
return True
print("Failed to attain altitude range")
progress("Failed to attain altitude range")
return False
def wait_groundspeed(mav, gs_min, gs_max, timeout=30):
"""Wait for a given ground speed range."""
tstart = get_sim_time(mav)
print("Waiting for groundspeed between %.1f and %.1f" % (gs_min, gs_max))
progress("Waiting for groundspeed between %.1f and %.1f" % (gs_min, gs_max))
while get_sim_time(mav) < tstart + timeout:
m = mav.recv_match(type='VFR_HUD', blocking=True)
print("Wait groundspeed %.1f, target:%.1f" % (m.groundspeed, gs_min))
progress("Wait groundspeed %.1f, target:%.1f" % (m.groundspeed, gs_min))
if m.groundspeed >= gs_min and m.groundspeed <= gs_max:
return True
print("Failed to attain groundspeed range")
progress("Failed to attain groundspeed range")
return False
def wait_roll(mav, roll, accuracy, timeout=30):
"""Wait for a given roll in degrees."""
tstart = get_sim_time(mav)
print("Waiting for roll of %d at %s" % (roll, time.ctime()))
progress("Waiting for roll of %d at %s" % (roll, time.ctime()))
while get_sim_time(mav) < tstart + timeout:
m = mav.recv_match(type='ATTITUDE', blocking=True)
p = math.degrees(m.pitch)
r = math.degrees(m.roll)
print("Roll %d Pitch %d" % (r, p))
progress("Roll %d Pitch %d" % (r, p))
if math.fabs(r - roll) <= accuracy:
print("Attained roll %d" % roll)
progress("Attained roll %d" % roll)
return True
print("Failed to attain roll %d" % roll)
progress("Failed to attain roll %d" % roll)
return False
def wait_pitch(mav, pitch, accuracy, timeout=30):
"""Wait for a given pitch in degrees."""
tstart = get_sim_time(mav)
print("Waiting for pitch of %u at %s" % (pitch, time.ctime()))
progress("Waiting for pitch of %u at %s" % (pitch, time.ctime()))
while get_sim_time(mav) < tstart + timeout:
m = mav.recv_match(type='ATTITUDE', blocking=True)
p = math.degrees(m.pitch)
r = math.degrees(m.roll)
print("Pitch %d Roll %d" % (p, r))
progress("Pitch %d Roll %d" % (p, r))
if math.fabs(p - pitch) <= accuracy:
print("Attained pitch %d" % pitch)
progress("Attained pitch %d" % pitch)
return True
print("Failed to attain pitch %d" % pitch)
progress("Failed to attain pitch %d" % pitch)
return False
def wait_heading(mav, heading, accuracy=5, timeout=30):
"""Wait for a given heading."""
tstart = get_sim_time(mav)
print("Waiting for heading %u with accuracy %u" % (heading, accuracy))
progress("Waiting for heading %u with accuracy %u" % (heading, accuracy))
while get_sim_time(mav) < tstart + timeout:
m = mav.recv_match(type='VFR_HUD', blocking=True)
print("Heading %u" % m.heading)
progress("Heading %u" % m.heading)
if math.fabs(m.heading - heading) <= accuracy:
print("Attained heading %u" % heading)
progress("Attained heading %u" % heading)
return True
print("Failed to attain heading %u" % heading)
progress("Failed to attain heading %u" % heading)
return False
@ -197,14 +204,14 @@ def wait_distance(mav, distance, accuracy=5, timeout=30):
while get_sim_time(mav) < tstart + timeout:
pos = mav.location()
delta = get_distance(start, pos)
print("Distance %.2f meters" % delta)
progress("Distance %.2f meters" % delta)
if math.fabs(delta - distance) <= accuracy:
print("Attained distance %.2f meters OK" % delta)
progress("Attained distance %.2f meters OK" % delta)
return True
if delta > (distance + accuracy):
print("Failed distance - overshoot delta=%f distance=%f" % (delta, distance))
progress("Failed distance - overshoot delta=%f distance=%f" % (delta, distance))
return False
print("Failed to attain distance %u" % distance)
progress("Failed to attain distance %u" % distance)
return False
@ -213,18 +220,18 @@ def wait_location(mav, loc, accuracy=5, timeout=30, target_altitude=None, height
tstart = get_sim_time(mav)
if target_altitude is None:
target_altitude = loc.alt
print("Waiting for location %.4f,%.4f at altitude %.1f height_accuracy=%.1f" % (
progress("Waiting for location %.4f,%.4f at altitude %.1f height_accuracy=%.1f" % (
loc.lat, loc.lng, target_altitude, height_accuracy))
while get_sim_time(mav) < tstart + timeout:
pos = mav.location()
delta = get_distance(loc, pos)
print("Distance %.2f meters alt %.1f" % (delta, pos.alt))
progress("Distance %.2f meters alt %.1f" % (delta, pos.alt))
if delta <= accuracy:
if height_accuracy != -1 and math.fabs(pos.alt - target_altitude) > height_accuracy:
continue
print("Reached location (%.2f meters)" % delta)
progress("Reached location (%.2f meters)" % delta)
return True
print("Failed to attain location")
progress("Failed to attain location")
return False
@ -236,9 +243,9 @@ def wait_waypoint(mav, wpnum_start, wpnum_end, allow_skip=True, max_dist=2, time
current_wp = start_wp
mode = mav.flightmode
print("\ntest: wait for waypoint ranges start=%u end=%u\n\n" % (wpnum_start, wpnum_end))
progress("\ntest: wait for waypoint ranges start=%u end=%u\n\n" % (wpnum_start, wpnum_end))
# if start_wp != wpnum_start:
# print("test: Expected start waypoint %u but got %u" % (wpnum_start, start_wp))
# progress("test: Expected start waypoint %u but got %u" % (wpnum_start, start_wp))
# return False
while get_sim_time(mav) < tstart + timeout:
@ -249,27 +256,27 @@ def wait_waypoint(mav, wpnum_start, wpnum_end, allow_skip=True, max_dist=2, time
# if we changed mode, fail
if mav.flightmode != mode:
print('Exited %s mode' % mode)
progress('Exited %s mode' % mode)
return False
print("test: WP %u (wp_dist=%u Alt=%d), current_wp: %u, wpnum_end: %u" % (seq, wp_dist, m.alt, current_wp, wpnum_end))
progress("test: WP %u (wp_dist=%u Alt=%d), current_wp: %u, wpnum_end: %u" % (seq, wp_dist, m.alt, current_wp, wpnum_end))
if seq == current_wp+1 or (seq > current_wp+1 and allow_skip):
print("test: Starting new waypoint %u" % seq)
progress("test: Starting new waypoint %u" % seq)
tstart = get_sim_time(mav)
current_wp = seq
# the wp_dist check is a hack until we can sort out the right seqnum
# for end of mission
# if current_wp == wpnum_end or (current_wp == wpnum_end-1 and wp_dist < 2):
if (current_wp == wpnum_end and wp_dist < max_dist):
print("Reached final waypoint %u" % seq)
progress("Reached final waypoint %u" % seq)
return True
if (seq >= 255):
print("Reached final waypoint %u" % seq)
progress("Reached final waypoint %u" % seq)
return True
if seq > current_wp+1:
print("Failed: Skipped waypoint! Got wp %u expected %u" % (seq, current_wp+1))
progress("Failed: Skipped waypoint! Got wp %u expected %u" % (seq, current_wp+1))
return False
print("Failed: Timed out waiting for waypoint %u of %u" % (wpnum_end, wpnum_end))
progress("Failed: Timed out waiting for waypoint %u of %u" % (wpnum_end, wpnum_end))
return False
@ -286,9 +293,9 @@ def save_wp(mavproxy, mav):
def wait_mode(mav, mode, timeout=None):
print("Waiting for mode %s" % mode)
progress("Waiting for mode %s" % mode)
mav.recv_match(condition='MAV.flightmode.upper()=="%s".upper()' % mode, timeout=timeout, blocking=True)
print("Got mode %s" % mode)
progress("Got mode %s" % mode)
return mav.flightmode

View File

@ -24,7 +24,7 @@ homeloc = None
def fly_mission(mavproxy, mav, filename, fence, height_accuracy=-1):
"""Fly a mission from a file."""
print("Flying mission %s" % filename)
progress("Flying mission %s" % filename)
mavproxy.send('wp load %s\n' % filename)
mavproxy.expect('Flight plan received')
mavproxy.send('fence load %s\n' % fence)
@ -42,7 +42,7 @@ def fly_mission(mavproxy, mav, filename, fence, height_accuracy=-1):
if not wait_waypoint(mav, 20, 34, max_dist=60, timeout=1200):
return False
mavproxy.expect('DISARMED')
print("Mission OK")
progress("Mission OK")
return True
@ -65,10 +65,10 @@ def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
mavproxy = util.start_MAVProxy_SITL('QuadPlane', options=options)
mavproxy.expect('Telemetry log: (\S+)')
logfile = mavproxy.match.group(1)
print("LOGFILE %s" % logfile)
progress("LOGFILE %s" % logfile)
buildlog = util.reltopdir("../buildlogs/QuadPlane-test.tlog")
print("buildlog=%s" % buildlog)
progress("buildlog=%s" % buildlog)
if os.path.exists(buildlog):
os.unlink(buildlog)
try:
@ -83,13 +83,13 @@ def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
expect_list_clear()
expect_list_extend([sitl, mavproxy])
print("Started simulator")
progress("Started simulator")
# get a mavlink connection going
try:
mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True)
except Exception as msg:
print("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
progress("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
raise
mav.message_hooks.append(message_hook)
mav.idle_hooks.append(idle_hook)
@ -97,15 +97,15 @@ def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
failed = False
e = 'None'
try:
print("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION)
progress("Waiting for a heartbeat with mavlink protocol %s" % mav.WIRE_PROTOCOL_VERSION)
mav.wait_heartbeat()
print("Waiting for GPS fix")
progress("Waiting for GPS fix")
mav.recv_match(condition='VFR_HUD.alt>10', blocking=True)
mav.wait_gps_fix()
while mav.location().alt < 10:
mav.wait_gps_fix()
homeloc = mav.location()
print("Home location: %s" % homeloc)
progress("Home location: %s" % homeloc)
# wait for EKF and GPS checks to pass
wait_seconds(mav, 30)
@ -116,10 +116,10 @@ def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
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")
progress("Failed mission")
failed = True
except pexpect.TIMEOUT as e:
print("Failed with timeout")
progress("Failed with timeout")
failed = True
mav.close()
@ -132,6 +132,6 @@ def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
shutil.copy(valgrind_log, util.reltopdir("../buildlogs/QuadPlane-valgrind.log"))
if failed:
print("FAILED: %s" % e)
progress("FAILED: %s" % e)
return False
return True