mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Tools: autotest: get mavproxy to heartbeat at speedup rate
This should resolve a race condition we have with guided position modes. MAVProxy's heartbeat rate defaults to 1Hz. When GCS failsafe is active on Copter because we're in GUIDED (or GUIDED_NOGPS mode) we require a heartbeat every 5 seconds. At speedup 8, we can only expect a heartbeat every 8 seconds of sim time. We also only check for this heartbeat every 3 seconds - leading to this awesome race condition.
This commit is contained in:
parent
87e43d6e44
commit
bd50f288a1
@ -249,7 +249,8 @@ class AutoTest(ABC):
|
|||||||
"""Returns options to be passed to MAVProxy."""
|
"""Returns options to be passed to MAVProxy."""
|
||||||
ret = ['--sitl=127.0.0.1:5501',
|
ret = ['--sitl=127.0.0.1:5501',
|
||||||
'--out=' + self.autotest_connection_string_from_mavproxy(),
|
'--out=' + self.autotest_connection_string_from_mavproxy(),
|
||||||
'--streamrate=%u' % self.sitl_streamrate()]
|
'--streamrate=%u' % self.sitl_streamrate(),
|
||||||
|
'--cmd="set heartbeat %u"' % self.speedup]
|
||||||
if self.viewerip:
|
if self.viewerip:
|
||||||
ret.append("--out=%s:14550" % self.viewerip)
|
ret.append("--out=%s:14550" % self.viewerip)
|
||||||
if self.use_map:
|
if self.use_map:
|
||||||
|
Loading…
Reference in New Issue
Block a user