diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index c40f04225b..8556d27df7 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -4197,8 +4197,12 @@ class AutoTest(ABC): # the autopilot at 20Hz - that's our 50Hz wallclock, , not # the autopilot's simulated 20Hz, so if speedup is 10 the # autopilot will see ~2Hz. + timeout = 0.02 + # ... and 2Hz is too slow when we now run at 100x speedup: + timeout /= (self.speedup / 10.0) + try: - map_copy = self.rc_queue.get(timeout=0.02) + map_copy = self.rc_queue.get(timeout=timeout) # 16 packed entries: for i in range(1, 17):