Browse Source

autotest: remove retry loop from within fly_dynamic_notches

We retried externally to the test - may as well do so within
c415-sdk
Peter Barker 4 years ago committed by Peter Barker
parent
commit
4928ec18af
  1. 85
      Tools/autotest/arducopter.py

85
Tools/autotest/arducopter.py

@ -4356,58 +4356,53 @@ class AutoTestCopter(AutoTest):
self.context_push() self.context_push()
ex = None ex = None
# we are dealing with probabalistic scenarios involving threads, have two bites at the cherry try:
for loop in ["first", "second"]: self.set_parameters({
try: "AHRS_EKF_TYPE": 10,
self.set_rc_default() "INS_LOG_BAT_MASK": 3,
self.set_parameter("AHRS_EKF_TYPE", 10) "INS_LOG_BAT_OPT": 0,
self.set_parameter("INS_LOG_BAT_MASK", 3) "INS_GYRO_FILTER": 100, # set the gyro filter high so we can observe behaviour
self.set_parameter("INS_LOG_BAT_OPT", 0) "LOG_BITMASK": 958,
# set the gyro filter high so we can observe behaviour "LOG_DISARMED": 0,
self.set_parameter("INS_GYRO_FILTER", 100) "SIM_VIB_MOT_MAX": 350,
self.set_parameter("LOG_BITMASK", 958) "SIM_GYR1_RND": 20,
self.set_parameter("LOG_DISARMED", 0) })
self.set_parameter("SIM_VIB_MOT_MAX", 350) self.reboot_sitl()
self.set_parameter("SIM_GYR1_RND", 20)
self.reboot_sitl()
self.takeoff(10, mode="ALT_HOLD") self.takeoff(10, mode="ALT_HOLD")
# find a motor peak # find a motor peak
freq, vfr_hud, peakdb = self.hover_and_check_matched_frequency_with_fft(-15, 200, 300) freq, vfr_hud, peakdb = self.hover_and_check_matched_frequency_with_fft(-15, 200, 300)
# now add a dynamic notch and check that the peak is squashed # now add a dynamic notch and check that the peak is squashed
self.set_parameter("INS_LOG_BAT_OPT", 2) self.set_parameters({
self.set_parameter("INS_HNTCH_ENABLE", 1) "INS_LOG_BAT_OPT": 2,
self.set_parameter("INS_HNTCH_FREQ", freq) "INS_HNTCH_ENABLE": 1,
self.set_parameter("INS_HNTCH_REF", vfr_hud.throttle/100.) "INS_HNTCH_FREQ": freq,
# first and third harmonic "INS_HNTCH_REF": vfr_hud.throttle/100.,
self.set_parameter("INS_HNTCH_HMNCS", 5) "INS_HNTCH_HMNCS": 5, # first and third harmonic
self.set_parameter("INS_HNTCH_ATT", 50) "INS_HNTCH_ATT": 50,
self.set_parameter("INS_HNTCH_BW", freq/2) "INS_HNTCH_BW": freq/2,
self.reboot_sitl() })
self.reboot_sitl()
freq, vfr_hud, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) freq, vfr_hud, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True)
# now add double dynamic notches and check that the peak is squashed # now add double dynamic notches and check that the peak is squashed
self.set_parameter("INS_HNTCH_OPTS", 1) self.set_parameter("INS_HNTCH_OPTS", 1)
self.reboot_sitl() self.reboot_sitl()
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 * 1.05 > peakdb1: if peakdb2 * 1.05 > peakdb1:
raise NotAchievedException( raise NotAchievedException(
"Double-notch peak was higher than single-notch peak %fdB > %fdB" % "Double-notch peak was higher than single-notch peak %fdB > %fdB" %
(peakdb2, peakdb1)) (peakdb2, peakdb1))
except Exception as e: except Exception as e:
self.print_exception_caught(e) self.print_exception_caught(e)
self.progress("Exception caught in %s loop" % (loop,)) ex = e
if loop != "second":
continue
ex = e
break
self.context_pop() self.context_pop()
@ -6948,7 +6943,7 @@ class AutoTestCopter(AutoTest):
Test("DynamicNotches", Test("DynamicNotches",
"Fly Dynamic Notches", "Fly Dynamic Notches",
self.fly_dynamic_notches, self.fly_dynamic_notches,
attempts=4), attempts=8),
Test("PositionWhenGPSIsZero", Test("PositionWhenGPSIsZero",
"Ensure position doesn't zero when GPS lost", "Ensure position doesn't zero when GPS lost",

Loading…
Cancel
Save