Package swervelib.simulation
Class SwerveIMUSimulation
java.lang.Object
swervelib.simulation.SwerveIMUSimulation
Simulation for
SwerveDrive
IMU.-
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptiongetAccel()
Fetch the acceleration [x, y, z] from the IMU in m/s/s.Gets the estimated gyroRotation3d
of the robot.getPitch()
Pitch is not simulated currently, always returns 0.getRoll()
Roll is not simulated currently, always returns 0.getYaw()
Get the estimated angle of the robot.void
setAngle
(double angle) Set the heading of the robot.void
updateOdometry
(SwerveDriveKinematics kinematics, SwerveModuleState[] states, Pose2d[] modulePoses, Field2d field)
-
Constructor Details
-
SwerveIMUSimulation
public SwerveIMUSimulation()Create the swerve drive IMU simulation.
-
-
Method Details
-
getYaw
Get the estimated angle of the robot.- Returns:
Rotation2d
estimation of the robot.
-
getPitch
Pitch is not simulated currently, always returns 0.- Returns:
- Pitch of the robot as
Rotation2d
.
-
getRoll
Roll is not simulated currently, always returns 0.- Returns:
- Roll of the robot as
Rotation2d
.
-
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(SwerveDriveKinematics kinematics, SwerveModuleState[] states, Pose2d[] modulePoses, 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.
-