Skip to content

Commit

Permalink
Refactor SwerveDrive to use DriveConstants for kinematics and remove …
Browse files Browse the repository at this point in the history
…unused test files
  • Loading branch information
Ishan1522 committed Dec 31, 2024
1 parent 34a0c4b commit abaea2a
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 135 deletions.
16 changes: 3 additions & 13 deletions src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@ public class SwerveDrive extends SubsystemBase {

private final Alert gyroDisconnectedAlert =
new Alert("Gyro Hardware Fault", Alert.AlertType.kError);
private SwerveDriveKinematics kinematics;

public SwerveDrive(
GyroInterface gyroIO,
Expand All @@ -54,7 +53,6 @@ public SwerveDrive(
this.gyroInputs = new GyroInputsAutoLogged();
this.rawGyroRotation = new Rotation2d();

setKinematics(DriveConstants.DRIVE_KINEMATICS);
swerveModules =
new SwerveModule[] {
new SwerveModule(frontLeftModuleIO, "FrontLeft"),
Expand All @@ -72,7 +70,7 @@ public SwerveDrive(
};
poseEstimator =
new SwerveDrivePoseEstimator(
getKinematics(),
DriveConstants.DRIVE_KINEMATICS,
rawGyroRotation,
lastModulePositions,
new Pose2d(),
Expand All @@ -90,14 +88,6 @@ public SwerveDrive(
gyroDisconnectedAlert.set(false);
}

public SwerveDriveKinematics getKinematics() {
return kinematics;
}

public void setKinematics(SwerveDriveKinematics newKinematics) {
kinematics = newKinematics;
}

/**
* Gets the current velocity of the gyro's yaw
*
Expand Down Expand Up @@ -198,7 +188,7 @@ private void modulesPeriodic() {
*/
public void drive(double xSpeed, double ySpeed, double rotationSpeed, boolean fieldRelative) {
SwerveModuleState[] swerveModuleStates =
getKinematics()
DriveConstants.DRIVE_KINEMATICS
.toSwerveModuleStates(
fieldRelative
? ChassisSpeeds.fromFieldRelativeSpeeds(
Expand Down Expand Up @@ -243,7 +233,7 @@ private void addPoseEstimatorSwerveMeasurement(int timestampIndex) {
if (gyroInputs.isConnected) {
rawGyroRotation = gyroInputs.odometryYawPositions[timestampIndex];
} else {
Twist2d twist = getKinematics().toTwist2d(moduleDeltas);
Twist2d twist = DriveConstants.DRIVE_KINEMATICS.toTwist2d(moduleDeltas);
rawGyroRotation = rawGyroRotation.plus(new Rotation2d(twist.dtheta));
}

Expand Down
83 changes: 0 additions & 83 deletions src/test/java/SwerveDriveTest.java

This file was deleted.

39 changes: 0 additions & 39 deletions src/test/java/SwerveModuleTest.java

This file was deleted.

0 comments on commit abaea2a

Please sign in to comment.