mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 14:25:20 +03:00
Improved initialisation order. Stopped calling pidInit before gyro detected (#4218)
This commit is contained in:
parent
ac1cc31ae5
commit
db8698d801
3 changed files with 70 additions and 60 deletions
|
@ -170,6 +170,14 @@ void pidInitFilters(const pidProfile_t *pidProfile)
|
|||
{
|
||||
BUILD_BUG_ON(FD_YAW != 2); // only setting up Dterm filters on roll and pitch axes, so ensure yaw axis is 2
|
||||
|
||||
if (targetPidLooptime == 0) {
|
||||
// no looptime set, so set all the filters to null
|
||||
dtermNotchFilterApplyFn = nullFilterApply;
|
||||
dtermLpfApplyFn = nullFilterApply;
|
||||
ptermYawFilterApplyFn = nullFilterApply;
|
||||
return;
|
||||
}
|
||||
|
||||
const uint32_t pidFrequencyNyquist = (1.0f / dT) / 2; // No rounding needed
|
||||
|
||||
uint16_t dTermNotchHz;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue