Package swervelib.simulation
Class SwerveIMUSimulation
java.lang.Object
swervelib.simulation.SwerveIMUSimulation
Simulation for
SwerveDrive IMU.-
Constructor Summary
Constructors -
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.Rotation3dGets the estimated gyroRotation3dof the robot.edu.wpi.first.math.geometry.Rotation2dgetPitch()Pitch is not simulated currently, always returns 0.edu.wpi.first.math.geometry.Rotation2dgetRoll()Roll is not simulated currently, always returns 0.edu.wpi.first.math.geometry.Rotation2dgetYaw()Get the estimated angle of the robot.voidsetAngle(double angle) Set the heading of the robot.voidupdateOdometry(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)
-
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:
Rotation2destimation 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 gyroRotation3dof the robot.- Returns:
- The heading as a
Rotation3dangle
-
getAccel
Fetch the acceleration [x, y, z] from the IMU in m/s/s. If acceleration isn't supported returns empty.- Returns:
Translation3dof 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-SwerveDriveKinematicsof the swerve drive.states-SwerveModuleStatearray of the module states.modulePoses-Pose2drepresenting the swerve modules.field-Field2dto update.
-
setAngle
public void setAngle(double angle) Set the heading of the robot.- Parameters:
angle- Angle of the robot in radians.
-