mirror of https://github.com/ArduPilot/ardupilot
autotest: remove retry loop from within GyroFFT
This effectively removes an infinite loop from the GyroFFT test.
This commit is contained in:
parent
765889b827
commit
0a235ce094
|
@ -4624,141 +4624,147 @@ class AutoTestCopter(AutoTest):
|
|||
self.context_push()
|
||||
|
||||
ex = None
|
||||
# we are dealing with probabalistic scenarios involving threads, have two bites at the cherry
|
||||
for loop in ["first" "second"]:
|
||||
try:
|
||||
self.set_rc_default()
|
||||
# magic tridge EKF type that dramatically speeds up the test
|
||||
self.set_parameter("AHRS_EKF_TYPE", 10)
|
||||
self.set_parameter("EK2_ENABLE", 0)
|
||||
self.set_parameter("EK3_ENABLE", 0)
|
||||
self.set_parameter("INS_LOG_BAT_MASK", 3)
|
||||
self.set_parameter("INS_LOG_BAT_OPT", 0)
|
||||
self.set_parameter("INS_GYRO_FILTER", 100)
|
||||
self.set_parameter("INS_FAST_SAMPLE", 0)
|
||||
self.set_parameter("LOG_BITMASK", 958)
|
||||
self.set_parameter("LOG_DISARMED", 0)
|
||||
self.set_parameter("SIM_DRIFT_SPEED", 0)
|
||||
self.set_parameter("SIM_DRIFT_TIME", 0)
|
||||
# enable a noisy motor peak
|
||||
self.set_parameter("SIM_GYR1_RND", 20)
|
||||
# enabling FFT will also enable the arming check, self-testing the functionality
|
||||
self.set_parameter("FFT_ENABLE", 1)
|
||||
self.set_parameter("FFT_MINHZ", 50)
|
||||
self.set_parameter("FFT_MAXHZ", 450)
|
||||
self.set_parameter("FFT_SNR_REF", 10)
|
||||
self.set_parameter("FFT_WINDOW_SIZE", 128)
|
||||
self.set_parameter("FFT_WINDOW_OLAP", 0.75)
|
||||
self.set_parameter("FFT_SAMPLE_MODE", 0)
|
||||
try:
|
||||
# magic tridge EKF type that dramatically speeds up the test
|
||||
self.set_parameters({
|
||||
"AHRS_EKF_TYPE": 10,
|
||||
"EK2_ENABLE": 0,
|
||||
"EK3_ENABLE": 0,
|
||||
"INS_LOG_BAT_MASK": 3,
|
||||
"INS_LOG_BAT_OPT": 0,
|
||||
"INS_GYRO_FILTER": 100,
|
||||
"INS_FAST_SAMPLE": 0,
|
||||
"LOG_BITMASK": 958,
|
||||
"LOG_DISARMED": 0,
|
||||
"SIM_DRIFT_SPEED": 0,
|
||||
"SIM_DRIFT_TIME": 0,
|
||||
"SIM_GYR1_RND": 20, # enable a noisy motor peak
|
||||
})
|
||||
# enabling FFT will also enable the arming check,
|
||||
# self-testing the functionality
|
||||
self.set_parameters({
|
||||
"FFT_ENABLE": 1,
|
||||
"FFT_MINHZ": 50,
|
||||
"FFT_MAXHZ": 450,
|
||||
"FFT_SNR_REF": 10,
|
||||
"FFT_WINDOW_SIZE": 128,
|
||||
"FFT_WINDOW_OLAP": 0.75,
|
||||
"FFT_SAMPLE_MODE": 0,
|
||||
})
|
||||
|
||||
# Step 1: inject a very precise noise peak at 250hz and make sure the in-flight fft
|
||||
# can detect it really accurately. For a 128 FFT the frequency resolution is 8Hz so
|
||||
# a 250Hz peak should be detectable within 5%
|
||||
self.start_subtest("Inject noise at 250Hz and check the FFT can find the noise")
|
||||
self.set_parameter("SIM_VIB_FREQ_X", 250)
|
||||
self.set_parameter("SIM_VIB_FREQ_Y", 250)
|
||||
self.set_parameter("SIM_VIB_FREQ_Z", 250)
|
||||
# Step 1: inject a very precise noise peak at 250hz and make sure the in-flight fft
|
||||
# can detect it really accurately. For a 128 FFT the frequency resolution is 8Hz so
|
||||
# a 250Hz peak should be detectable within 5%
|
||||
self.start_subtest("Inject noise at 250Hz and check the FFT can find the noise")
|
||||
self.set_parameters({
|
||||
"SIM_VIB_FREQ_X": 250,
|
||||
"SIM_VIB_FREQ_Y": 250,
|
||||
"SIM_VIB_FREQ_Z": 250,
|
||||
})
|
||||
|
||||
self.reboot_sitl()
|
||||
self.reboot_sitl()
|
||||
|
||||
# find a motor peak
|
||||
self.hover_and_check_matched_frequency(-15, 100, 350, 128, 250)
|
||||
# find a motor peak
|
||||
self.hover_and_check_matched_frequency(-15, 100, 350, 128, 250)
|
||||
|
||||
# Step 1b: run the same test with an FFT length of 256 which is needed to flush out a
|
||||
# whole host of bugs related to uint8_t. This also tests very accurately the frequency resolution
|
||||
self.set_parameter("FFT_WINDOW_SIZE", 256)
|
||||
self.start_subtest("Inject noise at 250Hz and check the FFT can find the noise")
|
||||
# Step 1b: run the same test with an FFT length of 256 which is needed to flush out a
|
||||
# whole host of bugs related to uint8_t. This also tests very accurately the frequency resolution
|
||||
self.set_parameter("FFT_WINDOW_SIZE", 256)
|
||||
self.start_subtest("Inject noise at 250Hz and check the FFT can find the noise")
|
||||
|
||||
self.reboot_sitl()
|
||||
self.reboot_sitl()
|
||||
|
||||
# find a motor peak
|
||||
self.hover_and_check_matched_frequency(-15, 100, 350, 256, 250)
|
||||
self.set_parameter("FFT_WINDOW_SIZE", 128)
|
||||
# find a motor peak
|
||||
self.hover_and_check_matched_frequency(-15, 100, 350, 256, 250)
|
||||
self.set_parameter("FFT_WINDOW_SIZE", 128)
|
||||
|
||||
# Step 2: inject actual motor noise and use the standard length FFT to track it
|
||||
self.start_subtest("Hover and check that the FFT can find the motor noise")
|
||||
self.set_parameter("SIM_VIB_FREQ_X", 0)
|
||||
self.set_parameter("SIM_VIB_FREQ_Y", 0)
|
||||
self.set_parameter("SIM_VIB_FREQ_Z", 0)
|
||||
self.set_parameter("SIM_VIB_MOT_MAX", 250) # gives a motor peak at about 175Hz
|
||||
self.set_parameter("FFT_WINDOW_SIZE", 32)
|
||||
self.set_parameter("FFT_WINDOW_OLAP", 0.5)
|
||||
# Step 2: inject actual motor noise and use the standard length FFT to track it
|
||||
self.start_subtest("Hover and check that the FFT can find the motor noise")
|
||||
self.set_parameters({
|
||||
"SIM_VIB_FREQ_X": 0,
|
||||
"SIM_VIB_FREQ_Y": 0,
|
||||
"SIM_VIB_FREQ_Z": 0,
|
||||
"SIM_VIB_MOT_MAX": 250, # gives a motor peak at about 175Hz
|
||||
"FFT_WINDOW_SIZE": 32,
|
||||
"FFT_WINDOW_OLAP": 0.5,
|
||||
})
|
||||
|
||||
self.reboot_sitl()
|
||||
freq = self.hover_and_check_matched_frequency(-15, 100, 250, 32)
|
||||
self.reboot_sitl()
|
||||
freq = self.hover_and_check_matched_frequency(-15, 100, 250, 32)
|
||||
|
||||
self.set_parameter("SIM_VIB_MOT_MULT", 1.)
|
||||
self.set_parameter("SIM_VIB_MOT_MULT", 1.)
|
||||
|
||||
# Step 3: add a FFT dynamic notch and check that the peak is squashed
|
||||
self.start_subtest("Add a dynamic notch, hover and check that the noise peak is now gone")
|
||||
self.set_parameter("INS_LOG_BAT_OPT", 2)
|
||||
self.set_parameter("INS_HNTCH_ENABLE", 1)
|
||||
self.set_parameter("INS_HNTCH_FREQ", freq)
|
||||
self.set_parameter("INS_HNTCH_REF", 1.0)
|
||||
self.set_parameter("INS_HNTCH_ATT", 50)
|
||||
self.set_parameter("INS_HNTCH_BW", freq/2)
|
||||
self.set_parameter("INS_HNTCH_MODE", 4)
|
||||
self.reboot_sitl()
|
||||
# Step 3: add a FFT dynamic notch and check that the peak is squashed
|
||||
self.start_subtest("Add a dynamic notch, hover and check that the noise peak is now gone")
|
||||
self.set_parameters({
|
||||
"INS_LOG_BAT_OPT": 2,
|
||||
"INS_HNTCH_ENABLE": 1,
|
||||
"INS_HNTCH_FREQ": freq,
|
||||
"INS_HNTCH_REF": 1.0,
|
||||
"INS_HNTCH_ATT": 50,
|
||||
"INS_HNTCH_BW": freq/2,
|
||||
"INS_HNTCH_MODE": 4,
|
||||
})
|
||||
self.reboot_sitl()
|
||||
|
||||
self.takeoff(10, mode="ALT_HOLD")
|
||||
hover_time = 15
|
||||
self.progress("Hovering for %u seconds" % hover_time)
|
||||
tstart = self.get_sim_time()
|
||||
while self.get_sim_time_cached() < tstart + hover_time:
|
||||
self.mav.recv_match(type='ATTITUDE', blocking=True)
|
||||
tend = self.get_sim_time()
|
||||
self.takeoff(10, mode="ALT_HOLD")
|
||||
hover_time = 15
|
||||
self.progress("Hovering for %u seconds" % hover_time)
|
||||
tstart = self.get_sim_time()
|
||||
while self.get_sim_time_cached() < tstart + hover_time:
|
||||
self.mav.recv_match(type='ATTITUDE', blocking=True)
|
||||
tend = self.get_sim_time()
|
||||
|
||||
# fly fast forrest!
|
||||
self.set_rc(3, 1900)
|
||||
self.set_rc(2, 1200)
|
||||
self.wait_groundspeed(5, 1000)
|
||||
self.set_rc(3, 1500)
|
||||
self.set_rc(2, 1500)
|
||||
# fly fast forrest!
|
||||
self.set_rc(3, 1900)
|
||||
self.set_rc(2, 1200)
|
||||
self.wait_groundspeed(5, 1000)
|
||||
self.set_rc(3, 1500)
|
||||
self.set_rc(2, 1500)
|
||||
|
||||
self.do_RTL()
|
||||
psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6)
|
||||
self.do_RTL()
|
||||
psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6)
|
||||
|
||||
# batch sampler defaults give 1024 fft and sample rate of 1kz so roughly 1hz/bin
|
||||
scale = 1000. / 1024.
|
||||
sminhz = int(100 * scale)
|
||||
smaxhz = int(350 * scale)
|
||||
freq = psd["F"][numpy.argmax(psd["X"][sminhz:smaxhz]) + sminhz]
|
||||
peakdb = numpy.amax(psd["X"][sminhz:smaxhz])
|
||||
if peakdb < -9:
|
||||
self.progress("Did not detect a motor peak, found %fHz at %fdB" % (freq, peakdb))
|
||||
else:
|
||||
raise NotAchievedException("Detected %fHz motor peak at %fdB" % (freq, peakdb))
|
||||
# batch sampler defaults give 1024 fft and sample rate of 1kz so roughly 1hz/bin
|
||||
scale = 1000. / 1024.
|
||||
sminhz = int(100 * scale)
|
||||
smaxhz = int(350 * scale)
|
||||
freq = psd["F"][numpy.argmax(psd["X"][sminhz:smaxhz]) + sminhz]
|
||||
peakdb = numpy.amax(psd["X"][sminhz:smaxhz])
|
||||
if peakdb < -9:
|
||||
self.progress("Did not detect a motor peak, found %fHz at %fdB" % (freq, peakdb))
|
||||
else:
|
||||
raise NotAchievedException("Detected %fHz motor peak at %fdB" % (freq, peakdb))
|
||||
|
||||
# Step 4: loop sample rate test with larger window
|
||||
self.start_subtest("Hover and check that the FFT can find the motor noise when running at fast loop rate")
|
||||
# we are limited to half the loop rate for frequency detection
|
||||
self.set_parameter("FFT_MAXHZ", 185)
|
||||
self.set_parameter("INS_LOG_BAT_OPT", 0)
|
||||
self.set_parameter("SIM_VIB_MOT_MAX", 220)
|
||||
self.set_parameter("FFT_WINDOW_SIZE", 64)
|
||||
self.set_parameter("FFT_WINDOW_OLAP", 0.75)
|
||||
self.set_parameter("FFT_SAMPLE_MODE", 1)
|
||||
self.reboot_sitl()
|
||||
# Step 4: loop sample rate test with larger window
|
||||
self.start_subtest("Hover and check that the FFT can find the motor noise when running at fast loop rate")
|
||||
# we are limited to half the loop rate for frequency detection
|
||||
self.set_parameters({
|
||||
"FFT_MAXHZ": 185,
|
||||
"INS_LOG_BAT_OPT": 0,
|
||||
"SIM_VIB_MOT_MAX": 220,
|
||||
"FFT_WINDOW_SIZE": 64,
|
||||
"FFT_WINDOW_OLAP": 0.75,
|
||||
"FFT_SAMPLE_MODE": 1,
|
||||
})
|
||||
self.reboot_sitl()
|
||||
|
||||
self.takeoff(10, mode="ALT_HOLD")
|
||||
self.takeoff(10, mode="ALT_HOLD")
|
||||
|
||||
self.progress("Hovering for %u seconds" % hover_time)
|
||||
tstart = self.get_sim_time()
|
||||
while self.get_sim_time_cached() < tstart + hover_time:
|
||||
self.mav.recv_match(type='ATTITUDE', blocking=True)
|
||||
tend = self.get_sim_time()
|
||||
self.progress("Hovering for %u seconds" % hover_time)
|
||||
tstart = self.get_sim_time()
|
||||
while self.get_sim_time_cached() < tstart + hover_time:
|
||||
self.mav.recv_match(type='ATTITUDE', blocking=True)
|
||||
tend = self.get_sim_time()
|
||||
|
||||
self.do_RTL()
|
||||
# prevent update parameters from messing with the settings when we pop the context
|
||||
self.set_parameter("FFT_ENABLE", 0)
|
||||
self.reboot_sitl()
|
||||
self.do_RTL()
|
||||
# prevent update parameters from messing with the settings when we pop the context
|
||||
self.set_parameter("FFT_ENABLE", 0)
|
||||
self.reboot_sitl()
|
||||
|
||||
except Exception as e:
|
||||
self.progress("Exception caught in %s loop" % (loop, ))
|
||||
if loop != "second":
|
||||
continue
|
||||
ex = e
|
||||
break
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
|
||||
self.context_pop()
|
||||
|
||||
|
@ -6951,7 +6957,7 @@ class AutoTestCopter(AutoTest):
|
|||
Test("GyroFFT",
|
||||
"Fly Gyro FFT",
|
||||
self.fly_gyro_fft,
|
||||
attempts=4),
|
||||
attempts=8),
|
||||
|
||||
Test("GyroFFTHarmonic",
|
||||
"Fly Gyro FFT Harmonic Matching",
|
||||
|
|
Loading…
Reference in New Issue