mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
autotest: remove pointless manipulation of expect list
start_sitl and start_mavproxy already do this stuff
This commit is contained in:
parent
dcc04ccd09
commit
2d17f019b6
@ -5440,6 +5440,7 @@ Also, ignores heartbeats not from our target system'''
|
||||
|
||||
# self.progress("Waiting for Parameters")
|
||||
# self.mavproxy.expect('Received [0-9]+ parameters')
|
||||
self.expect_list_add(self.mavproxy)
|
||||
|
||||
def start_SITL(self, **sitl_args):
|
||||
start_sitl_args = {
|
||||
@ -5498,12 +5499,6 @@ Also, ignores heartbeats not from our target system'''
|
||||
|
||||
util.expect_setup_callback(self.mavproxy, self.expect_callback)
|
||||
|
||||
self.expect_list_clear()
|
||||
if self.sup_prog is not None:
|
||||
self.expect_list_extend([self.sitl, self.mavproxy])
|
||||
else:
|
||||
self.expect_list_extend([self.sitl, self.mavproxy, self.sup_prog])
|
||||
|
||||
# need to wait for a heartbeat to arrive as then mavutil will
|
||||
# select the correct set of messages for us to receive in
|
||||
# self.mav.messages. You can actually recieve messages with
|
||||
|
Loading…
Reference in New Issue
Block a user