From 91b2d0dcdfd16d9f4a319402452282cc35cc9c5b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 8 Jul 2024 18:54:09 +1000 Subject: [PATCH] autotest: fix race condition in DataFlashOverMAVLink test we're running at large speedups; 5 simulated seconds might not be enough time for MAVProxy to accumulate statistics. So get MAVProxy to emit the rate each second instead --- Tools/autotest/vehicle_test_suite.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 03ebd0fa7a..64773a9500 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -9991,13 +9991,13 @@ Also, ignores heartbeats not from our target system''' self.arm_vehicle() tstart = self.get_sim_time() last_status = 0 + mavproxy.send('repeat add 1 dataflash_logger status\n') while True: now = self.get_sim_time() if now - tstart > 60: break if now - last_status > 5: last_status = now - mavproxy.send('dataflash_logger status\n') # seen on autotest: Active Rate(3s):97.790kB/s Block:164 Missing:0 Fixed:0 Abandoned:0 mavproxy.expect(r"Active Rate\([0-9]+s\):([0-9]+[.][0-9]+)") rate = float(mavproxy.match.group(1)) @@ -10008,6 +10008,7 @@ Also, ignores heartbeats not from our target system''' if rate < desired_rate: raise NotAchievedException("Exceptionally low transfer rate (%u < %u)" % (rate, desired_rate)) self.disarm_vehicle() + mavproxy.send('repeat remove 0\n') except Exception as e: self.print_exception_caught(e) self.disarm_vehicle()