mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_Vehicle: removed num_dynamic_notches limit in dynamic harmonic
use INS_MAX_NOTCHES instead, allowing for more ESCs to be added by lua scripts
This commit is contained in:
parent
02c06167c1
commit
ac2701b1bf
@ -517,8 +517,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]);
|
||||
|
Loading…
Reference in New Issue
Block a user