mirror of https://github.com/ArduPilot/ardupilot
autotest: limit frequency matching to resolution of the FFT
This commit is contained in:
parent
18ddfbdd6e
commit
94ff5d13c0
|
@ -239,7 +239,7 @@ class AutoTestQuadPlane(AutoTest):
|
|||
timeout=60)
|
||||
self.set_rc(3, 1500)
|
||||
|
||||
def hover_and_check_matched_frequency(self, dblevel=-15, minhz=200, maxhz=300, peakhz=None):
|
||||
def hover_and_check_matched_frequency(self, dblevel=-15, minhz=200, maxhz=300, fftLength=32, peakhz=None):
|
||||
|
||||
# find a motor peak
|
||||
self.takeoff(10, mode="QHOVER")
|
||||
|
@ -266,6 +266,8 @@ class AutoTestQuadPlane(AutoTest):
|
|||
# we have a peak make sure that the FFT detected something close
|
||||
# logging is at 10Hz
|
||||
mlog = self.dfreader_for_current_onboard_log()
|
||||
# accuracy is determined by sample rate and fft length, given our use of quinn we could probably use half of this
|
||||
freqDelta = 1000. / fftLength
|
||||
pkAvg = freq
|
||||
|
||||
while True:
|
||||
|
@ -276,8 +278,8 @@ class AutoTestQuadPlane(AutoTest):
|
|||
if m is None:
|
||||
break
|
||||
pkAvg = pkAvg + (0.1 * (m.PkAvg - pkAvg))
|
||||
# peak within 5%
|
||||
if abs(pkAvg - freq) / freq > 0.05:
|
||||
# peak within resolution of FFT length
|
||||
if abs(pkAvg - freq) > freqDelta:
|
||||
raise NotAchievedException("FFT did not detect a motor peak at %f, found %f, wanted %f" % (dblevel, pkAvg, freq))
|
||||
|
||||
return freq
|
||||
|
@ -321,7 +323,7 @@ class AutoTestQuadPlane(AutoTest):
|
|||
self.reboot_sitl()
|
||||
|
||||
# find a motor peak
|
||||
self.hover_and_check_matched_frequency(-15, 100, 350, 250)
|
||||
self.hover_and_check_matched_frequency(-15, 100, 350, 128, 250)
|
||||
|
||||
# Step 2: inject actual motor noise and use the standard length FFT to track it
|
||||
self.set_parameter("SIM_VIB_MOT_MAX", 350)
|
||||
|
@ -330,7 +332,7 @@ class AutoTestQuadPlane(AutoTest):
|
|||
|
||||
self.reboot_sitl()
|
||||
# find a motor peak
|
||||
freq = self.hover_and_check_matched_frequency(-15, 200, 300)
|
||||
freq = self.hover_and_check_matched_frequency(-15, 200, 300, 32)
|
||||
|
||||
# Step 3: add a FFT dynamic notch and check that the peak is squashed
|
||||
self.set_parameter("INS_LOG_BAT_OPT", 2)
|
||||
|
|
Loading…
Reference in New Issue