Class SwerveIMUSimulation

java.lang.Object
swervelib.simulation.SwerveIMUSimulation

public class SwerveIMUSimulation extends Object
Simulation for SwerveDrive IMU.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    private double
    Heading of the robot.
    private double
    The last time the timer was read, used to determine position changes.
    private final edu.wpi.first.wpilibj.Timer
    Main timer to control movement estimations.
  • Constructor Summary

    Constructors
    Constructor
    Description
    Create the swerve drive IMU simulation.
  • Method Summary

    Modifier and Type
    Method
    Description
    Optional<edu.wpi.first.math.geometry.Translation3d>
    Fetch the acceleration [x, y, z] from the IMU in m/s/s.
    edu.wpi.first.math.geometry.Rotation3d
    Gets the estimated gyro Rotation3d of the robot.
    edu.wpi.first.math.geometry.Rotation2d
    Pitch is not simulated currently, always returns 0.
    edu.wpi.first.math.geometry.Rotation2d
    Roll is not simulated currently, always returns 0.
    edu.wpi.first.math.geometry.Rotation2d
    Get the estimated angle of the robot.
    void
    setAngle(double angle)
    Set the heading of the robot.
    void
    updateOdometry(edu.wpi.first.math.kinematics.SwerveDriveKinematics kinematics, edu.wpi.first.math.kinematics.SwerveModuleState[] states, edu.wpi.first.math.geometry.Pose2d[] modulePoses, edu.wpi.first.wpilibj.smartdashboard.Field2d field)
    Update the odometry of the simulated SwerveDrive and post the SwerveModule states to the Field2d.

    Methods inherited from class java.lang.Object

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

    • timer

      private final edu.wpi.first.wpilibj.Timer timer
      Main timer to control movement estimations.
    • lastTime

      private double lastTime
      The last time the timer was read, used to determine position changes.
    • angle

      private double angle
      Heading of the robot.
  • Constructor Details

    • SwerveIMUSimulation

      public SwerveIMUSimulation()
      Create the swerve drive IMU simulation.
  • Method Details

    • getYaw

      public edu.wpi.first.math.geometry.Rotation2d getYaw()
      Get the estimated angle of the robot.
      Returns:
      Rotation2d estimation of the robot.
    • getPitch

      public edu.wpi.first.math.geometry.Rotation2d getPitch()
      Pitch is not simulated currently, always returns 0.
      Returns:
      Pitch of the robot as Rotation2d.
    • getRoll

      public edu.wpi.first.math.geometry.Rotation2d getRoll()
      Roll is not simulated currently, always returns 0.
      Returns:
      Roll of the robot as Rotation2d.
    • getGyroRotation3d

      public edu.wpi.first.math.geometry.Rotation3d getGyroRotation3d()
      Gets the estimated gyro Rotation3d of the robot.
      Returns:
      The heading as a Rotation3d angle
    • getAccel

      public Optional<edu.wpi.first.math.geometry.Translation3d> getAccel()
      Fetch the acceleration [x, y, z] from the IMU in m/s/s. If acceleration isn't supported returns empty.
      Returns:
      Translation3d of the acceleration as an Optional.
    • updateOdometry

      public void updateOdometry(edu.wpi.first.math.kinematics.SwerveDriveKinematics kinematics, edu.wpi.first.math.kinematics.SwerveModuleState[] states, edu.wpi.first.math.geometry.Pose2d[] modulePoses, edu.wpi.first.wpilibj.smartdashboard.Field2d field)
      Update the odometry of the simulated SwerveDrive and post the SwerveModule states to the Field2d.
      Parameters:
      kinematics - SwerveDriveKinematics of the swerve drive.
      states - SwerveModuleState array of the module states.
      modulePoses - Pose2d representing the swerve modules.
      field - Field2d to update.
    • setAngle

      public void setAngle(double angle)
      Set the heading of the robot.
      Parameters:
      angle - Angle of the robot in radians.