From 662e86780b0d19e3cc3f051451152e297f363c8f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 18 Jan 2021 15:45:41 +1100 Subject: [PATCH] autotest: reduce motor vibration for landing --- Tools/autotest/arducopter.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 3537dcad0b..c27c61c2f4 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -2144,6 +2144,9 @@ class AutoTestCopter(AutoTest): attitude = self.mav.recv_match(type='ATTITUDE', blocking=True) tend = self.get_sim_time() + # if we don't reduce vibes here then the landing detector + # may not trigger + self.set_parameter("SIM_VIB_MOT_MAX", 0) self.do_RTL() 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 @@ -2161,6 +2164,7 @@ class AutoTestCopter(AutoTest): "INS_NOTCH_FREQ": freq, "INS_NOTCH_ATT": 50, "INS_NOTCH_BW": freq/2, + "SIM_VIB_MOT_MAX": 350, }) self.reboot_sitl() @@ -2171,6 +2175,7 @@ class AutoTestCopter(AutoTest): while self.get_sim_time_cached() < tstart + hover_time: attitude = self.mav.recv_match(type='ATTITUDE', blocking=True) tend = self.get_sim_time() + self.set_parameter("SIM_VIB_MOT_MAX", 0) 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]