Autotest: Fix a race condition on the regression tests on Windows
This commit is contained in:
parent
78a3e1d07a
commit
9de1813ae6
@ -70,7 +70,7 @@ class AutoTestRover(AutoTest):
|
|||||||
gdbserver=self.gdbserver)
|
gdbserver=self.gdbserver)
|
||||||
self.mavproxy = util.start_MAVProxy_SITL(
|
self.mavproxy = util.start_MAVProxy_SITL(
|
||||||
'APMrover2', options=self.mavproxy_options())
|
'APMrover2', options=self.mavproxy_options())
|
||||||
self.mavproxy.expect('Telemetry log: (\S+)')
|
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||||
logfile = self.mavproxy.match.group(1)
|
logfile = self.mavproxy.match.group(1)
|
||||||
self.progress("LOGFILE %s" % logfile)
|
self.progress("LOGFILE %s" % logfile)
|
||||||
|
|
||||||
|
@ -94,7 +94,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
gdbserver=self.gdbserver)
|
gdbserver=self.gdbserver)
|
||||||
self.mavproxy = util.start_MAVProxy_SITL(
|
self.mavproxy = util.start_MAVProxy_SITL(
|
||||||
'ArduCopter', options=self.mavproxy_options())
|
'ArduCopter', options=self.mavproxy_options())
|
||||||
self.mavproxy.expect('Telemetry log: (\S+)')
|
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||||
self.logfile = self.mavproxy.match.group(1)
|
self.logfile = self.mavproxy.match.group(1)
|
||||||
self.progress("LOGFILE %s" % self.logfile)
|
self.progress("LOGFILE %s" % self.logfile)
|
||||||
|
|
||||||
|
@ -66,7 +66,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
gdbserver=self.gdbserver)
|
gdbserver=self.gdbserver)
|
||||||
self.mavproxy = util.start_MAVProxy_SITL(
|
self.mavproxy = util.start_MAVProxy_SITL(
|
||||||
'ArduPlane', options=self.mavproxy_options())
|
'ArduPlane', options=self.mavproxy_options())
|
||||||
self.mavproxy.expect('Telemetry log: (\S+)')
|
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||||
logfile = self.mavproxy.match.group(1)
|
logfile = self.mavproxy.match.group(1)
|
||||||
self.progress("LOGFILE %s" % logfile)
|
self.progress("LOGFILE %s" % logfile)
|
||||||
|
|
||||||
|
@ -62,7 +62,7 @@ class AutoTestSub(AutoTest):
|
|||||||
gdbserver=self.gdbserver)
|
gdbserver=self.gdbserver)
|
||||||
self.mavproxy = util.start_MAVProxy_SITL(
|
self.mavproxy = util.start_MAVProxy_SITL(
|
||||||
'ArduSub', options=self.mavproxy_options())
|
'ArduSub', options=self.mavproxy_options())
|
||||||
self.mavproxy.expect('Telemetry log: (\S+)')
|
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||||
logfile = self.mavproxy.match.group(1)
|
logfile = self.mavproxy.match.group(1)
|
||||||
self.progress("LOGFILE %s" % logfile)
|
self.progress("LOGFILE %s" % logfile)
|
||||||
|
|
||||||
|
@ -67,7 +67,7 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
gdbserver=self.gdbserver)
|
gdbserver=self.gdbserver)
|
||||||
self.mavproxy = util.start_MAVProxy_SITL(
|
self.mavproxy = util.start_MAVProxy_SITL(
|
||||||
'QuadPlane', options=self.mavproxy_options())
|
'QuadPlane', options=self.mavproxy_options())
|
||||||
self.mavproxy.expect('Telemetry log: (\S+)')
|
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
|
||||||
logfile = self.mavproxy.match.group(1)
|
logfile = self.mavproxy.match.group(1)
|
||||||
self.progress("LOGFILE %s" % logfile)
|
self.progress("LOGFILE %s" % logfile)
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user