mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Tools: autotest: raise exception on get_parameter failure
This commit is contained in:
parent
6585b6036d
commit
8985cc05c7
@ -663,8 +663,8 @@ class AutoTest(ABC):
|
|||||||
self.mavproxy.expect("%s = ([-0-9.]*)\r\n" % (name,), timeout=timeout/retry)
|
self.mavproxy.expect("%s = ([-0-9.]*)\r\n" % (name,), timeout=timeout/retry)
|
||||||
return float(self.mavproxy.match.group(1))
|
return float(self.mavproxy.match.group(1))
|
||||||
except pexpect.TIMEOUT:
|
except pexpect.TIMEOUT:
|
||||||
if i < retry:
|
pass
|
||||||
continue
|
raise NotAchievedException("Failed to retrieve parameter")
|
||||||
|
|
||||||
def context_get(self):
|
def context_get(self):
|
||||||
"""Get Saved parameters."""
|
"""Get Saved parameters."""
|
||||||
|
Loading…
Reference in New Issue
Block a user