From 0ea0b51ccdd1884608718b91fd6951542e70a2ba Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 24 Mar 2015 08:04:48 -0700 Subject: [PATCH] autotest: start plane sim during initial parameter load this is now needed to get timestamps from JSBSim --- Tools/autotest/arduplane.py | 26 ++++++++++++++++++-------- 1 file changed, 18 insertions(+), 8 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index c591bcb7fd..643e0e9dda 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -433,9 +433,23 @@ def fly_ArduPlane(viewerip=None, map=False): if map: options += ' --map' + cmd = util.reltopdir("Tools/autotest/jsbsim/runsim.py") + cmd += " --home=%s --wind=%s" % (HOME_LOCATION, WIND) + if viewerip: + cmd += " --fgout=%s:5503" % viewerip + + runsim = pexpect.spawn(cmd, timeout=10) + runsim.delaybeforesend = 0 + util.pexpect_autoclose(runsim) + runsim.expect('Simulator ready to fly') + sil = util.start_SIL('ArduPlane', wipe=True) + print("Starting MAVProxy") mavproxy = util.start_MAVProxy_SIL('ArduPlane', options=options) - mavproxy.expect('Received [0-9]+ parameters') + util.expect_setup_callback(mavproxy, expect_callback) + + mavproxy.expect('Logging to (\S+)') + mavproxy.expect('Received [0-9]+ parameters',timeout=3000) # setup test parameters mavproxy.send("param load %s/ArduPlane.parm\n" % testdir) @@ -446,11 +460,7 @@ def fly_ArduPlane(viewerip=None, map=False): # restart with new parms util.pexpect_close(mavproxy) util.pexpect_close(sil) - - cmd = util.reltopdir("Tools/autotest/jsbsim/runsim.py") - cmd += " --home=%s --wind=%s" % (HOME_LOCATION, WIND) - if viewerip: - cmd += " --fgout=%s:5503" % viewerip + util.pexpect_close(runsim) runsim = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10) runsim.delaybeforesend = 0 @@ -472,10 +482,10 @@ def fly_ArduPlane(viewerip=None, map=False): except Exception: pass - mavproxy.expect('Received [0-9]+ parameters') - util.expect_setup_callback(mavproxy, expect_callback) + mavproxy.expect('Received [0-9]+ parameters') + expect_list_clear() expect_list_extend([runsim, sil, mavproxy])