Browse Source

autotest: upload failed CI logs to autotest server

mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
6b5088207b
  1. 3
      Tools/autotest/apmrover2.py
  2. 6
      Tools/autotest/arducopter.py
  3. 3
      Tools/autotest/arduplane.py
  4. 3
      Tools/autotest/ardusub.py
  5. 3
      Tools/autotest/balancebot.py
  6. 13
      Tools/autotest/common.py

3
Tools/autotest/apmrover2.py

@ -864,7 +864,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.run_test("Download logs", lambda: self.run_test("Download logs", lambda:
self.log_download( self.log_download(
self.buildlogs_path("APMrover2-log.bin"))) self.buildlogs_path("APMrover2-log.bin"),
upload_logs=len(self.fail_list)>0))
# if not drive_left_circuit(self): # if not drive_left_circuit(self):
# self.progress("Failed left circuit") # self.progress("Failed left circuit")
# failed = True # failed = True

6
Tools/autotest/arducopter.py

@ -2403,7 +2403,8 @@ class AutoTestCopter(AutoTest):
# Download logs # Download logs
self.run_test("log download", self.run_test("log download",
lambda: self.log_download( lambda: self.log_download(
self.buildlogs_path("ArduCopter-log.bin"))) self.buildlogs_path("ArduCopter-log.bin"),
upload_logs=len(self.fail_list)>0))
except pexpect.TIMEOUT: except pexpect.TIMEOUT:
self.progress("Failed with timeout") self.progress("Failed with timeout")
@ -2449,7 +2450,8 @@ class AutoTestCopter(AutoTest):
# mission ends with disarm so should be ok to download logs now # mission ends with disarm so should be ok to download logs now
self.run_test("log download", self.run_test("log download",
lambda: self.log_download( lambda: self.log_download(
self.buildlogs_path("Helicopter-log.bin"))) self.buildlogs_path("Helicopter-log.bin"),
upload_logs=len(self.fail_list)>0))
except pexpect.TIMEOUT: except pexpect.TIMEOUT:
self.fail_list.append("Failed with timeout") self.fail_list.append("Failed with timeout")

3
Tools/autotest/arduplane.py

@ -759,7 +759,8 @@ class AutoTestPlane(AutoTest):
self.run_test("Log download", self.run_test("Log download",
lambda: self.log_download( lambda: self.log_download(
self.buildlogs_path("ArduPlane-log.bin"))) self.buildlogs_path("ArduPlane-log.bin"),
upload_logs=True))
except pexpect.TIMEOUT: except pexpect.TIMEOUT:
self.progress("Failed with timeout") self.progress("Failed with timeout")

3
Tools/autotest/ardusub.py

@ -196,7 +196,8 @@ class AutoTestSub(AutoTest):
self.run_test("Log download", self.run_test("Log download",
lambda: self.log_download( lambda: self.log_download(
self.buildlogs_path("ArduSub-log.bin"))) self.buildlogs_path("ArduSub-log.bin"),
upload_logs=len(self.fail_list)>0))
except pexpect.TIMEOUT: except pexpect.TIMEOUT:
self.progress("Failed with timeout") self.progress("Failed with timeout")

3
Tools/autotest/balancebot.py

@ -93,7 +93,8 @@ class AutoTestBalanceBot(AutoTestRover):
self.run_test("Download logs", lambda: self.run_test("Download logs", lambda:
self.log_download( self.log_download(
self.buildlogs_path("APMrover2-log.bin"))) self.buildlogs_path("APMrover2-log.bin"),
upload_logs=len(self.fail_list)>0))
# if not drive_left_circuit(self): # if not drive_left_circuit(self):
# self.progress("Failed left circuit") # self.progress("Failed left circuit")
# failed = True # failed = True

13
Tools/autotest/common.py

@ -349,7 +349,7 @@ class AutoTest(ABC):
self.mavproxy.send('wp list\n') self.mavproxy.send('wp list\n')
self.mavproxy.expect('Requesting 0 waypoints') self.mavproxy.expect('Requesting 0 waypoints')
def log_download(self, filename, timeout=360): def log_download(self, filename, timeout=360, upload_logs=False):
"""Download latest log.""" """Download latest log."""
self.mav.wait_heartbeat() self.mav.wait_heartbeat()
self.mavproxy.send("log list\n") self.mavproxy.send("log list\n")
@ -361,6 +361,17 @@ class AutoTest(ABC):
self.mavproxy.expect("Finished downloading", timeout=timeout) self.mavproxy.expect("Finished downloading", timeout=timeout)
self.mav.wait_heartbeat() self.mav.wait_heartbeat()
self.mav.wait_heartbeat() self.mav.wait_heartbeat()
if upload_logs and not os.getenv("AUTOTEST_NO_UPLOAD"):
# optionally upload logs to server so we can see travis failure logs
import subprocess, glob, datetime
logdir=os.path.dirname(filename)
datedir=datetime.datetime.now().strftime("%Y-%m-%d-%H-%M")
flist = glob.glob("logs/*.BIN")
for e in ['BIN','bin','tlog']:
flist += glob.glob(os.path.join(logdir, '*.%s' % e))
print("Uploading %u logs to http://firmware.ardupilot.org/CI-Logs/%s" % (len(flist), datedir))
cmd = ['rsync', '-avz'] + flist + ['cilogs@autotest.ardupilot.org::CI-Logs/%s/' % datedir]
subprocess.call(cmd)
def show_gps_and_sim_positions(self, on_off): def show_gps_and_sim_positions(self, on_off):
"""Allow to display gps and actual position on map.""" """Allow to display gps and actual position on map."""

Loading…
Cancel
Save