mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
autotest: scale SITL RC input according to speedup
Too slow when running at 100 times speedup
This commit is contained in:
parent
abc1b7b644
commit
b550949766
@ -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):
|
||||
|
Loading…
Reference in New Issue
Block a user