mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_GyroFFT: update harmonics to uint32
This commit is contained in:
parent
e35a459090
commit
85234b5b18
@ -273,7 +273,7 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz)
|
||||
|
||||
// check for harmonics across all harmonic notch filters
|
||||
// note that we only allow one harmonic notch filter linked to the FFT code
|
||||
uint8_t harmonics = 0;
|
||||
uint32_t harmonics = 0;
|
||||
uint8_t num_notches = 0;
|
||||
for (auto ¬ch : _ins->harmonic_notches) {
|
||||
if (notch.params.enabled()) {
|
||||
|
Loading…
Reference in New Issue
Block a user