diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 1adabc0020..3e9e802b7c 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1500,7 +1500,8 @@ void Plane::load_parameters(void) AP_Param::convert_class(old_key, &airspeed, airspeed.var_info, old_index, old_top_element, true); } - 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" }, @@ -1512,11 +1513,12 @@ void Plane::load_parameters(void) for (uint8_t i=0; iprintf("load_all took %uus\n", (unsigned)(micros() - before)); }