mirror of https://github.com/ArduPilot/ardupilot
Tools: autotest: increase timeout waiting for MISSION_COUNT
This commit is contained in:
parent
1ef6204c1d
commit
f896af6800
|
@ -2168,7 +2168,7 @@ class AutoTest(ABC):
|
|||
while True:
|
||||
m = self.mav.recv_match(type='MISSION_COUNT',
|
||||
blocking=True,
|
||||
timeout=1)
|
||||
timeout=5)
|
||||
self.progress(str(m))
|
||||
if m is None:
|
||||
raise NotAchievedException("Did not get MISSION_COUNT response")
|
||||
|
|
Loading…
Reference in New Issue