diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 3e9e802b7c..21e0811179 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1501,7 +1501,7 @@ void Plane::load_parameters(void) } #if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1 - if (!ins.gyro_harmonic_notch_enabled(1)) { + if (!ins.harmonic_notches[1].params.enabled()) { // 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" }, @@ -1513,10 +1513,8 @@ void Plane::load_parameters(void) for (uint8_t i=0; iget_throttle_out() / ref))); - } -#endif - break; - - case HarmonicNotchDynamicMode::UpdateRPM: // rpm sensor based tracking - case HarmonicNotchDynamicMode::UpdateRPM2: { - uint8_t sensor = (ins.get_gyro_harmonic_notch_tracking_mode(idx)==HarmonicNotchDynamicMode::UpdateRPM?0:1); - float rpm; - if (rpm_sensor.get_rpm(sensor, rpm)) { - // set the harmonic notch filter frequency from the main rotor rpm - ins.update_harmonic_notch_freq_hz(idx, MAX(ref_freq, rpm * ref * (1/60.0))); - } else { - ins.update_harmonic_notch_freq_hz(idx, ref_freq); - } - break; - } -#if HAL_WITH_ESC_TELEM - case HarmonicNotchDynamicMode::UpdateBLHeli: // BLHeli based tracking - // set the harmonic notch filter frequency scaled on measured frequency - if (ins.has_harmonic_option(idx, HarmonicNotchFilterParams::Options::DynamicHarmonic)) { - float notches[INS_MAX_NOTCHES]; - const uint8_t num_notches = AP::esc_telem().get_motor_frequencies_hz(ins.get_num_gyro_dynamic_notches(idx), notches); - - for (uint8_t i = 0; i < num_notches; i++) { - notches[i] = MAX(ref_freq, notches[i]); - } - if (num_notches > 0) { - ins.update_harmonic_notch_frequencies_hz(idx, num_notches, notches); -#if HAL_QUADPLANE_ENABLED - } else if (quadplane.available()) { // throttle fallback - ins.update_harmonic_notch_freq_hz(idx, ref_freq * MAX(1.0f, sqrtf(quadplane.motors->get_throttle_out() / ref))); -#endif - } else { - ins.update_harmonic_notch_freq_hz(idx, ref_freq); - } - } else { - ins.update_harmonic_notch_freq_hz(idx, MAX(ref_freq, AP::esc_telem().get_average_motor_frequency_hz() * ref)); - } - break; -#endif -#if HAL_GYROFFT_ENABLED - case HarmonicNotchDynamicMode::UpdateGyroFFT: // FFT based tracking - // set the harmonic notch filter frequency scaled on measured frequency - if (ins.has_harmonic_option(idx, HarmonicNotchFilterParams::Options::DynamicHarmonic)) { - float notches[INS_MAX_NOTCHES]; - const uint8_t peaks = gyro_fft.get_weighted_noise_center_frequencies_hz(ins.get_num_gyro_dynamic_notches(idx), notches); - - ins.update_harmonic_notch_frequencies_hz(idx, peaks, notches); - } else { - ins.update_harmonic_notch_freq_hz(idx, gyro_fft.get_weighted_noise_center_freq_hz()); - } - break; -#endif - case HarmonicNotchDynamicMode::Fixed: // static - default: - ins.update_harmonic_notch_freq_hz(idx, ref_freq); - break; - } -}