mirror of https://github.com/ArduPilot/ardupilot
Tools: unify exception on os.link
This commit is contained in:
parent
73f8dd98f2
commit
a930822d9d
|
@ -75,17 +75,9 @@ class AutoTestRover(AutoTest):
|
|||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'APMrover2', options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||
logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % logfile)
|
||||
|
||||
buildlog = self.buildlogs_path("APMrover2-test.tlog")
|
||||
self.progress("buildlog=%s" % buildlog)
|
||||
if os.path.exists(buildlog):
|
||||
os.unlink(buildlog)
|
||||
try:
|
||||
os.link(logfile, buildlog)
|
||||
except Exception:
|
||||
pass
|
||||
self.logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % self.logfile)
|
||||
self.try_symlink_tlog()
|
||||
|
||||
self.progress("WAITING FOR PARAMETERS")
|
||||
self.mavproxy.expect('Received [0-9]+ parameters')
|
||||
|
|
|
@ -57,9 +57,6 @@ class AutoTestCopter(AutoTest):
|
|||
self.speedup = speedup
|
||||
|
||||
self.log_name = "ArduCopter"
|
||||
self.logfile = None
|
||||
self.buildlog = None
|
||||
self.copy_tlog = False
|
||||
|
||||
self.sitl = None
|
||||
self.hasInit = False
|
||||
|
@ -103,19 +100,7 @@ class AutoTestCopter(AutoTest):
|
|||
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||
self.logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % self.logfile)
|
||||
|
||||
self.buildlog = self.buildlogs_path(self.log_name + "-test.tlog")
|
||||
self.progress("buildlog=%s" % self.buildlog)
|
||||
self.copy_tlog = False
|
||||
if os.path.exists(self.buildlog):
|
||||
os.unlink(self.buildlog)
|
||||
try:
|
||||
os.link(self.logfile, self.buildlog)
|
||||
except Exception:
|
||||
self.progress("WARN: Failed to create symlink: %s => %s, "
|
||||
"will copy tlog manually to target location" %
|
||||
(self.logfile, self.buildlog))
|
||||
self.copy_tlog = True
|
||||
self.try_symlink_tlog()
|
||||
|
||||
self.progress("WAITING FOR PARAMETERS")
|
||||
self.mavproxy.expect('Received [0-9]+ parameters')
|
||||
|
|
|
@ -70,17 +70,9 @@ class AutoTestPlane(AutoTest):
|
|||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'ArduPlane', options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||
logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % logfile)
|
||||
|
||||
buildlog = self.buildlogs_path("ArduPlane-test.tlog")
|
||||
self.progress("buildlog=%s" % buildlog)
|
||||
if os.path.exists(buildlog):
|
||||
os.unlink(buildlog)
|
||||
try:
|
||||
os.link(logfile, buildlog)
|
||||
except Exception:
|
||||
pass
|
||||
self.logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % self.logfile)
|
||||
self.try_symlink_tlog()
|
||||
|
||||
self.mavproxy.expect('Received [0-9]+ parameters')
|
||||
|
||||
|
|
|
@ -64,17 +64,9 @@ class AutoTestSub(AutoTest):
|
|||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'ArduSub', options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||
logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % logfile)
|
||||
|
||||
buildlog = self.buildlogs_path("ArduSub-test.tlog")
|
||||
self.progress("buildlog=%s" % buildlog)
|
||||
if os.path.exists(buildlog):
|
||||
os.unlink(buildlog)
|
||||
try:
|
||||
os.link(logfile, buildlog)
|
||||
except Exception:
|
||||
pass
|
||||
self.logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % self.logfile)
|
||||
self.try_symlink_tlog()
|
||||
|
||||
self.progress("WAITING FOR PARAMETERS")
|
||||
self.mavproxy.expect('Received [0-9]+ parameters')
|
||||
|
|
|
@ -115,6 +115,9 @@ class AutoTest(ABC):
|
|||
self.use_map = use_map
|
||||
self.contexts = []
|
||||
self.context_push()
|
||||
self.buildlog = None
|
||||
self.copy_tlog = False
|
||||
self.logfile = None
|
||||
|
||||
@staticmethod
|
||||
def progress(text):
|
||||
|
@ -228,6 +231,20 @@ class AutoTest(ABC):
|
|||
self.progress("########## %s ##########" % description)
|
||||
self.progress("#")
|
||||
|
||||
def try_symlink_tlog(self):
|
||||
self.buildlog = self.buildlogs_path(self.log_name + "-test.tlog")
|
||||
self.progress("buildlog=%s" % self.buildlog)
|
||||
if os.path.exists(self.buildlog):
|
||||
os.unlink(self.buildlog)
|
||||
try:
|
||||
os.link(self.logfile, self.buildlog)
|
||||
except OSError as error:
|
||||
self.progress("OSError [%d]: %s" % (error.errno, error.strerror))
|
||||
self.progress("WARN: Failed to create symlink: %s => %s, "
|
||||
"will copy tlog manually to target location" %
|
||||
(self.logfile, self.buildlog))
|
||||
self.copy_tlog = True
|
||||
|
||||
#################################################
|
||||
# GENERAL UTILITIES
|
||||
#################################################
|
||||
|
|
|
@ -46,8 +46,6 @@ class AutoTestQuadPlane(AutoTest):
|
|||
|
||||
self.log_name = "QuadPlane"
|
||||
self.logfile = None
|
||||
self.buildlog = None
|
||||
self.copy_tlog = False
|
||||
|
||||
self.sitl = None
|
||||
self.hasInit = False
|
||||
|
@ -71,17 +69,9 @@ class AutoTestQuadPlane(AutoTest):
|
|||
self.mavproxy = util.start_MAVProxy_SITL(
|
||||
'QuadPlane', options=self.mavproxy_options())
|
||||
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||
logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % logfile)
|
||||
|
||||
buildlog = self.buildlogs_path("QuadPlane-test.tlog")
|
||||
self.progress("buildlog=%s" % buildlog)
|
||||
if os.path.exists(buildlog):
|
||||
os.unlink(buildlog)
|
||||
try:
|
||||
os.link(logfile, buildlog)
|
||||
except Exception:
|
||||
pass
|
||||
self.logfile = self.mavproxy.match.group(1)
|
||||
self.progress("LOGFILE %s" % self.logfile)
|
||||
self.try_symlink_tlog()
|
||||
|
||||
self.mavproxy.expect('Received [0-9]+ parameters')
|
||||
|
||||
|
|
Loading…
Reference in New Issue