diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 8b9524d355..28daeab809 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -2102,7 +2102,7 @@ class AutoTestCopter(AutoTest): # ignore the first 20Hz and look for a peak at -15dB or more ignore_bins = 20 freq = psd["F"][numpy.argmax(psd["X"][ignore_bins:]) + ignore_bins] - if numpy.amax(psd["X"][ignore_bins:]) < -15 or freq < 200 or freq > 300: + if numpy.amax(psd["X"][ignore_bins:]) < -15 or freq < 180 or freq > 300: raise NotAchievedException("Did not detect a motor peak, found %f at %f dB" % (freq, numpy.amax(psd["X"][ignore_bins:]))) else: self.progress("Detected motor peak at %fHz" % freq) @@ -2125,10 +2125,11 @@ class AutoTestCopter(AutoTest): self.do_RTL() psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6) freq = psd["F"][numpy.argmax(psd["X"][ignore_bins:]) + ignore_bins] - if numpy.amax(psd["X"][ignore_bins:]) < -30: - self.progress("Did not detect a motor peak, found %f at %f dB" % (freq, numpy.amax(psd["X"][ignore_bins:]))) + peakdB = numpy.amax(psd["X"][ignore_bins:]) + if peakdB < -23: + self.progress("Did not detect a motor peak, found %f at %f dB" % (freq, peakdB)) else: - raise NotAchievedException("Detected motor peak at %f Hz" % (freq)) + raise NotAchievedException("Detected peak %.1f Hz %.2f dB" % (freq, peakdB)) except Exception as e: ex = e