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

Added \r\n to the expect() string as recomended at:
http://pexpect.readthedocs.io/en/stable/overview.html#find-the-end-of-line-cr-lf-conventions
this should work on both windows and linux systems

pexpect says it will always do a minimal (non greedy) matching and docs explicitly say that a .+ expression will always return only one character. These lines in autotest are looking for \S+, which, believing the documentation, would only return one character of the log file path.
Now we know that's not true, neither for Linux or for Windows (given the logs from @karthikdesai), so I can only assume that it does a greedy match but only for the characters it has received at the time expect is called.
Apparently, in the machines we are using autotest, it isn't a problem since MAVProxy is likely fast to give its output to pexpect before the expect method is called. On @karthikdesai's machine that wasn't happening since his machine was more or less loaded.
Concluding, this looks like a correct fix in the sense that it extends the regex pattern to wait for the end of line (and probably other places could benefit from it too).
This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-07-20 05:57:24 +02:00 committed by Randy Mackay
parent 700aaf2e8f
commit 5c07a44a6d
4 changed files with 5 additions and 5 deletions

View File

@ -239,7 +239,7 @@ def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fa
sitl = util.start_SITL(binary, model='rover', home=home, speedup=speedup, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
mavproxy = util.start_MAVProxy_SITL('APMrover2', options=options)
mavproxy.expect('Telemetry log: (\S+)')
mavproxy.expect('Telemetry log: (\S+)\r\n')
logfile = mavproxy.match.group(1)
progress("LOGFILE %s" % logfile)

View File

@ -1004,7 +1004,7 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal
if use_map:
options += ' --map'
mavproxy = util.start_MAVProxy_SITL('ArduCopter', options=options)
mavproxy.expect('Telemetry log: (\S+)')
mavproxy.expect('Telemetry log: (\S+)\r\n')
logfile = mavproxy.match.group(1)
progress("LOGFILE %s" % logfile)
@ -1357,7 +1357,7 @@ def fly_CopterAVC(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
if use_map:
options += ' --map'
mavproxy = util.start_MAVProxy_SITL('ArduCopter', options=options)
mavproxy.expect('Telemetry log: (\S+)')
mavproxy.expect('Telemetry log: (\S+)\r\n')
logfile = mavproxy.match.group(1)
progress("LOGFILE %s" % logfile)

View File

@ -456,7 +456,7 @@ def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
valgrind=valgrind, gdb=gdb, gdbserver=gdbserver,
defaults_file=os.path.join(testdir, 'default_params/plane-jsbsim.parm'))
mavproxy = util.start_MAVProxy_SITL('ArduPlane', options=options)
mavproxy.expect('Telemetry log: (\S+)')
mavproxy.expect('Telemetry log: (\S+)\r\n')
logfile = mavproxy.match.group(1)
progress("LOGFILE %s" % logfile)

View File

@ -125,7 +125,7 @@ def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False
sitl = util.start_SITL(binary, model='vectored', home=home, speedup=speedup, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
mavproxy = util.start_MAVProxy_SITL('ArduSub', options=options)
mavproxy.expect('Telemetry log: (\S+)')
mavproxy.expect('Telemetry log: (\S+)\r\n')
logfile = mavproxy.match.group(1)
progress("LOGFILE %s" % logfile)