diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 247183d684..a3f1c672cb 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1387,7 +1387,8 @@ void Copter::convert_pid_parameters(void) AP_Param::convert_old_parameters(&ff_and_filt_conversion_info[i], 1.0f); } - if (!ins.gyro_notch_enabled()) { +#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1 + if (!ins.gyro_harmonic_notch_enabled(1)) { // notch filter parameter conversions (moved to INS_HNTC2) for 4.2.x, converted from fixed notch const AP_Param::ConversionInfo notchfilt_conversion_info[] { { Parameters::k_param_ins, 101, AP_PARAM_INT8, "INS_HNTC2_ENABLE" }, @@ -1399,11 +1400,12 @@ void Copter::convert_pid_parameters(void) for (uint8_t i=0; i