Browse Source

Autotest: Fix a race condition on the regression tests on Windows

master
Karthik Desai 7 years ago committed by Randy Mackay
parent
commit
9de1813ae6
  1. 2
      Tools/autotest/apmrover2.py
  2. 2
      Tools/autotest/arducopter.py
  3. 2
      Tools/autotest/arduplane.py
  4. 2
      Tools/autotest/ardusub.py
  5. 2
      Tools/autotest/quadplane.py

2
Tools/autotest/apmrover2.py

@ -70,7 +70,7 @@ class AutoTestRover(AutoTest): @@ -70,7 +70,7 @@ class AutoTestRover(AutoTest):
gdbserver=self.gdbserver)
self.mavproxy = util.start_MAVProxy_SITL(
'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)
self.progress("LOGFILE %s" % logfile)

2
Tools/autotest/arducopter.py

@ -94,7 +94,7 @@ class AutoTestCopter(AutoTest): @@ -94,7 +94,7 @@ class AutoTestCopter(AutoTest):
gdbserver=self.gdbserver)
self.mavproxy = util.start_MAVProxy_SITL(
'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.progress("LOGFILE %s" % self.logfile)

2
Tools/autotest/arduplane.py

@ -66,7 +66,7 @@ class AutoTestPlane(AutoTest): @@ -66,7 +66,7 @@ class AutoTestPlane(AutoTest):
gdbserver=self.gdbserver)
self.mavproxy = util.start_MAVProxy_SITL(
'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)
self.progress("LOGFILE %s" % logfile)

2
Tools/autotest/ardusub.py

@ -62,7 +62,7 @@ class AutoTestSub(AutoTest): @@ -62,7 +62,7 @@ class AutoTestSub(AutoTest):
gdbserver=self.gdbserver)
self.mavproxy = util.start_MAVProxy_SITL(
'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)
self.progress("LOGFILE %s" % logfile)

2
Tools/autotest/quadplane.py

@ -67,7 +67,7 @@ class AutoTestQuadPlane(AutoTest): @@ -67,7 +67,7 @@ class AutoTestQuadPlane(AutoTest):
gdbserver=self.gdbserver)
self.mavproxy = util.start_MAVProxy_SITL(
'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)
self.progress("LOGFILE %s" % logfile)

Loading…
Cancel
Save