mirror of https://github.com/ArduPilot/ardupilot
Tools: autotest: add assumption run_tests is only called once - remove hasInit
This commit is contained in:
parent
8a7555bf56
commit
6f1f98dc3c
|
@ -56,7 +56,6 @@ class AutoTestRover(AutoTest):
|
|||
self.speedup = speedup
|
||||
|
||||
self.sitl = None
|
||||
self.hasInit = False
|
||||
|
||||
self.log_name = "APMrover2"
|
||||
|
||||
|
@ -96,8 +95,6 @@ class AutoTestRover(AutoTest):
|
|||
|
||||
self.get_mavlink_connection_going()
|
||||
|
||||
self.hasInit = True
|
||||
|
||||
self.apply_defaultfile_parameters()
|
||||
|
||||
self.progress("Ready to start testing!")
|
||||
|
|
|
@ -61,7 +61,6 @@ class AutoTestCopter(AutoTest):
|
|||
self.log_name = "ArduCopter"
|
||||
|
||||
self.sitl = None
|
||||
self.hasInit = False
|
||||
|
||||
def mavproxy_options(self):
|
||||
ret = super(AutoTestCopter, self).mavproxy_options()
|
||||
|
@ -113,7 +112,6 @@ class AutoTestCopter(AutoTest):
|
|||
|
||||
self.progress("Started simulator")
|
||||
|
||||
self.hasInit = True
|
||||
self.progress("Ready to start testing!")
|
||||
|
||||
def close(self):
|
||||
|
|
|
@ -50,7 +50,6 @@ class AutoTestPlane(AutoTest):
|
|||
self.speedup = speedup
|
||||
|
||||
self.sitl = None
|
||||
self.hasInit = False
|
||||
|
||||
self.log_name = "ArduPlane"
|
||||
|
||||
|
@ -90,7 +89,6 @@ class AutoTestPlane(AutoTest):
|
|||
|
||||
self.get_mavlink_connection_going()
|
||||
|
||||
self.hasInit = True
|
||||
self.progress("Ready to start testing!")
|
||||
|
||||
def is_plane(self):
|
||||
|
|
|
@ -45,7 +45,6 @@ class AutoTestSub(AutoTest):
|
|||
self.speedup = speedup
|
||||
|
||||
self.sitl = None
|
||||
self.hasInit = False
|
||||
|
||||
self.log_name = "ArduSub"
|
||||
|
||||
|
@ -86,8 +85,6 @@ class AutoTestSub(AutoTest):
|
|||
|
||||
self.get_mavlink_connection_going()
|
||||
|
||||
self.hasInit = True
|
||||
|
||||
self.apply_defaultfile_parameters()
|
||||
|
||||
# FIXME:
|
||||
|
|
|
@ -168,6 +168,7 @@ class AutoTest(ABC):
|
|||
self.last_wp_load = 0
|
||||
self.forced_post_test_sitl_reboots = 0
|
||||
self.skip_list = []
|
||||
self.run_tests_called = False
|
||||
|
||||
@staticmethod
|
||||
def progress(text):
|
||||
|
@ -2040,8 +2041,11 @@ switch value'''
|
|||
def run_tests(self, tests):
|
||||
"""Autotest vehicle in SITL."""
|
||||
self.check_test_syntax(test_file=os.path.realpath(__file__))
|
||||
if not self.hasInit:
|
||||
self.init()
|
||||
if self.run_tests_called:
|
||||
raise ValueError("run_tests called twice")
|
||||
self.run_tests_called = True
|
||||
|
||||
self.init()
|
||||
|
||||
self.fail_list = []
|
||||
|
||||
|
|
|
@ -48,7 +48,6 @@ class AutoTestQuadPlane(AutoTest):
|
|||
self.logfile = None
|
||||
|
||||
self.sitl = None
|
||||
self.hasInit = False
|
||||
|
||||
def init(self):
|
||||
if self.frame is None:
|
||||
|
@ -86,7 +85,6 @@ class AutoTestQuadPlane(AutoTest):
|
|||
|
||||
self.get_mavlink_connection_going()
|
||||
|
||||
self.hasInit = True
|
||||
self.progress("Ready to start testing!")
|
||||
|
||||
def is_plane(self):
|
||||
|
|
Loading…
Reference in New Issue