mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
autotest: db's are negative so check dynamic notches the right way
This commit is contained in:
parent
c8f1b44ee6
commit
a00b5cb770
@ -3881,8 +3881,8 @@ class AutoTestCopter(AutoTest):
|
|||||||
freq, vfr_hud, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True)
|
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%
|
# double-notch should do better, but check for within 5%
|
||||||
if peakdb2 > peakdb1 * 1.05:
|
if peakdb2 * 1.05 > peakdb1:
|
||||||
raise NotAchievedException("Double-notch peak was higher than single-notch peak %fdB < %fdB" % (peakdb2, peakdb1))
|
raise NotAchievedException("Double-notch peak was higher than single-notch peak %fdB > %fdB" % (peakdb2, peakdb1))
|
||||||
|
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
self.progress("Exception caught in %s loop: %s" % (loop, self.get_exception_stacktrace(e)))
|
self.progress("Exception caught in %s loop: %s" % (loop, self.get_exception_stacktrace(e)))
|
||||||
|
Loading…
Reference in New Issue
Block a user