Package swervelib.simulation
Class SwerveIMUSimulation
java.lang.Object
swervelib.simulation.SwerveIMUSimulation
Simulation for
SwerveDrive
IMU.-
Field Summary
-
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionOptional<edu.wpi.first.math.geometry.Translation3d>
getAccel()
Fetch the acceleration [x, y, z] from the IMU in m/s/s.edu.wpi.first.math.geometry.Rotation3d
Gets the estimated gyroRotation3d
of the robot.edu.wpi.first.math.geometry.Rotation2d
getPitch()
Pitch is not simulated currently, always returns 0.edu.wpi.first.math.geometry.Rotation2d
getRoll()
Roll is not simulated currently, always returns 0.edu.wpi.first.math.geometry.Rotation2d
getYaw()
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)
-
Field Details
-
timer
private final edu.wpi.first.wpilibj.Timer timerMain timer to control movement estimations. -
lastTime
private double lastTimeThe last time the timer was read, used to determine position changes. -
angle
private double angleHeading 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 gyroRotation3d
of the robot.- Returns:
- The heading as a
Rotation3d
angle
-
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 anOptional
.
-
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) - 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.
-