Skip to content
This repository has been archived by the owner on May 19, 2024. It is now read-only.

Commit

Permalink
refactor(swerve): Move modules to controllers.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Apr 28, 2024
1 parent 7716544 commit 7932cad
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 13 deletions.
Original file line number Diff line number Diff line change
@@ -1,22 +1,22 @@
package frc.robot.swerve;
package frc.lib.controller;

import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;

/** Swerve module hardware interface. */
/** Swerve module interface. */
public interface SwerveModuleIO {

/**
* Gets the state of the swerve module.
* Returns the swerve module state.
*
* @return the state of the swerve module.
* @return the swerve module state.
*/
public SwerveModuleState getState();

/**
* Gets the setpoint of the swerve module.
* Returns the swerve module setpoint.
*
* @return the setpoint of the swerve module.
* @return the swerve module setpoint.
*/
public SwerveModuleState getSetpoint();

Expand All @@ -29,9 +29,9 @@ public interface SwerveModuleIO {
public void setSetpoint(SwerveModuleState setpoint, boolean lazy);

/**
* Gets the position of the swerve module.
* Returns the swerve module position.
*
* @return the position of the swerve module.
* @return the swerve module position.
*/
public SwerveModulePosition getPosition();
}
Original file line number Diff line number Diff line change
@@ -1,15 +1,14 @@
package frc.robot.swerve;
package frc.lib.controller;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.util.Units;
import frc.lib.CAN;
import frc.lib.controller.PositionControllerIO;
import frc.lib.controller.PositionControllerIO.PositionControllerIOValues;
import frc.lib.controller.VelocityControllerIO;
import frc.lib.controller.VelocityControllerIO.VelocityControllerIOValues;
import frc.robot.swerve.SwerveConstants.MK4iConstants;
import frc.robot.swerve.SwerveFactory;

/** Custom swerve module. */
public class SwerveModuleIOCustom implements SwerveModuleIO {
Expand Down Expand Up @@ -65,7 +64,7 @@ public void setSetpoint(SwerveModuleState setpoint, boolean lazy) {
}

/**
* Optimizes a swerve module's setpoint.
* Optimizes a swerve module setpoint.
*
* @param setpoint the setpoint to optimize.
* @param state the state of the module.
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/swerve/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.lib.Subsystem;
import frc.lib.Telemetry;
import frc.lib.controller.SwerveModuleIO;
import frc.robot.RobotConstants;

/** Swerve subsystem. */
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/swerve/SwerveFactory.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
import frc.lib.controller.PositionControllerIO;
import frc.lib.controller.PositionControllerIOSim;
import frc.lib.controller.PositionControllerIOTalonFXSteer;
import frc.lib.controller.SwerveModuleIO;
import frc.lib.controller.SwerveModuleIOCustom;
import frc.lib.controller.VelocityControllerIO;
import frc.lib.controller.VelocityControllerIOSim;
import frc.lib.controller.VelocityControllerIOTalonFXPIDF;
Expand Down Expand Up @@ -102,7 +104,7 @@ public static SwerveModuleIO createSouthWestModule() {
return createModule(
new CAN(10, "swerve"),
new CAN(20, "swerve"),
new CAN(28, "drive"),
new CAN(28, "swerve"),
Rotation2d.fromRotations(0.223145).unaryMinus());
}

Expand Down

0 comments on commit 7932cad

Please sign in to comment.