Package swervelib.imu
Class IMUVelocity
java.lang.Object
swervelib.imu.IMUVelocity
Generic IMU Velocity filter.
-
Field Summary
FieldsModifier and TypeFieldDescriptionprivate booleanPrevents calculation when no previous measurement exists.private final SwerveIMUSwerve IMU.private final edu.wpi.first.wpilibj.NotifierWPILibNotifierto keep IMU velocity up to date.private edu.wpi.first.math.geometry.Rotation2dTracks the previous loop's position as a Rotation2d.private doubleTracks the previous loop's recorded time.private doubleThe calculated velocity of the robot based on averaged IMU measurements.private final IMULinearMovingAverageFilterLinear filter used to calculate velocity, we use a custom filter class to prevent unwanted operations. -
Constructor Summary
ConstructorsConstructorDescriptionIMUVelocity(SwerveIMU gyro, double periodSeconds, int averagingTaps) Constructor for the IMU Velocity. -
Method Summary
Modifier and TypeMethodDescriptionstatic IMUVelocitycreateIMUVelocity(SwerveIMU gyro) Static factory for IMU Velocity.doubleGet the robot's angular velocity based on averaged meaasurements from the IMU.private voidupdate()Update the robot's rotational velocity based on the current gyro position.
-
Field Details
-
gyro
Swerve IMU. -
velocityFilter
Linear filter used to calculate velocity, we use a custom filter class to prevent unwanted operations. -
notifier
private final edu.wpi.first.wpilibj.Notifier notifierWPILibNotifierto keep IMU velocity up to date. -
firstCycle
private boolean firstCyclePrevents calculation when no previous measurement exists. -
timestamp
private double timestampTracks the previous loop's recorded time. -
position
private edu.wpi.first.math.geometry.Rotation2d positionTracks the previous loop's position as a Rotation2d. -
velocity
private double velocityThe calculated velocity of the robot based on averaged IMU measurements.
-
-
Constructor Details
-
IMUVelocity
Constructor for the IMU Velocity.- Parameters:
gyro- The SwerveIMU gyro.periodSeconds- The rate to collect measurements from the gyro, in the form (1/number of samples per second), make sure this does not exceed the update rate of your IMU.averagingTaps- The number of samples to used for the moving average linear filter. Higher values will not allow the system to update to changes in velocity, lower values may create a less smooth signal. Expected taps will probably be ~2-8, with the goal of having the lowest smooth value.
-
-
Method Details
-
createIMUVelocity
Static factory for IMU Velocity. Supported IMU rates will be as quick as possible but will not exceed 100hz and will use 5 taps (supported IMUs are listed in swervelib's IMU folder). Other gyroscopes will default to 50hz and 5 taps. For custom rates please use the IMUVelocity constructor.- Parameters:
gyro- The SwerveIMU gyro.- Returns:
IMUVelocityfor the given gyro with adjusted period readings for velocity.
-
update
private void update()Update the robot's rotational velocity based on the current gyro position. -
getVelocity
public double getVelocity()Get the robot's angular velocity based on averaged meaasurements from the IMU. Velocity is multiplied by 1e+6 (1,000,000) because the timestamps are in microseconds.- Returns:
- robot's angular velocity in rads/s as a double.
-