AP_InertialSensor: allow access to harmonic notch for scripting

This commit is contained in:
Andy Piper 2024-11-03 14:04:22 +00:00
parent 4c9da021eb
commit 05eea57438
2 changed files with 22 additions and 0 deletions

View File

@ -1083,6 +1083,17 @@ AP_InertialSensor::init(uint16_t loop_rate)
#endif
}
#if AP_SCRIPTING_ENABLED
AP_InertialSensor::HarmonicNotch* AP_InertialSensor::get_harmonic_notch(uint8_t idx)
{
HarmonicNotch& notch = harmonic_notches[idx];
if (notch.params.tracking_mode() == HarmonicNotchDynamicMode::Scripting) {
return &notch;
}
return nullptr;
}
#endif
bool AP_InertialSensor::_add_backend(AP_InertialSensor_Backend *backend)
{

View File

@ -465,6 +465,13 @@ public:
return inactive;
}
#if AP_SCRIPTING_ENABLED
void set_frequency(uint8_t idx, float scaled_freq) { calculated_notch_freq_hz[idx] = fabsf(scaled_freq); }
void set_num_frequencies(uint8_t nfreqs) { num_calculated_notch_frequencies = nfreqs; }
float get_frequency(uint8_t idx) { return calculated_notch_freq_hz[idx]; }
uint8_t get_num_frequencies() { return num_calculated_notch_frequencies; }
#endif
private:
// support for updating harmonic filter at runtime
float last_center_freq_hz[INS_MAX_INSTANCES];
@ -472,6 +479,10 @@ public:
float last_attenuation_dB[INS_MAX_INSTANCES];
bool inactive;
} harmonic_notches[HAL_INS_NUM_HARMONIC_NOTCH_FILTERS];
#if AP_SCRIPTING_ENABLED
HarmonicNotch* get_harmonic_notch(uint8_t idx);
#endif
#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
private: