mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 05:45:31 +03:00
Fixed array out of bounds issue - not all set.
This commit is contained in:
parent
00c0ca7c71
commit
d779daad2d
1 changed files with 7 additions and 7 deletions
|
@ -161,13 +161,13 @@ void gyroUpdate(void)
|
||||||
if (gyroLpfCutFreq) {
|
if (gyroLpfCutFreq) {
|
||||||
if (!gyroFilterStateIsSet) initGyroFilterCoefficients(); /* initialise filter coefficients */
|
if (!gyroFilterStateIsSet) initGyroFilterCoefficients(); /* initialise filter coefficients */
|
||||||
|
|
||||||
|
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||||
if (gyroFilterStateIsSet) {
|
if (gyroFilterStateIsSet) {
|
||||||
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++){
|
|
||||||
gyroADCf[axis] = applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis]);
|
gyroADCf[axis] = applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis]);
|
||||||
gyroADC[axis] = lrintf(gyroADCf[axis]);
|
gyroADC[axis] = lrintf(gyroADCf[axis]);
|
||||||
}
|
|
||||||
} else {
|
} else {
|
||||||
gyroADCf[axis] = gyroADC[axis]; // Otherwise float pid controller will not have gyro input when filter disabled
|
gyroADCf[axis] = gyroADC[axis]; // Otherwise float pid controller will not have gyro input when filter disabled
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue