mirror of https://github.com/ArduPilot/ardupilot
autotest: test for scripted notches
This commit is contained in:
parent
a9f036e1da
commit
07910ac32b
|
@ -6405,6 +6405,43 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||||
})
|
})
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
|
|
||||||
|
self.hover_and_check_matched_frequency_with_fft(dblevel=-15, minhz=20, maxhz=350, reverse=True, instance=2)
|
||||||
|
|
||||||
|
def StaticScriptedNotches(self):
|
||||||
|
"""Use a scripted static harmonic notch to control motor noise."""
|
||||||
|
self.progress("Flying with Scripted Static notches")
|
||||||
|
self.set_parameters({
|
||||||
|
"AHRS_EKF_TYPE": 10,
|
||||||
|
"INS_LOG_BAT_MASK": 3,
|
||||||
|
"INS_LOG_BAT_OPT": 4,
|
||||||
|
"INS_GYRO_FILTER": 100, # set the gyro filter high so we can observe behaviour
|
||||||
|
"LOG_BITMASK": 65535,
|
||||||
|
"LOG_DISARMED": 0,
|
||||||
|
"SIM_VIB_FREQ_X": 120, # roll
|
||||||
|
"SIM_VIB_FREQ_Y": 120, # pitch
|
||||||
|
"SIM_VIB_FREQ_Z": 120, # yaw
|
||||||
|
"SIM_VIB_MOT_MULT": 0,
|
||||||
|
"SIM_GYR1_RND": 5,
|
||||||
|
"INS_HNTCH_ENABLE": 1,
|
||||||
|
#"INS_HNTCH_FREQ": 120,
|
||||||
|
"INS_HNTCH_REF": 1.0,
|
||||||
|
"INS_HNTCH_HMNCS": 1, # first and second harmonic
|
||||||
|
"INS_HNTCH_ATT": 50,
|
||||||
|
"INS_HNTCH_BW": 40,
|
||||||
|
"INS_HNTCH_MODE": 6, # static notch
|
||||||
|
"SCR_ENABLE": 1,
|
||||||
|
})
|
||||||
|
|
||||||
|
# install copter-posoffset script
|
||||||
|
self.install_test_script_context('static_notches.lua')
|
||||||
|
self.reboot_sitl()
|
||||||
|
|
||||||
|
self.set_parameters({
|
||||||
|
"SNOTCH1_FREQ": 120,
|
||||||
|
"SNOTCH2_FREQ": 240,
|
||||||
|
})
|
||||||
|
|
||||||
|
|
||||||
self.hover_and_check_matched_frequency_with_fft(dblevel=-15, minhz=20, maxhz=350, reverse=True, instance=2)
|
self.hover_and_check_matched_frequency_with_fft(dblevel=-15, minhz=20, maxhz=350, reverse=True, instance=2)
|
||||||
|
|
||||||
def ThrottleGainBoost(self):
|
def ThrottleGainBoost(self):
|
||||||
|
@ -12177,6 +12214,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||||
self.DynamicRpmNotches, # Do not add attempts to this - failure is sign of a bug
|
self.DynamicRpmNotches, # Do not add attempts to this - failure is sign of a bug
|
||||||
self.PIDNotches,
|
self.PIDNotches,
|
||||||
self.StaticNotches,
|
self.StaticNotches,
|
||||||
|
self.StaticScriptedNotches,
|
||||||
self.RefindGPS,
|
self.RefindGPS,
|
||||||
Test(self.GyroFFT, attempts=1, speedup=8),
|
Test(self.GyroFFT, attempts=1, speedup=8),
|
||||||
Test(self.GyroFFTHarmonic, attempts=4, speedup=8),
|
Test(self.GyroFFTHarmonic, attempts=4, speedup=8),
|
||||||
|
|
Loading…
Reference in New Issue