Package swervelib.imu

Class IMUVelocity

java.lang.Object
swervelib.imu.IMUVelocity

public class IMUVelocity extends Object
Generic IMU Velocity filter.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    private boolean
    Prevents calculation when no previous measurement exists.
    private final SwerveIMU
    Swerve IMU.
    private final edu.wpi.first.wpilibj.Notifier
    WPILib Notifier to keep IMU velocity up to date.
    private edu.wpi.first.math.geometry.Rotation2d
    Tracks the previous loop's position as a Rotation2d.
    private double
    Tracks the previous loop's recorded time.
    private double
    The calculated velocity of the robot based on averaged IMU measurements.
    Linear filter used to calculate velocity, we use a custom filter class to prevent unwanted operations.
  • Constructor Summary

    Constructors
    Constructor
    Description
    IMUVelocity(SwerveIMU gyro, double periodSeconds, int averagingTaps)
    Constructor for the IMU Velocity.
  • Method Summary

    Modifier and Type
    Method
    Description
    Static factory for IMU Velocity.
    double
    Get the robot's angular velocity based on averaged meaasurements from the IMU.
    private void
    Update the robot's rotational velocity based on the current gyro position.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • gyro

      private final SwerveIMU gyro
      Swerve IMU.
    • velocityFilter

      private final IMULinearMovingAverageFilter 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 notifier
      WPILib Notifier to keep IMU velocity up to date.
    • firstCycle

      private boolean firstCycle
      Prevents calculation when no previous measurement exists.
    • timestamp

      private double timestamp
      Tracks the previous loop's recorded time.
    • position

      private edu.wpi.first.math.geometry.Rotation2d position
      Tracks the previous loop's position as a Rotation2d.
    • velocity

      private double velocity
      The calculated velocity of the robot based on averaged IMU measurements.
  • Constructor Details

    • IMUVelocity

      public IMUVelocity(SwerveIMU gyro, double periodSeconds, int averagingTaps)
      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

      public static IMUVelocity createIMUVelocity(SwerveIMU gyro)
      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:
      IMUVelocity for 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.