From f9c86bbfd0cd40d17046354c7fe80a5455f61f97 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 19 May 2020 13:12:46 +1000 Subject: [PATCH] autotest: ensure cached timestamp is up-to-date for run_cmd_get_ack If a long-running process drains the mavlink stream rather than parsing it then the cached timestamp can be very, very out-of-date. When we next receieve a timestamp, then, there can be a signficant change in time when we weren't expecting it. run_cmd_get_ack can't use get_sim_time() as it might swallow the ack it is looking for. --- Tools/autotest/common.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 0a87e14c8d..a072d54b3d 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -2577,6 +2577,8 @@ class AutoTest(ABC): if target_compid is None: target_compid = 1 + self.get_sim_time() # required for timeout in run_cmd_get_ack to work + """Send a MAVLink command int.""" self.mav.mav.command_int_send(target_sysid, target_compid, @@ -2652,6 +2654,7 @@ class AutoTest(ABC): target_compid=None, timeout=10, quiet=False): + self.get_sim_time() # required for timeout in run_cmd_get_ack to work self.send_cmd(command, p1, p2, @@ -2666,6 +2669,8 @@ class AutoTest(ABC): self.run_cmd_get_ack(command, want_result, timeout, quiet=quiet) def run_cmd_get_ack(self, command, want_result, timeout, quiet=False): + # note that the caller should ensure that this cached + # timestamp is reasonably up-to-date! tstart = self.get_sim_time_cached() while True: delta_time = self.get_sim_time_cached() - tstart