AP_InertialSensor: use freq_min_ratio on notch tune setup

set harmonics in notch setup
This commit is contained in:
Andy Piper 2023-01-18 22:58:44 +00:00 committed by Andrew Tridgell
parent 4199ccc292
commit bd05b548a7
2 changed files with 4 additions and 2 deletions

View File

@ -2135,7 +2135,7 @@ void AP_InertialSensor::HarmonicNotch::update_frequencies_hz(uint8_t num_freqs,
}
// setup the notch for throttle based tracking, called from FFT based tuning
bool AP_InertialSensor::setup_throttle_gyro_harmonic_notch(float center_freq_hz, float ref)
bool AP_InertialSensor::setup_throttle_gyro_harmonic_notch(float center_freq_hz, float lower_freq_hz, float ref, uint8_t harmonics)
{
for (auto &notch : harmonic_notches) {
if (notch.params.tracking_mode() != HarmonicNotchDynamicMode::UpdateThrottle) {
@ -2145,6 +2145,8 @@ bool AP_InertialSensor::setup_throttle_gyro_harmonic_notch(float center_freq_hz,
notch.params.set_center_freq_hz(center_freq_hz);
notch.params.set_reference(ref);
notch.params.set_bandwidth_hz(center_freq_hz / 2.0f);
notch.params.set_freq_min_ratio(lower_freq_hz / center_freq_hz);
notch.params.set_harmonics(harmonics);
notch.params.save_params();
// only enable the first notch
return true;

View File

@ -257,7 +257,7 @@ public:
uint16_t get_accel_filter_hz(void) const { return _accel_filter_cutoff; }
// setup the notch for throttle based tracking
bool setup_throttle_gyro_harmonic_notch(float center_freq_hz, float ref);
bool setup_throttle_gyro_harmonic_notch(float center_freq_hz, float lower_freq_hz, float ref, uint8_t harmonics);
// write out harmonic notch log messages
void write_notch_log_messages() const;