Package swervelib.simulation
Class SwerveIMUSimulation
java.lang.Object
swervelib.simulation.SwerveIMUSimulation
Simulation for
SwerveDrive IMU.-
Constructor Summary
ConstructorsConstructorDescriptionSwerveIMUSimulation(GyroSimulation gyroSimulation) Create the swerve drive IMU simulation. -
Method Summary
Modifier and TypeMethodDescriptiongetAccel()Fetch the acceleration [x, y, z] from the IMU in m/s/s.Gets the estimated gyroRotation3dof 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.voidsetAngle(double angle) Set the heading of the robot.voidupdateOdometry(SwerveDriveKinematics kinematics, SwerveModuleState[] states, Pose2d[] modulePoses, Field2d field)
-
Constructor Details
-
SwerveIMUSimulation
Create the swerve drive IMU simulation.- Parameters:
gyroSimulation- Gyro simulation from MapleSim.
-
-
Method Details
-
getYaw
Get the estimated angle of the robot.- Returns:
Rotation2destimation 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 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(SwerveDriveKinematics kinematics, SwerveModuleState[] states, Pose2d[] modulePoses, 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.
-