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

Commit

Permalink
refactor(swerve): Start moving away from config.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Apr 28, 2024
1 parent 085c28c commit bde4bdc
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 8 deletions.
15 changes: 9 additions & 6 deletions src/main/java/frc/robot/swerve/SwerveFactory.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
package frc.robot.swerve;

import edu.wpi.first.math.geometry.Rotation2d;
import frc.lib.CAN;
import frc.lib.config.AbsoluteEncoderConfig;
import frc.lib.controller.PositionControllerIO;
import frc.lib.controller.PositionControllerIOSim;
import frc.lib.controller.PositionControllerIOTalonFXSteer;
Expand Down Expand Up @@ -27,13 +30,13 @@ public static SwerveModuleIO createModule(SwerveModuleConfig config) {
*
* @return a steer motor.
*/
public static PositionControllerIO createSteerMotor(SwerveModuleConfig config) {
public static PositionControllerIO createSteerMotor(CAN steer, CAN azimuth, Rotation2d offset) {
if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.SWERVE))
return new PositionControllerIOTalonFXSteer(
config.moduleCAN().steer(),
config.moduleCAN().azimuth(),
steer,
azimuth,
SwerveConstants.STEER_CONFIG.withAbsoluteEncoderConfig(
SwerveConstants.STEER_CONFIG.absoluteEncoderConfig().withOffset(config.offset())),
new AbsoluteEncoderConfig().withOffset(offset)),
false);

return new PositionControllerIOSim();
Expand All @@ -44,10 +47,10 @@ public static PositionControllerIO createSteerMotor(SwerveModuleConfig config) {
*
* @return a drive motor.
*/
public static VelocityControllerIO createDriveMotor(SwerveModuleConfig config) {
public static VelocityControllerIO createDriveMotor(CAN drive) {
if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.SWERVE))
return new VelocityControllerIOTalonFXPIDF(
config.moduleCAN().drive(), SwerveConstants.DRIVE_CONFIG, false);
drive, SwerveConstants.DRIVE_CONFIG, false);

return new VelocityControllerIOSim();
}
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/swerve/SwerveModuleIOCustom.java
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,10 @@ public class SwerveModuleIOCustom implements SwerveModuleIO {
* @param config the swerve module's configuration.
*/
public SwerveModuleIOCustom(SwerveModuleConfig config) {
steerMotor = SwerveFactory.createSteerMotor(config);
steerMotor = SwerveFactory.createSteerMotor(config.moduleCAN().steer(), config.moduleCAN().azimuth(), config.offset());
steerMotor.configure();

driveMotor = SwerveFactory.createDriveMotor(config);
driveMotor = SwerveFactory.createDriveMotor(config.moduleCAN().drive());
driveMotor.configure();

setpoint = new SwerveModuleState();
Expand Down

0 comments on commit bde4bdc

Please sign in to comment.