From 88fb38b52406ee7c934483e6adb2d9b97d1c332e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 31 Jan 2024 07:34:25 +1100 Subject: [PATCH] AP_InertialSensor: added comments --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index ec21119f80..c2c0cb46a3 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -2285,7 +2285,12 @@ void AP_InertialSensor::acal_update() } #endif -// Update the harmonic notch frequency +/* + Update the harmonic notch frequency + + Note that zero is a valid value and will disable the notch unless + the TreatLowAsMin option is set +*/ void AP_InertialSensor::HarmonicNotch::update_freq_hz(float scaled_freq) { calculated_notch_freq_hz[0] = scaled_freq; @@ -2294,7 +2299,7 @@ void AP_InertialSensor::HarmonicNotch::update_freq_hz(float scaled_freq) // Update the harmonic notch frequency void AP_InertialSensor::HarmonicNotch::update_frequencies_hz(uint8_t num_freqs, const float scaled_freq[]) { - // protect against zero as the scaled frequency + // note that we allow zero through, which will disable the notch for (uint8_t i = 0; i < num_freqs; i++) { calculated_notch_freq_hz[i] = scaled_freq[i]; }