Skip to content
Snippets Groups Projects
Commit cad14417 authored by Randy Mackay's avatar Randy Mackay
Browse files

AutoTest: print failed copter test

Name of the failed tests appears at the moment it fails and then again
after all tests have been run.  This hopefully makes it slightly easier
to know which test has failed
parent a4c675c2
No related branches found
No related tags found
No related merge requests found
...@@ -298,7 +298,8 @@ def fly_battery_failsafe(mavproxy, mav, timeout=30): ...@@ -298,7 +298,8 @@ def fly_battery_failsafe(mavproxy, mav, timeout=30):
mavproxy.send('param set SIM_BATT_VOLTAGE 10\n') mavproxy.send('param set SIM_BATT_VOLTAGE 10\n')
# wait for LAND mode # wait for LAND mode
if wait_mode(mav, 'LAND', timeout) == 'LAND': new_mode = wait_mode(mav, 'LAND')
if new_mode == 'LAND':
success = True success = True
# disable battery failsafe # disable battery failsafe
...@@ -308,7 +309,7 @@ def fly_battery_failsafe(mavproxy, mav, timeout=30): ...@@ -308,7 +309,7 @@ def fly_battery_failsafe(mavproxy, mav, timeout=30):
if success: if success:
print("Successfully entered LAND mode after battery failsafe") print("Successfully entered LAND mode after battery failsafe")
else: else:
print("Failed to neter LAND mode after battery failsafe") print("Failed to enter LAND mode after battery failsafe")
return success return success
...@@ -960,7 +961,8 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -960,7 +961,8 @@ def fly_ArduCopter(viewerip=None, map=False):
failed = False failed = False
e = 'None' failed_test_msg = "None"
try: try:
mav.wait_heartbeat() mav.wait_heartbeat()
setup_rc(mavproxy) setup_rc(mavproxy)
...@@ -968,18 +970,21 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -968,18 +970,21 @@ def fly_ArduCopter(viewerip=None, map=False):
print("# Calibrate level") print("# Calibrate level")
if not calibrate_level(mavproxy, mav): if not calibrate_level(mavproxy, mav):
print("calibrate_level failed") failed_test_msg = "calibrate_level failed"
print(failed_test_msg)
failed = True failed = True
# Arm # Arm
print("# Arm motors") print("# Arm motors")
if not arm_motors(mavproxy, mav): if not arm_motors(mavproxy, mav):
print("arm_motors failed") failed_test_msg = "arm_motors failed"
print(failed_test_msg)
failed = True failed = True
print("# Takeoff") print("# Takeoff")
if not takeoff(mavproxy, mav, 10): if not takeoff(mavproxy, mav, 10):
print("takeoff failed") failed_test_msg = "takeoff failed"
print(failed_test_msg)
failed = True failed = True
# Fly a square in Stabilize mode # Fly a square in Stabilize mode
...@@ -987,12 +992,14 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -987,12 +992,14 @@ def fly_ArduCopter(viewerip=None, map=False):
print("########## Fly a square and save WPs with CH7 switch ##########") print("########## Fly a square and save WPs with CH7 switch ##########")
print("#") print("#")
if not fly_square(mavproxy, mav): if not fly_square(mavproxy, mav):
print("fly_square failed") failed_test_msg = "fly_square failed"
print(failed_test_msg)
failed = True failed = True
print("# Land") print("# Land")
if not land(mavproxy, mav): if not land(mavproxy, mav):
print("land failed") failed_test_msg = "land failed"
print(failed_test_msg)
failed = True failed = True
print("Save landing WP") print("Save landing WP")
...@@ -1001,13 +1008,15 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -1001,13 +1008,15 @@ def fly_ArduCopter(viewerip=None, map=False):
# save the stored mission to file # save the stored mission to file
print("# Save out the CH7 mission to file") print("# Save out the CH7 mission to file")
if not save_mission_to_file(mavproxy, mav, os.path.join(testdir, "ch7_mission.txt")): if not save_mission_to_file(mavproxy, mav, os.path.join(testdir, "ch7_mission.txt")):
print("save_mission_to_file failed") failed_test_msg = "save_mission_to_file failed"
print(failed_test_msg)
failed = True failed = True
# fly the stored mission # fly the stored mission
print("# Fly CH7 saved mission") print("# Fly CH7 saved mission")
if not fly_mission(mavproxy, mav,height_accuracy = 0.5, target_altitude=10): if not fly_mission(mavproxy, mav,height_accuracy = 0.5, target_altitude=10):
print("fly_mission failed") failed_test_msg = "fly_mission failed"
print(failed_test_msg)
failed = True failed = True
# Throttle Failsafe # Throttle Failsafe
...@@ -1015,24 +1024,28 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -1015,24 +1024,28 @@ def fly_ArduCopter(viewerip=None, map=False):
print("########## Test Failsafe ##########") print("########## Test Failsafe ##########")
print("#") print("#")
if not fly_throttle_failsafe(mavproxy, mav): if not fly_throttle_failsafe(mavproxy, mav):
print("FS failed") failed_test_msg = "fly_throttle_failsafe failed"
print(failed_test_msg)
failed = True failed = True
# Takeoff # Takeoff
print("# Takeoff") print("# Takeoff")
if not takeoff(mavproxy, mav, 10): if not takeoff(mavproxy, mav, 10):
print("takeoff failed") failed_test_msg = "takeoff failed"
print(failed_test_msg)
failed = True failed = True
# Battery failsafe # Battery failsafe
if not fly_battery_failsafe(mavproxy, mav): if not fly_battery_failsafe(mavproxy, mav):
print("battery failsafe failed") failed_test_msg = "fly_battery_failsafe failed"
print(failed_test_msg)
failed = True failed = True
# Takeoff # Takeoff
print("# Takeoff") print("# Takeoff")
if not takeoff(mavproxy, mav, 10): if not takeoff(mavproxy, mav, 10):
print("takeoff failed") failed_test_msg = "takeoff failed"
print(failed_test_msg)
failed = True failed = True
# Stability patch # Stability patch
...@@ -1040,19 +1053,22 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -1040,19 +1053,22 @@ def fly_ArduCopter(viewerip=None, map=False):
print("########## Test Stability Patch ##########") print("########## Test Stability Patch ##########")
print("#") print("#")
if not fly_stability_patch(mavproxy, mav, 30): if not fly_stability_patch(mavproxy, mav, 30):
print("Stability Patch failed") failed_test_msg = "fly_stability_patch failed"
print(failed_test_msg)
failed = True failed = True
# RTL # RTL
print("# RTL #") print("# RTL #")
if not fly_RTL(mavproxy, mav): if not fly_RTL(mavproxy, mav):
print("RTL failed") failed_test_msg = "fly_RTL failed"
print(failed_test_msg)
failed = True failed = True
# Takeoff # Takeoff
print("# Takeoff") print("# Takeoff")
if not takeoff(mavproxy, mav, 10): if not takeoff(mavproxy, mav, 10):
print("takeoff failed") failed_test_msg = "takeoff failed"
print(failed_test_msg)
failed = True failed = True
# Fence test # Fence test
...@@ -1060,37 +1076,43 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -1060,37 +1076,43 @@ def fly_ArduCopter(viewerip=None, map=False):
print("########## Test Horizontal Fence ##########") print("########## Test Horizontal Fence ##########")
print("#") print("#")
if not fly_fence_test(mavproxy, mav, 180): if not fly_fence_test(mavproxy, mav, 180):
print("Fence test failed") failed_test_msg = "fly_fence_test failed"
print(failed_test_msg)
failed = True failed = True
# Takeoff # Takeoff
print("# Takeoff") print("# Takeoff")
if not takeoff(mavproxy, mav, 10): if not takeoff(mavproxy, mav, 10):
print("takeoff failed") failed_test_msg = "takeoff failed"
print(failed_test_msg)
failed = True failed = True
# Fly GPS Glitch Loiter test # Fly GPS Glitch Loiter test
print("# 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):
print("failed GPS glitch Loiter test") failed_test_msg = "fly_gps_glitch_loiter_test failed"
print(failed_test_msg)
failed = True failed = True
# RTL after GPS Glitch Loiter test # RTL after GPS Glitch Loiter test
print("# RTL #") print("# RTL #")
if not fly_RTL(mavproxy, mav): if not fly_RTL(mavproxy, mav):
print("RTL failed") failed_test_msg = "fly_RTL failed"
print(failed_test_msg)
failed = True failed = True
# Fly GPS Glitch test in auto mode # Fly GPS Glitch test in auto mode
print("# GPS Glitch Auto Test") print("# GPS Glitch Auto Test")
if not fly_gps_glitch_auto_test(mavproxy, mav): if not fly_gps_glitch_auto_test(mavproxy, mav):
print("failed GPS glitch Auto test") failed_test_msg = "fly_gps_glitch_auto_test failed"
print(failed_test_msg)
failed = True failed = True
# take-off ahead of next test # take-off ahead of next test
print("# Takeoff") print("# Takeoff")
if not takeoff(mavproxy, mav, 10): if not takeoff(mavproxy, mav, 10):
print("takeoff failed") failed_test_msg = "takeoff failed"
print(failed_test_msg)
failed = True failed = True
# Loiter for 10 seconds # Loiter for 10 seconds
...@@ -1098,7 +1120,8 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -1098,7 +1120,8 @@ def fly_ArduCopter(viewerip=None, map=False):
print("########## Test Loiter for 10 seconds ##########") print("########## Test Loiter for 10 seconds ##########")
print("#") print("#")
if not loiter(mavproxy, mav): if not loiter(mavproxy, mav):
print("loiter failed") failed_test_msg = "loiter failed"
print(failed_test_msg)
failed = True failed = True
# Loiter Climb # Loiter Climb
...@@ -1106,7 +1129,8 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -1106,7 +1129,8 @@ def fly_ArduCopter(viewerip=None, map=False):
print("# Loiter - climb to 30m") print("# Loiter - climb to 30m")
print("#") print("#")
if not change_alt(mavproxy, mav, 30): if not change_alt(mavproxy, mav, 30):
print("change_alt failed") failed_test_msg = "change_alt climb failed"
print(failed_test_msg)
failed = True failed = True
# Loiter Descend # Loiter Descend
...@@ -1114,11 +1138,13 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -1114,11 +1138,13 @@ def fly_ArduCopter(viewerip=None, map=False):
print("# Loiter - descend to 20m") print("# Loiter - descend to 20m")
print("#") print("#")
if not change_alt(mavproxy, mav, 20): if not change_alt(mavproxy, mav, 20):
print("change_alt failed") failed_test_msg = "change_alt descend failed"
print(failed_test_msg)
failed = True failed = True
if not takeoff(mavproxy, mav, 10): if not takeoff(mavproxy, mav, 10):
print("takeoff failed") failed_test_msg = "takeoff failed"
print(failed_test_msg)
failed = True failed = True
# RTL # RTL
...@@ -1126,19 +1152,22 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -1126,19 +1152,22 @@ def fly_ArduCopter(viewerip=None, map=False):
print("########## Test RTL ##########") print("########## Test RTL ##########")
print("#") print("#")
if not fly_RTL(mavproxy, mav): if not fly_RTL(mavproxy, mav):
print("RTL failed") failed_test_msg = "fly_RTL failed"
print(failed_test_msg)
failed = True failed = True
# Takeoff # Takeoff
print("# Takeoff") print("# Takeoff")
if not takeoff(mavproxy, mav, 10): if not takeoff(mavproxy, mav, 10):
print("takeoff failed") failed_test_msg = "takeoff failed"
print(failed_test_msg)
failed = True failed = True
# Simple mode # Simple mode
print("# Fly in SIMPLE mode") print("# Fly in SIMPLE mode")
if not fly_simple(mavproxy, mav): if not fly_simple(mavproxy, mav):
print("fly_simple failed") failed_test_msg = "fly_simple failed"
print(failed_test_msg)
failed = True failed = True
# RTL # RTL
...@@ -1146,37 +1175,43 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -1146,37 +1175,43 @@ def fly_ArduCopter(viewerip=None, map=False):
print("########## Test RTL ##########") print("########## Test RTL ##########")
print("#") print("#")
if not fly_RTL(mavproxy, mav): if not fly_RTL(mavproxy, mav):
print("RTL failed") failed_test_msg = "fly_RTL failed"
print(failed_test_msg)
failed = True failed = True
# Takeoff # Takeoff
print("# Takeoff") print("# Takeoff")
if not takeoff(mavproxy, mav, 10): if not takeoff(mavproxy, mav, 10):
print("takeoff failed") failed_test_msg = "takeoff failed"
print(failed_test_msg)
failed = True failed = True
# Fly a circle in super simple mode # Fly a circle in super simple mode
print("# Fly a circle in SUPER SIMPLE mode") print("# Fly a circle in SUPER SIMPLE mode")
if not fly_super_simple(mavproxy, mav): if not fly_super_simple(mavproxy, mav):
print("fly super simple failed") failed_test_msg = "fly_super_simple failed"
print(failed_test_msg)
failed = True failed = True
# RTL # RTL
print("# RTL #") print("# RTL #")
if not fly_RTL(mavproxy, mav): if not fly_RTL(mavproxy, mav):
print("RTL failed") failed_test_msg = "fly_RTL failed"
print(failed_test_msg)
failed = True failed = True
# Takeoff # Takeoff
print("# Takeoff") print("# Takeoff")
if not takeoff(mavproxy, mav, 10): if not takeoff(mavproxy, mav, 10):
print("takeoff failed") failed_test_msg = "takeoff failed"
print(failed_test_msg)
failed = True failed = True
# Circle mode # Circle mode
print("# Fly CIRCLE mode") print("# Fly CIRCLE mode")
if not fly_circle(mavproxy, mav): if not fly_circle(mavproxy, mav):
print("fly_circle failed") failed_test_msg = "fly_circle failed"
print(failed_test_msg)
failed = True failed = True
# RTL # RTL
...@@ -1184,21 +1219,25 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -1184,21 +1219,25 @@ def fly_ArduCopter(viewerip=None, map=False):
print("########## Test RTL ##########") print("########## Test RTL ##########")
print("#") print("#")
if not fly_RTL(mavproxy, mav): if not fly_RTL(mavproxy, mav):
print("RTL failed") failed_test_msg = "fly_RTL failed"
print(failed_test_msg)
failed = True failed = True
print("# Fly copter mission") print("# Fly copter mission")
if not fly_auto_test(mavproxy, mav): if not fly_auto_test(mavproxy, mav):
print("fly_mission failed") failed_test_msg = "fly_auto_test failed"
print(failed_test_msg)
failed = True failed = True
else: else:
print("Flew copter mission OK") print("Flew copter mission OK")
if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/ArduCopter-log.bin")): if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/ArduCopter-log.bin")):
print("Failed log download") failed_test_msg = "log_download failed"
print(failed_test_msg)
failed = True failed = True
except pexpect.TIMEOUT, e: except pexpect.TIMEOUT, failed_test_msg:
failed_test_msg = "Timeout"
failed = True failed = True
mav.close() mav.close()
...@@ -1211,7 +1250,7 @@ def fly_ArduCopter(viewerip=None, map=False): ...@@ -1211,7 +1250,7 @@ def fly_ArduCopter(viewerip=None, map=False):
shutil.copy("ArduCopter-valgrind.log", util.reltopdir("../buildlogs/ArduCopter-valgrind.log")) shutil.copy("ArduCopter-valgrind.log", util.reltopdir("../buildlogs/ArduCopter-valgrind.log"))
if failed: if failed:
print("FAILED: %s" % e) print("FAILED: %s" % failed_test_msg)
return False return False
return True return True
...@@ -1288,7 +1327,8 @@ def fly_CopterAVC(viewerip=None, map=False): ...@@ -1288,7 +1327,8 @@ def fly_CopterAVC(viewerip=None, map=False):
failed = False failed = False
e = 'None' failed_test_msg = "None"
try: try:
mav.wait_heartbeat() mav.wait_heartbeat()
setup_rc(mavproxy) setup_rc(mavproxy)
...@@ -1296,28 +1336,33 @@ def fly_CopterAVC(viewerip=None, map=False): ...@@ -1296,28 +1336,33 @@ def fly_CopterAVC(viewerip=None, map=False):
print("# Calibrate level") print("# Calibrate level")
if not calibrate_level(mavproxy, mav): if not calibrate_level(mavproxy, mav):
print("calibrate_level failed") failed_test_msg = "calibrate_level failed"
print(failed_test_msg)
failed = True failed = True
# Arm # Arm
print("# Arm motors") print("# Arm motors")
if not arm_motors(mavproxy, mav): if not arm_motors(mavproxy, mav):
print("arm_motors failed") failed_test_msg = "arm_motors failed"
print(failed_test_msg)
failed = True failed = True
print("# Fly AVC mission") print("# Fly AVC mission")
if not fly_avc_test(mavproxy, mav): if not fly_avc_test(mavproxy, mav):
print("fly_avc_test failed") failed_test_msg = "fly_avc_test failed"
print(failed_test_msg)
failed = True failed = True
else: else:
print("Flew AVC mission OK") print("Flew AVC mission OK")
#mission includes disarm at end so should be ok to download logs now #mission includes disarm at end so should be ok to download logs now
if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/CopterAVC-log.bin")): if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/CopterAVC-log.bin")):
print("Failed log download") failed_test_msg = "log_download failed"
print(failed_test_msg)
failed = True failed = True
except pexpect.TIMEOUT, e: except pexpect.TIMEOUT, failed_test_msg:
failed_test_msg = "Timeout"
failed = True failed = True
mav.close() mav.close()
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment