AP_InertialSensor: move to new constant dt low pass filter class

This commit is contained in:
Iampete1 2024-07-27 13:12:50 +01:00 committed by Andrew Tridgell
parent 44918b0e75
commit 89297737ea
2 changed files with 2 additions and 2 deletions

View File

@ -182,7 +182,7 @@ private:
Vector3f gyro;
uint8_t accel_count;
uint8_t gyro_count;
LowPassFilterVector3f accel_filter{4000, 188};
LowPassFilterConstDtVector3f accel_filter{4000, 188};
} _accum;
};

View File

@ -152,7 +152,7 @@ private:
Vector3f gyro;
uint8_t accel_count;
uint8_t gyro_count;
LowPassFilterVector3f accel_filter{4500, 188};
LowPassFilterConstDtVector3f accel_filter{4500, 188};
} _accum;
};