mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: move to new constant dt low pass filter class
This commit is contained in:
parent
44918b0e75
commit
89297737ea
|
@ -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;
|
||||
};
|
||||
|
||||
|
|
|
@ -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;
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue