From 04aed495726b7f01da4ca9b79fa5e329fe80bb4d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 7 May 2021 09:05:01 +1000 Subject: [PATCH] autotest: adjust GyroFFT threshold to make it pass From Andy: Can you make this 0. The test should then pass. I'm not terribly happy about it but its better than disabling the test and I can't tell whether there is actually a problem or not. --- Tools/autotest/arducopter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index af6dc614f9..780f0f131a 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -4731,7 +4731,7 @@ class AutoTestCopter(AutoTest): smaxhz = int(350 * scale) freq = psd["F"][numpy.argmax(psd["X"][sminhz:smaxhz]) + sminhz] peakdb = numpy.amax(psd["X"][sminhz:smaxhz]) - if peakdb < -9: + if peakdb < 0: self.progress("Did not detect a motor peak, found %fHz at %fdB" % (freq, peakdb)) else: raise NotAchievedException("Detected %fHz motor peak at %fdB" % (freq, peakdb))