Browse Source

autotest: removed the set of SYSID_THISMAV

this led to a race condition where some parameters were not loaded as
they were being sent with the wrong system ID
master
Andrew Tridgell 11 years ago
parent
commit
ccc449db19
  1. 1
      Tools/autotest/apmrover2.py
  2. 2
      Tools/autotest/arducopter.py
  3. 1
      Tools/autotest/arduplane.py
  4. 1
      Tools/autotest/autotest_jenkins.py

1
Tools/autotest/apmrover2.py

@ -88,7 +88,6 @@ def drive_APMrover2(viewerip=None, map=False): @@ -88,7 +88,6 @@ def drive_APMrover2(viewerip=None, map=False):
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
mavproxy.send('param set SYSID_THISMAV %u\n' % random.randint(100, 200))
mavproxy.send("param load %s/Rover.parm\n" % testdir)
mavproxy.expect('Loaded [0-9]+ parameters')

2
Tools/autotest/arducopter.py

@ -822,7 +822,6 @@ def fly_ArduCopter(viewerip=None, map=False): @@ -822,7 +822,6 @@ def fly_ArduCopter(viewerip=None, map=False):
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
mavproxy.send('param set SYSID_THISMAV %u\n' % random.randint(100, 200))
mavproxy.send("param load %s/ArduCopter.parm\n" % testdir)
mavproxy.expect('Loaded [0-9]+ parameters')
@ -1165,7 +1164,6 @@ def fly_CopterAVC(viewerip=None, map=False): @@ -1165,7 +1164,6 @@ def fly_CopterAVC(viewerip=None, map=False):
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
mavproxy.send('param set SYSID_THISMAV %u\n' % random.randint(100, 200))
mavproxy.send("param load %s/CopterAVC.parm\n" % testdir)
mavproxy.expect('Loaded [0-9]+ parameters')

1
Tools/autotest/arduplane.py

@ -432,7 +432,6 @@ def fly_ArduPlane(viewerip=None, map=False): @@ -432,7 +432,6 @@ def fly_ArduPlane(viewerip=None, map=False):
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
mavproxy.send('param set SYSID_THISMAV %u\n' % random.randint(100, 200))
mavproxy.send("param load %s/ArduPlane.parm\n" % testdir)
mavproxy.expect('Loaded [0-9]+ parameters')

1
Tools/autotest/autotest_jenkins.py

@ -150,7 +150,6 @@ def fly_ArduCopter_scripted(testname): @@ -150,7 +150,6 @@ def fly_ArduCopter_scripted(testname):
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
mavproxy.send('param set SYSID_THISMAV %u\n' % random.randint(100, 200))
mavproxy.send("param load %s/ArduCopter.parm\n" % testdir)
mavproxy.expect('Loaded [0-9]+ parameters')

Loading…
Cancel
Save