mirror of https://github.com/ArduPilot/ardupilot
autotest: improve reliability of MotorVibration test
This commit is contained in:
parent
95c06d418e
commit
946c891e14
|
@ -3178,9 +3178,10 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
|
||||
psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6)
|
||||
# ignore the first 20Hz and look for a peak at -15dB or more
|
||||
ignore_bins = 20
|
||||
# it should be at about 190Hz, each bin is 1000/1024Hz wide
|
||||
ignore_bins = int(100 * 1.024) # start at 100Hz to be safe
|
||||
freq = psd["F"][numpy.argmax(psd["X"][ignore_bins:]) + ignore_bins]
|
||||
if numpy.amax(psd["X"][ignore_bins:]) < -15 or freq < 180 or freq > 300:
|
||||
if numpy.amax(psd["X"][ignore_bins:]) < -15 or freq < 100 or freq > 300:
|
||||
raise NotAchievedException(
|
||||
"Did not detect a motor peak, found %f at %f dB" %
|
||||
(freq, numpy.amax(psd["X"][ignore_bins:])))
|
||||
|
@ -11308,7 +11309,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.MotorVibration,
|
||||
Test(self.DynamicNotches, attempts=4),
|
||||
self.PositionWhenGPSIsZero,
|
||||
self.DynamicRpmNotches,
|
||||
self.DynamicRpmNotches, # Do not add attempts to this - failure is sign of a bug
|
||||
self.PIDNotches,
|
||||
self.RefindGPS,
|
||||
Test(self.GyroFFT, attempts=1, speedup=8),
|
||||
|
|
|
@ -14208,6 +14208,8 @@ SERIAL5_BAUD 128
|
|||
sample_rate = 0
|
||||
counts = 0
|
||||
window = numpy.hanning(fft_len)
|
||||
# The returned float array f contains the frequency bin centers in cycles per unit of the
|
||||
# sample spacing (with zero at the start).
|
||||
freqmap = numpy.fft.rfftfreq(fft_len, 1.0 / messages[0].sample_rate_hz)
|
||||
|
||||
# calculate NEBW constant
|
||||
|
|
Loading…
Reference in New Issue