|
|
|
@ -477,12 +477,12 @@ void Plane::update_dynamic_notch()
@@ -477,12 +477,12 @@ void Plane::update_dynamic_notch()
|
|
|
|
|
ins.update_harmonic_notch_freq_hz(ref_freq); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
#ifdef HAVE_AP_BLHELI_SUPPORT |
|
|
|
|
#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(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { |
|
|
|
|
float notches[INS_MAX_NOTCHES]; |
|
|
|
|
const uint8_t num_notches = AP_BLHeli::get_singleton()->get_motor_frequencies_hz(INS_MAX_NOTCHES, notches); |
|
|
|
|
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++) { |
|
|
|
|
notches[i] = MAX(ref_freq, notches[i]); |
|
|
|
@ -495,7 +495,7 @@ void Plane::update_dynamic_notch()
@@ -495,7 +495,7 @@ void Plane::update_dynamic_notch()
|
|
|
|
|
ins.update_harmonic_notch_freq_hz(ref_freq); |
|
|
|
|
} |
|
|
|
|
} else { |
|
|
|
|
ins.update_harmonic_notch_freq_hz(MAX(ref_freq, AP_BLHeli::get_singleton()->get_average_motor_frequency_hz() * ref)); |
|
|
|
|
ins.update_harmonic_notch_freq_hz(MAX(ref_freq, AP::esc_telem().get_average_motor_frequency_hz() * ref)); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
|