From bd50f288a14f4bb2b74a4aa74e56982d0a220049 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jul 2019 11:54:06 +1000 Subject: [PATCH] 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. --- Tools/autotest/common.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 1ad646c4f2..fdf6e4ab81 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -249,7 +249,8 @@ class AutoTest(ABC): """Returns options to be passed to MAVProxy.""" ret = ['--sitl=127.0.0.1:5501', '--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: ret.append("--out=%s:14550" % self.viewerip) if self.use_map: