From ad06a616b896c94ad6b52258ccf2c5de4e443e2f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 18 Feb 2021 11:24:20 +1100 Subject: [PATCH] autotest: adjust for low log transfer rate under valgrind --- Tools/autotest/common.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 1b3674a447..0c8255d16e 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -6568,8 +6568,11 @@ Also, ignores heartbeats not from our target system''' self.mavproxy.expect(r"Active Rate\([0-9]+s\):([0-9]+[.][0-9]+)") rate = float(self.mavproxy.match.group(1)) self.progress("Rate: %f" % rate) - if rate < 50: - raise NotAchievedException("Exceptionally low transfer rate") + desired_rate = 50 + if self.valgrind: + desired_rate /= 10 + if rate < desired_rate: + raise NotAchievedException("Exceptionally low transfer rate (%u < %u)" % (rate, desired_rate)) self.disarm_vehicle() except Exception as e: self.progress("Exception caught: %s" %