Class SwerveIMUSimulation

java.lang.Object
swervelib.simulation.SwerveIMUSimulation

public class SwerveIMUSimulation extends Object
Simulation for SwerveDrive IMU.
  • Constructor Details

    • SwerveIMUSimulation

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

    • getYaw

      public Rotation2d getYaw()
      Get the estimated angle of the robot.
      Returns:
      Rotation2d estimation of the robot.
    • getPitch

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

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

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

      public Optional<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(SwerveDriveKinematics kinematics, SwerveModuleState[] states, Pose2d[] modulePoses, 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.