mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Tools: autotest: fix race condition on parameter values
This commit is contained in:
parent
4a1ecd9fd0
commit
b23ea9a47b
@ -365,10 +365,7 @@ class AutoTest(ABC):
|
|||||||
def set_parameter(self, name, value):
|
def set_parameter(self, name, value):
|
||||||
for i in range(1, 10):
|
for i in range(1, 10):
|
||||||
self.mavproxy.send("param set %s %s\n" % (name, str(value)))
|
self.mavproxy.send("param set %s %s\n" % (name, str(value)))
|
||||||
self.mavproxy.send("param fetch %s\n" % name)
|
if self.get_parameter(name) == float(value):
|
||||||
self.mavproxy.expect("%s = (.*)" % (name,))
|
|
||||||
returned_value = self.mavproxy.match.group(1)
|
|
||||||
if float(returned_value) == float(value):
|
|
||||||
# yes, exactly equal.
|
# yes, exactly equal.
|
||||||
break
|
break
|
||||||
self.progress("Param fetch returned incorrect value (%s) vs (%s)"
|
self.progress("Param fetch returned incorrect value (%s) vs (%s)"
|
||||||
@ -376,7 +373,7 @@ class AutoTest(ABC):
|
|||||||
|
|
||||||
def get_parameter(self, name):
|
def get_parameter(self, name):
|
||||||
self.mavproxy.send("param fetch %s\n" % name)
|
self.mavproxy.send("param fetch %s\n" % name)
|
||||||
self.mavproxy.expect("%s = ([-0-9.]*)" % (name,))
|
self.mavproxy.expect("%s = ([-0-9.]*)\r\n" % (name,))
|
||||||
return float(self.mavproxy.match.group(1))
|
return float(self.mavproxy.match.group(1))
|
||||||
|
|
||||||
#################################################
|
#################################################
|
||||||
|
Loading…
Reference in New Issue
Block a user