Browse Source

autotest: disable mavutil autoreconnect in drain_mav

The process may not be available
apm_2208
Peter Barker 3 years ago committed by Peter Barker
parent
commit
271b4d7d3c
  1. 13
      Tools/autotest/common.py

13
Tools/autotest/common.py

@ -2749,7 +2749,17 @@ class AutoTest(ABC): @@ -2749,7 +2749,17 @@ class AutoTest(ABC):
timeout = 120
failed_to_drain = False
self.pause_SITL()
while mav.recv_msg() is not None:
# sometimes we recv() when the process is likely to go away..
old_autoreconnect = mav.autoreconnect
mav.autoreconnect = False
while True:
try:
receive_result = mav.recv_msg()
except Exception:
mav.autoreconnect = True
raise
if receive_result is None:
break
count += 1
if time.time() - tstart > timeout:
# ArduPilot can produce messages faster than we can
@ -2757,6 +2767,7 @@ class AutoTest(ABC): @@ -2757,6 +2767,7 @@ class AutoTest(ABC):
# just die if that seems to be the case:
failed_to_drain = True
quiet = False
mav.autoreconnect = old_autoreconnect
self.unpause_SITL()
if quiet:
self.in_drain_mav = False

Loading…
Cancel
Save