From bde4bdc108a9c5dc71b78fd00390ffb088c21d1f Mon Sep 17 00:00:00 2001 From: Hayden Heroux Date: Sun, 28 Apr 2024 11:38:38 -0400 Subject: [PATCH] refactor(swerve): Start moving away from config. --- src/main/java/frc/robot/swerve/SwerveFactory.java | 15 +++++++++------ .../frc/robot/swerve/SwerveModuleIOCustom.java | 4 ++-- 2 files changed, 11 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/swerve/SwerveFactory.java b/src/main/java/frc/robot/swerve/SwerveFactory.java index 5bce6f3..5442c07 100644 --- a/src/main/java/frc/robot/swerve/SwerveFactory.java +++ b/src/main/java/frc/robot/swerve/SwerveFactory.java @@ -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; @@ -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(); @@ -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(); } diff --git a/src/main/java/frc/robot/swerve/SwerveModuleIOCustom.java b/src/main/java/frc/robot/swerve/SwerveModuleIOCustom.java index 5774f14..0aba5c3 100644 --- a/src/main/java/frc/robot/swerve/SwerveModuleIOCustom.java +++ b/src/main/java/frc/robot/swerve/SwerveModuleIOCustom.java @@ -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();