From a00b5cb770394b25cc34573817ecd828757c82cf Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 18 Jul 2020 09:11:44 +0100 Subject: [PATCH] autotest: db's are negative so check dynamic notches the right way --- Tools/autotest/arducopter.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 66beb3cc3d..a47e402356 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -3881,8 +3881,8 @@ class AutoTestCopter(AutoTest): freq, vfr_hud, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) # double-notch should do better, but check for within 5% - if peakdb2 > peakdb1 * 1.05: - raise NotAchievedException("Double-notch peak was higher than single-notch peak %fdB < %fdB" % (peakdb2, peakdb1)) + if peakdb2 * 1.05 > peakdb1: + raise NotAchievedException("Double-notch peak was higher than single-notch peak %fdB > %fdB" % (peakdb2, peakdb1)) except Exception as e: self.progress("Exception caught in %s loop: %s" % (loop, self.get_exception_stacktrace(e)))