diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 506a48f11d..5282e01e2f 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -515,8 +515,8 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch ¬ch) // set the harmonic notch filter frequency scaled on measured frequency if (notch.params.hasOption(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { float notches[INS_MAX_NOTCHES]; - const uint8_t num_notches = AP::esc_telem().get_motor_frequencies_hz(notch.num_dynamic_notches, notches); // ESC telemetry will return 0 for missing data, but only after 1s + const uint8_t num_notches = AP::esc_telem().get_motor_frequencies_hz(INS_MAX_NOTCHES, notches); for (uint8_t i = 0; i < num_notches; i++) { if (!is_zero(notches[i])) { notches[i] = MAX(ref_freq, notches[i]);