Tools: update for changed INS_NOTCH parameter name

This commit is contained in:
Andrew Tridgell 2022-04-13 13:44:27 +10:00
parent f5c3b56426
commit db9d796dd4
8 changed files with 32 additions and 31 deletions

View File

@ -455,10 +455,10 @@ class FilterTest:
filt_type = f.get_type()
if filt_type == BiquadFilterType.PEAK: # NOTCH
print("INS_NOTCH_ENABLE,", 1)
print("INS_NOTCH_FREQ,", f.get_center_freq())
print("INS_NOTCH_BW,", f.get_bandwidth())
print("INS_NOTCH_ATT,", f.get_attenuation())
print("INS_HNTC2_ENABLE,", 1)
print("INS_HNTC2_FREQ,", f.get_center_freq())
print("INS_HNTC2_BW,", f.get_bandwidth())
print("INS_HNTC2_ATT,", f.get_attenuation())
else: # LPF
print("INS_GYRO_FILTER,", f.get_center_freq())

View File

@ -72,7 +72,7 @@ PREVENT_POST_FILTER_LOGS = False
PARAMS_TO_CHECK = [
"INS_LOG_BAT_OPT", "INS_GYRO_FILTER", "INS_ACCEL_FILTER",
"INS_NOTCH_ENABLE", "INS_NOTCH_FREQ", "INS_NOTCH_BW", "INS_NOTCH_ATT",
"INS_HNTC2_ENABLE", "INS_HNTC2_FREQ", "INS_HNTC2_BW", "INS_HNTC2_ATT",
"INS_NOTCA_ENABLE", "INS_NOTCA_FREQ", "INS_NOTCA_BW", "INS_NOTCA_ATT",
"LOG_BITMASK"
]
@ -226,18 +226,18 @@ if "INS_GYRO_FILTER" in params:
if "INS_ACCEL_FILTER" in params:
DEFAULT_ACC_FILTER = params["INS_ACCEL_FILTER"]
if "INS_NOTCH_ENABLE" in params:
if params["INS_NOTCH_ENABLE"] != 0:
if "INS_NOTCH_ATT" in params:
DEFAULT_GYR_NOTCH_ATTENUATION = params["INS_NOTCH_ATT"]
if "INS_HNTC2_ENABLE" in params:
if params["INS_HNTC2_ENABLE"] != 0:
if "INS_HNTC2_ATT" in params:
DEFAULT_GYR_NOTCH_ATTENUATION = params["INS_HNTC2_ATT"]
else:
DEFAULT_GYR_NOTCH_ATTENUATION = 0
if "INS_NOTCH_BW" in params:
DEFAULT_GYR_NOTCH_BANDWIDTH = params["INS_NOTCH_BW"]
if "INS_HNTC2_BW" in params:
DEFAULT_GYR_NOTCH_BANDWIDTH = params["INS_HNTC2_BW"]
if "INS_NOTCH_FREQ" in params:
DEFAULT_GYR_NOTCH_FREQ = params["INS_NOTCH_FREQ"]
if "INS_HNTC2_FREQ" in params:
DEFAULT_GYR_NOTCH_FREQ = params["INS_HNTC2_FREQ"]
if "INS_NOTCA_ENABLE" in params:
if params["INS_NOTCA_ENABLE"] != 0:

View File

@ -117,10 +117,10 @@ DISARM_DELAY 8
INS_FAST_SAMPLE 1
INS_GYRO_FILTER 20
LOG_BITMASK 65534
INS_NOTCH_ENABLE 1
INS_NOTCH_ATT 30
INS_NOTCH_BW 60
INS_NOTCH_FREQ 80
INS_HNTC2_ENABLE 1
INS_HNTC2_ATT 30
INS_HNTC2_BW 60
INS_HNTC2_FREQ 80
# rate controllers
ANGLE_MAX 3500

View File

@ -83,10 +83,10 @@ INS_HNTCH_ENABLE,1
INS_HNTCH_REF,0.26
INS_HNTCH_FREQ,200
INS_HNTCH_BW,100
INS_NOTCH_ATT,40
INS_NOTCH_ENABLE,1
INS_NOTCH_FREQ,98
INS_NOTCH_BW,49
INS_HNTC2_ATT,40
INS_HNTC2_ENABLE,1
INS_HNTC2_FREQ,98
INS_HNTC2_BW,49
INS_TRIM_OPTION,2
LAND_ALT_LOW,600
LAND_SPEED,45

View File

@ -82,10 +82,10 @@ INS_HNTCH_ENABLE,1
INS_HNTCH_REF,0.26
INS_HNTCH_FREQ,200
INS_HNTCH_BW,100
INS_NOTCH_ATT,40
INS_NOTCH_ENABLE,1
INS_NOTCH_FREQ,98
INS_NOTCH_BW,49
INS_HNTC2_ATT,40
INS_HNTC2_ENABLE,1
INS_HNTC2_FREQ,98
INS_HNTC2_BW,49
INS_TRIM_OPTION,2
LAND_ALT_LOW,600
LAND_SPEED,45

View File

@ -292,7 +292,7 @@ INS_LOG_BAT_LGCT,32
INS_LOG_BAT_LGIN,20
INS_LOG_BAT_MASK,0
INS_LOG_BAT_OPT,0
INS_NOTCH_ENABLE,0
INS_HNTC2_ENABLE,0
INS_POS1_X,0.0
INS_POS1_Y,0.0
INS_POS1_Z,0.0

View File

@ -292,7 +292,7 @@ INS_LOG_BAT_LGCT,32
INS_LOG_BAT_LGIN,20
INS_LOG_BAT_MASK,0
INS_LOG_BAT_OPT,0
INS_NOTCH_ENABLE,0
INS_HNTC2_ENABLE,0
INS_POS1_X,0.0
INS_POS1_Y,0.0
INS_POS1_Z,0.0

View File

@ -2679,10 +2679,11 @@ class AutoTestCopter(AutoTest):
# now add a notch and check that post-filter the peak is squashed below 40dB
self.set_parameters({
"INS_LOG_BAT_OPT": 2,
"INS_NOTCH_ENABLE": 1,
"INS_NOTCH_FREQ": freq,
"INS_NOTCH_ATT": 50,
"INS_NOTCH_BW": freq/2,
"INS_HNTC2_ENABLE": 1,
"INS_HNTC2_FREQ": freq,
"INS_HNTC2_ATT": 50,
"INS_HNTC2_BW": freq/2,
"INS_HNTC2_MODE": 0,
"SIM_VIB_MOT_MAX": 350,
})
self.reboot_sitl()