diff --git a/src/main/java/frc/lib/config/FeedbackControllerConfig.java b/src/main/java/frc/lib/config/FeedbackControllerConfig.java index d324e43..c019de9 100644 --- a/src/main/java/frc/lib/config/FeedbackControllerConfig.java +++ b/src/main/java/frc/lib/config/FeedbackControllerConfig.java @@ -14,13 +14,14 @@ public class FeedbackControllerConfig { /** Feedback controller derivative gain. */ private double kD = 0.0; + /** Feedback controller continuous input. */ + private boolean continuousInput = false; + /** Feedback controller position tolerance. */ - private double kPositionTolerance = 0.0; + private double positionTolerance = 0.0; /** Feedback controller velocity tolerance. */ - private double kVelocityTolerance = 0.0; - - // TODO Add velocity / acceleration constraints, profiled PID controller? + private double velocityTolerance = 0.0; /** * Modifies this controller config's proportional gain. @@ -56,38 +57,36 @@ public FeedbackControllerConfig withDerivativeGain(double kD) { } /** - * Modifies this controller config's position tolerance. + * Modifies this controller config's continuous input. * - * @param kPositionTolerance the position tolerance. + * @param continuousInput the continuous input. * @return this controller config. */ - public FeedbackControllerConfig withPositionTolerance(double kPositionTolerance) { - this.kPositionTolerance = kPositionTolerance; + public FeedbackControllerConfig withContinuousInput(boolean continuousInput) { + this.continuousInput = continuousInput; return this; } /** - * Modifies this controller config's velocity tolerance. + * Modifies this controller config's position tolerance. * - * @param kVelocityTolerance the velocity tolerance. + * @param positionTolerance the position tolerance. * @return this controller config. */ - public FeedbackControllerConfig withVelocityTolerance(double kVelocityTolerance) { - this.kVelocityTolerance = kVelocityTolerance; + public FeedbackControllerConfig withPositionTolerance(double positionTolerance) { + this.positionTolerance = positionTolerance; return this; } /** - * Creates a new PID controller using this feedback config. + * Modifies this controller config's velocity tolerance. * - * @return a new PID controller using this feedback config. + * @param velocityTolerance the velocity tolerance. + * @return this controller config. */ - public PIDController createPIDController() { - PIDController pidController = new PIDController(kP, kI, kD); - - pidController.setTolerance(kPositionTolerance, kVelocityTolerance); - - return pidController; + public FeedbackControllerConfig withVelocityTolerance(double velocityTolerance) { + this.velocityTolerance = velocityTolerance; + return this; } /** @@ -117,13 +116,22 @@ public double kD() { return kD; } + /** + * Returns the feedback controller continuous input. + * + * @return the feedback controller continuous input. + */ + public boolean continuousInput() { + return continuousInput; + } + /** * Returns the feedback controller position tolerance. * * @return the feedback controller position tolerance. */ - public double kPositionTolerance() { - return kPositionTolerance; + public double positionTolerance() { + return positionTolerance; } /** @@ -131,7 +139,24 @@ public double kPositionTolerance() { * * @return the feedback controller velocity tolerance. */ - public double kVelocityTolerance() { - return kVelocityTolerance; + public double velocityTolerance() { + return velocityTolerance; + } + + /** + * Creates a new PID controller using this feedback config. + * + * @return a new PID controller using this feedback config. + */ + public PIDController createPIDController() { + final PIDController pidController = new PIDController(kP, kI, kD); + + pidController.setTolerance(positionTolerance, velocityTolerance); + + if (continuousInput) { + pidController.enableContinuousInput(-0.5, 0.5); + } + + return pidController; } } diff --git a/src/main/java/frc/lib/controller/PositionControllerIOTalonFXSteer.java b/src/main/java/frc/lib/controller/PositionControllerIOTalonFXSteer.java new file mode 100644 index 0000000..d6decc2 --- /dev/null +++ b/src/main/java/frc/lib/controller/PositionControllerIOTalonFXSteer.java @@ -0,0 +1,106 @@ +package frc.lib.controller; + +import com.ctre.phoenix6.BaseStatusSignal; +import com.ctre.phoenix6.StatusSignal; +import com.ctre.phoenix6.controls.VoltageOut; +import com.ctre.phoenix6.hardware.CANcoder; +import com.ctre.phoenix6.hardware.ParentDevice; +import com.ctre.phoenix6.hardware.TalonFX; +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.math.controller.SimpleMotorFeedforward; +import frc.lib.CAN; +import frc.lib.config.Configurator; +import frc.lib.config.MechanismConfig; + +/** Creates a new position controller using a steer TalonFX and azimuth CANcoder. */ +public class PositionControllerIOTalonFXSteer implements PositionControllerIO { + + private final MechanismConfig config; + + private final TalonFX steer; + + private final CANcoder azimuth; + + private final StatusSignal position, velocity, acceleration, volts, amps; + + private final SimpleMotorFeedforward feedforward; + + private final PIDController feedback; + + private final VoltageOut voltage; + + public PositionControllerIOTalonFXSteer( + CAN steerCAN, CAN encoderCAN, MechanismConfig config, boolean enableFOC) { + this.config = config; + + steer = new TalonFX(steerCAN.id(), steerCAN.bus()); + + azimuth = new CANcoder(encoderCAN.id(), encoderCAN.bus()); + + // TODO Use steer position after seeding with azimuth + position = azimuth.getAbsolutePosition(); + + velocity = steer.getVelocity(); + acceleration = steer.getAcceleration(); + + volts = steer.getMotorVoltage(); + amps = steer.getStatorCurrent(); + + feedforward = config.feedforwardControllerConfig().createSimpleMotorFeedforward(); + + feedback = config.feedbackControllerConfig().createPIDController(); + + voltage = new VoltageOut(0.0).withEnableFOC(enableFOC); + } + + @Override + public void configure() { + BaseStatusSignal.setUpdateFrequencyForAll(100.0, position, velocity, acceleration, volts, amps); + + ParentDevice.optimizeBusUtilizationForAll(steer, azimuth); + + Configurator.configureTalonFX( + steer.getConfigurator(), config.motorConfig().createTalonFXConfig()); + + Configurator.configureCANcoder( + azimuth.getConfigurator(), config.absoluteEncoderConfig().createCANcoderConfig()); + } + + @Override + public void update(PositionControllerIOValues values) { + BaseStatusSignal.refreshAll(position, velocity, acceleration, volts, amps); + + values.positionRotations = position.getValue(); + values.velocityRotationsPerSecond = velocity.getValue(); + values.accelerationRotationsPerSecondPerSecond = acceleration.getValue(); + values.motorVolts = volts.getValue(); + values.motorAmps = amps.getValue(); + } + + @Override + public void setPosition(double positionRotations) {} + + @Override + public void setSetpoint(double positionRotations, double velocityRotationsPerSecond) { + double measuredPositionRotations = position.getValue(); + + // double feedforwardVolts = feedforward.calculate(velocityRotationsPerSecond); + double feedforwardVolts = calculateFeedforward(measuredPositionRotations, positionRotations); + + double feedbackVolts = feedback.calculate(measuredPositionRotations, positionRotations); + + steer.setControl(voltage.withOutput(feedforwardVolts + feedbackVolts)); + } + + private double calculateFeedforward(double measurementRotations, double setpointRotations) { + if (feedback.atSetpoint() == false) { + if (measurementRotations > setpointRotations) { + return feedforward.ks; + } else { + return -feedforward.ks; + } + } + + return 0.0; + } +} diff --git a/src/main/java/frc/robot/swerve/AzimuthEncoderIO.java b/src/main/java/frc/robot/swerve/AzimuthEncoderIO.java deleted file mode 100644 index 5233da8..0000000 --- a/src/main/java/frc/robot/swerve/AzimuthEncoderIO.java +++ /dev/null @@ -1,21 +0,0 @@ -package frc.robot.swerve; - -/** Azimuth encoder hardware interface. */ -public interface AzimuthEncoderIO { - - /** Values for the azimuth encoder hardware interface. */ - public static class AzimuthEncoderIOValues { - /** Position of the azimuth encoder in rotations. */ - public double positionRotations = 0.0; - } - - /** Configures the azimuth encoder. */ - public void configure(); - - /** - * Updates the azimuth encoder's values. - * - * @param values - */ - public void update(AzimuthEncoderIOValues values); -} diff --git a/src/main/java/frc/robot/swerve/AzimuthEncoderIOCANcoder.java b/src/main/java/frc/robot/swerve/AzimuthEncoderIOCANcoder.java deleted file mode 100644 index 02f98d4..0000000 --- a/src/main/java/frc/robot/swerve/AzimuthEncoderIOCANcoder.java +++ /dev/null @@ -1,51 +0,0 @@ -package frc.robot.swerve; - -import com.ctre.phoenix6.StatusSignal; -import com.ctre.phoenix6.configs.CANcoderConfiguration; -import com.ctre.phoenix6.hardware.CANcoder; -import edu.wpi.first.math.geometry.Rotation2d; -import frc.lib.CAN; -import frc.lib.config.Configurator; - -/** CANcoder azimuth encoder. */ -public class AzimuthEncoderIOCANcoder implements AzimuthEncoderIO { - - /** Hardware CANcoder. */ - private final CANcoder cancoder; - - /** CANcoder's absolute position status signal. */ - private final StatusSignal absolutePositionRotations; - - /** CANcoder's magnet offset. */ - private final Rotation2d magnetOffset; - - /** - * Creates a new CANcoder azimuth encoder. - * - * @param azimuthEncoderCAN the CANcoder's CAN identifier. - * @param magnetOffset the CANcoder's magnet offset. - */ - public AzimuthEncoderIOCANcoder(CAN azimuthEncoderCAN, Rotation2d magnetOffset) { - cancoder = new CANcoder(azimuthEncoderCAN.id(), azimuthEncoderCAN.bus()); - - absolutePositionRotations = cancoder.getAbsolutePosition(); - - this.magnetOffset = magnetOffset; - } - - @Override - public void configure() { - CANcoderConfiguration config = SwerveFactory.createAzimuthEncoderConfig(); - - config.MagnetSensor.MagnetOffset = magnetOffset.unaryMinus().getRotations(); - - Configurator.configureCANcoder(cancoder.getConfigurator(), config); - } - - @Override - public void update(AzimuthEncoderIOValues values) { - absolutePositionRotations.refresh(); - - values.positionRotations = absolutePositionRotations.getValue(); - } -} diff --git a/src/main/java/frc/robot/swerve/AzimuthEncoderIOSim.java b/src/main/java/frc/robot/swerve/AzimuthEncoderIOSim.java deleted file mode 100644 index ccf0279..0000000 --- a/src/main/java/frc/robot/swerve/AzimuthEncoderIOSim.java +++ /dev/null @@ -1,13 +0,0 @@ -package frc.robot.swerve; - -/** Simulated azimuth encoder. */ -public class AzimuthEncoderIOSim implements AzimuthEncoderIO { - - @Override - public void configure() {} - - @Override - public void update(AzimuthEncoderIOValues values) { - values.positionRotations = 0.0; - } -} diff --git a/src/main/java/frc/robot/swerve/SteerMotorIO.java b/src/main/java/frc/robot/swerve/SteerMotorIO.java deleted file mode 100644 index 35f7253..0000000 --- a/src/main/java/frc/robot/swerve/SteerMotorIO.java +++ /dev/null @@ -1,38 +0,0 @@ -package frc.robot.swerve; - -/** Steer motor hardware interface. */ -public interface SteerMotorIO { - - /** Values for the steer motor hardware interface. */ - public static class SteerMotorIOValues { - /** Position of the steer motor in rotations. */ - public double positionRotations = 0.0; - - /** Velocity of the steer motor in rotations per second. */ - public double velocityRotationsPerSecond = 0.0; - } - - /** Configures the steer motor. */ - public void configure(); - - /** - * Updates the steer motor's values. - * - * @param values - */ - public void update(SteerMotorIOValues values); - - /** - * Sets the steer motor's position. - * - * @param positionRotations the steer motor's position. - */ - public void setPosition(double positionRotations); - - /** - * Sets the steer motor's setpoint. - * - * @param positionRotations the steer motor's setpoint. - */ - public void setSetpoint(double positionRotations); -} diff --git a/src/main/java/frc/robot/swerve/SteerMotorIOSim.java b/src/main/java/frc/robot/swerve/SteerMotorIOSim.java deleted file mode 100644 index 2c9f033..0000000 --- a/src/main/java/frc/robot/swerve/SteerMotorIOSim.java +++ /dev/null @@ -1,74 +0,0 @@ -package frc.robot.swerve; - -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj.simulation.FlywheelSim; -import frc.lib.config.MechanismConfig; -import frc.robot.RobotConstants; -import frc.robot.swerve.SwerveConstants.MK4iConstants; - -/** Simulated steer motor. */ -public class SteerMotorIOSim implements SteerMotorIO { - - /** Represents the motor used to steer the wheel. */ - private final DCMotor motorSim = DCMotor.getFalcon500(1); - - /** Represents the wheel steered by the motor. */ - private final FlywheelSim wheelSim = - new FlywheelSim(motorSim, MK4iConstants.STEER_GEARING, MK4iConstants.STEER_MOI); - - /** Represents the position of the steer motor. */ - private double positionRotations; - - /** Represents the velocity of the steer motor. */ - private double velocityRotationsPerSecond; - - /** PIDF position controller. */ - private final SteerMotorPIDF pidf; - - public SteerMotorIOSim() { - positionRotations = 0.0; - velocityRotationsPerSecond = 0.0; - - MechanismConfig config = SwerveConstants.STEER_PIDF_CONSTANTS; - - // Simulation is an ideal environment that does not have friction - config = - config - .withFeedforwardConfig(config.feedforwardControllerConfig().withStaticFeedforward(0.0)) - .withFeedbackConfig(config.feedbackControllerConfig().withPositionTolerance(0.0)); - - pidf = new SteerMotorPIDF(config); - } - - @Override - public void configure() {} - - @Override - public void update(SteerMotorIOValues values) { - values.positionRotations = positionRotations; - values.velocityRotationsPerSecond = velocityRotationsPerSecond; - } - - @Override - public void setPosition(double positionRotations) { - this.positionRotations = positionRotations; - } - - @Override - public void setSetpoint(double positionRotations) { - double voltage = - pidf.calculate( - Rotation2d.fromRotations(this.positionRotations), - Rotation2d.fromRotations(positionRotations)); - - wheelSim.setInputVoltage(voltage); - wheelSim.update(RobotConstants.PERIODIC_DURATION); - - this.velocityRotationsPerSecond = - Units.radiansToRotations(wheelSim.getAngularVelocityRadPerSec()) - / MK4iConstants.STEER_GEARING; - this.positionRotations += this.velocityRotationsPerSecond; - } -} diff --git a/src/main/java/frc/robot/swerve/SteerMotorIOTalonFX.java b/src/main/java/frc/robot/swerve/SteerMotorIOTalonFX.java deleted file mode 100644 index c0f9d96..0000000 --- a/src/main/java/frc/robot/swerve/SteerMotorIOTalonFX.java +++ /dev/null @@ -1,56 +0,0 @@ -package frc.robot.swerve; - -import com.ctre.phoenix6.BaseStatusSignal; -import com.ctre.phoenix6.StatusSignal; -import com.ctre.phoenix6.hardware.TalonFX; -import frc.lib.CAN; - -/** TalonFX steer motor. */ -public abstract class SteerMotorIOTalonFX implements SteerMotorIO { - - /** Hardware TalonFX. */ - protected final TalonFX talonFX; - - /** TalonFX"s position and velocity status signals. */ - protected final StatusSignal positionRotations, velocityRotationsPerSecond; - - /** CAN identifier for the steer motor's corresponding azimuth encoder. */ - protected final CAN azimuthEncoderCAN; - - /** - * Creates a new TalonFX steer motor. - * - * @param steerMotorCAN the TalonFX's CAN identifier. - * @param azimuthEncoderCAN the CAN identifier for the steer motor's corresponding azimuth - * encoder. - */ - public SteerMotorIOTalonFX(CAN steerMotorCAN, CAN azimuthEncoderCAN) { - talonFX = new TalonFX(steerMotorCAN.id(), steerMotorCAN.bus()); - - positionRotations = talonFX.getPosition(); - velocityRotationsPerSecond = talonFX.getVelocity(); - - this.azimuthEncoderCAN = azimuthEncoderCAN; - } - - @Override - public abstract void configure(); - - @Override - public void update(SteerMotorIOValues values) { - positionRotations.refresh(); - velocityRotationsPerSecond.refresh(); - - values.positionRotations = - BaseStatusSignal.getLatencyCompensatedValue(positionRotations, velocityRotationsPerSecond); - values.velocityRotationsPerSecond = velocityRotationsPerSecond.getValue(); - } - - @Override - public void setPosition(double positionRotations) { - talonFX.setPosition(positionRotations); - } - - @Override - public abstract void setSetpoint(double positionRotations); -} diff --git a/src/main/java/frc/robot/swerve/SteerMotorIOTalonFXPIDF.java b/src/main/java/frc/robot/swerve/SteerMotorIOTalonFXPIDF.java deleted file mode 100644 index 98fe0cb..0000000 --- a/src/main/java/frc/robot/swerve/SteerMotorIOTalonFXPIDF.java +++ /dev/null @@ -1,63 +0,0 @@ -package frc.robot.swerve; - -import com.ctre.phoenix6.BaseStatusSignal; -import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.controls.VoltageOut; -import com.ctre.phoenix6.signals.InvertedValue; -import edu.wpi.first.math.geometry.Rotation2d; -import frc.lib.CAN; -import frc.lib.config.Configurator; -import frc.robot.swerve.SwerveConstants.MK4iConstants; - -/** TalonFX steer motor controlled by an external PIDF controller. */ -public class SteerMotorIOTalonFXPIDF extends SteerMotorIOTalonFX { - - /** PIDF position controller. */ - private final SteerMotorPIDF pidf; - - /** Voltage output request. */ - private final VoltageOut voltageOutRequest; - - /** - * Creates a new TalonFX steer motor controlled by an external PIDF controller. - * - * @param steerMotorCAN the TalonFX's CAN identifier. - * @param azimuthEncoderCAN the CAN identifier for the steer motor's corresponding azimuth - * encoder. - */ - public SteerMotorIOTalonFXPIDF(CAN steerMotorCAN, CAN azimuthEncoderCAN) { - super(steerMotorCAN, azimuthEncoderCAN); - - pidf = new SteerMotorPIDF(SwerveConstants.STEER_PIDF_CONSTANTS); - - voltageOutRequest = new VoltageOut(0).withEnableFOC(SwerveConstants.USE_PHOENIX_PRO_FOC); - } - - @Override - public void configure() { - TalonFXConfiguration talonFXPIDFConfig = new TalonFXConfiguration(); - - talonFXPIDFConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; - - talonFXPIDFConfig.ClosedLoopGeneral.ContinuousWrap = true; - - // talonFXPIDFConfig.CurrentLimits = - // new MotorCurrentLimits(35.0, 15.0, 25.0, 0.1).asCurrentLimitsConfigs(); - - talonFXPIDFConfig.Feedback.SensorToMechanismRatio = MK4iConstants.STEER_GEARING; - - Configurator.configureTalonFX(talonFX.getConfigurator(), talonFXPIDFConfig); - } - - @Override - public void setSetpoint(double positionRotations) { - Rotation2d measuredPosition = - Rotation2d.fromRotations( - BaseStatusSignal.getLatencyCompensatedValue( - this.positionRotations, this.velocityRotationsPerSecond)); - - double voltage = pidf.calculate(measuredPosition, Rotation2d.fromRotations(positionRotations)); - - talonFX.setControl(voltageOutRequest.withOutput(voltage)); - } -} diff --git a/src/main/java/frc/robot/swerve/SteerMotorPIDF.java b/src/main/java/frc/robot/swerve/SteerMotorPIDF.java deleted file mode 100644 index 6384e8d..0000000 --- a/src/main/java/frc/robot/swerve/SteerMotorPIDF.java +++ /dev/null @@ -1,56 +0,0 @@ -package frc.robot.swerve; - -import edu.wpi.first.math.controller.PIDController; -import edu.wpi.first.math.controller.SimpleMotorFeedforward; -import edu.wpi.first.math.geometry.Rotation2d; -import frc.lib.config.MechanismConfig; - -/** Utility class for calculating PIDF for steer motors. */ -public class SteerMotorPIDF { - - /** Feedforward controller for position. */ - private final SimpleMotorFeedforward feedforward; - - /** Feedback controller for position. */ - private final PIDController feedback; - - /** Creates a PIDF utility class. */ - public SteerMotorPIDF(MechanismConfig config) { - feedforward = config.feedforwardControllerConfig().createSimpleMotorFeedforward(); - - feedback = config.feedbackControllerConfig().createPIDController(); - feedback.enableContinuousInput(-0.5, 0.5); - } - - /** - * Returns true if feedback error is within tolerance. - * - * @return true if feedback error is within tolerance. - */ - public boolean atSetpoint() { - return feedback.atSetpoint(); - } - - /** - * Calculates the voltage to reach a setpoint position from a measured position. - * - * @param measurement the measured position of the steer motor. - * @param setpoint the setpoint position. - * @return the voltage to apply to the steer motor. - */ - public double calculate(Rotation2d measurement, Rotation2d setpoint) { - double feedbackVolts = feedback.calculate(measurement.getRotations(), setpoint.getRotations()); - - double feedforwardVolts = 0.0; - - if (feedback.atSetpoint() == false) { - if (measurement.getRadians() > setpoint.getRadians()) { - feedforwardVolts = feedforward.ks; - } else { - feedforwardVolts = -feedforward.ks; - } - } - - return feedbackVolts + feedforwardVolts; - } -} diff --git a/src/main/java/frc/robot/swerve/Swerve.java b/src/main/java/frc/robot/swerve/Swerve.java index f6abbd8..c3a569d 100644 --- a/src/main/java/frc/robot/swerve/Swerve.java +++ b/src/main/java/frc/robot/swerve/Swerve.java @@ -8,7 +8,6 @@ import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.lib.Subsystem; import frc.lib.Telemetry; @@ -87,7 +86,6 @@ public void addToShuffleboard(ShuffleboardTab tab) { ShuffleboardLayout swerveModuleColumn = Telemetry.addColumn(tab, "Module " + i); - swerveModuleColumn.addDouble("Azimuth (deg)", () -> swerveModule.getAzimuth().getDegrees()); swerveModuleColumn.addDouble("Angle (deg)", () -> swerveModule.getState().angle.getDegrees()); swerveModuleColumn.addDouble( "Velocity (mps)", () -> swerveModule.getState().speedMetersPerSecond); @@ -95,9 +93,6 @@ public void addToShuffleboard(ShuffleboardTab tab) { "Setpoint Angle (deg)", () -> swerveModule.getSetpoint().angle.getDegrees()); swerveModuleColumn.addDouble( "Setpoint Velocity (mps)", () -> swerveModule.getSetpoint().speedMetersPerSecond); - - swerveModuleColumn.add( - Commands.runOnce(swerveModule::syncSteerPosition).withName("Sync Steer")); } } diff --git a/src/main/java/frc/robot/swerve/SwerveConstants.java b/src/main/java/frc/robot/swerve/SwerveConstants.java index 9757661..eb96ade 100644 --- a/src/main/java/frc/robot/swerve/SwerveConstants.java +++ b/src/main/java/frc/robot/swerve/SwerveConstants.java @@ -161,13 +161,14 @@ private static double calculateKv(double voltsPerRotorRotationPerSecond) { ); /** Constants for steer motor PIDF position controllers. */ - public static final MechanismConfig STEER_PIDF_CONSTANTS = + public static final MechanismConfig STEER_CONFIG = new MechanismConfig() .withFeedforwardConfig( new FeedforwardControllerConfig().withStaticFeedforward(0.205) // volts ) .withFeedbackConfig( new FeedbackControllerConfig() + .withContinuousInput(true) .withProportionalGain(54.0) // volts per rotation .withDerivativeGain(0.16) // volts per rotation per second .withPositionTolerance(Units.degreesToRotations(1)) // rotations diff --git a/src/main/java/frc/robot/swerve/SwerveFactory.java b/src/main/java/frc/robot/swerve/SwerveFactory.java index 4263eaa..c91dd6c 100644 --- a/src/main/java/frc/robot/swerve/SwerveFactory.java +++ b/src/main/java/frc/robot/swerve/SwerveFactory.java @@ -1,6 +1,8 @@ package frc.robot.swerve; -import com.ctre.phoenix6.configs.CANcoderConfiguration; +import frc.lib.controller.PositionControllerIO; +import frc.lib.controller.PositionControllerIOSim; +import frc.lib.controller.PositionControllerIOTalonFXSteer; import frc.robot.Robot; import frc.robot.RobotConstants; import frc.robot.RobotConstants.Subsystem; @@ -17,39 +19,20 @@ public static SwerveModuleIO createModule(SwerveModuleConfig config) { return new SwerveModuleIOCustom(config); } - /** - * Creates an azimuth encoder. - * - * @return an azimuth encoder. - */ - public static AzimuthEncoderIO createAzimuthEncoder(SwerveModuleConfig config) { - if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.SWERVE)) - return new AzimuthEncoderIOCANcoder(config.moduleCAN().azimuth(), config.offset()); - - return new AzimuthEncoderIOSim(); - } - - /** - * Creates an azimuth encoder configuration. - * - * @return an azimuth encoder configuration. - */ - public static CANcoderConfiguration createAzimuthEncoderConfig() { - CANcoderConfiguration azimuthEncoderConfig = new CANcoderConfiguration(); - - return azimuthEncoderConfig; - } - /** * Creates a steer motor. * * @return a steer motor. */ - public static SteerMotorIO createSteerMotor(SwerveModuleConfig config) { + public static PositionControllerIO createSteerMotor(SwerveModuleConfig config) { if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.SWERVE)) - return new SteerMotorIOTalonFXPIDF(config.moduleCAN().steer(), config.moduleCAN().azimuth()); + return new PositionControllerIOTalonFXSteer( + config.moduleCAN().steer(), + config.moduleCAN().azimuth(), + SwerveConstants.STEER_CONFIG, + false); - return new SteerMotorIOSim(); + return new PositionControllerIOSim(); } /** diff --git a/src/main/java/frc/robot/swerve/SwerveModuleIO.java b/src/main/java/frc/robot/swerve/SwerveModuleIO.java index 9174540..a99e927 100644 --- a/src/main/java/frc/robot/swerve/SwerveModuleIO.java +++ b/src/main/java/frc/robot/swerve/SwerveModuleIO.java @@ -1,15 +1,11 @@ package frc.robot.swerve; -import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.SwerveModulePosition; import edu.wpi.first.math.kinematics.SwerveModuleState; /** Swerve module hardware interface. */ public interface SwerveModuleIO { - /** Sets the steer motor's position to the azimuth encoder's position. */ - public void syncSteerPosition(); - /** * Gets the state of the swerve module. * @@ -17,13 +13,6 @@ public interface SwerveModuleIO { */ public SwerveModuleState getState(); - /** - * Gets the azimuth angle of the swerve module. - * - * @return the azimuth angle of the swerve module. - */ - public Rotation2d getAzimuth(); - /** * Gets the setpoint of the swerve module. * diff --git a/src/main/java/frc/robot/swerve/SwerveModuleIOCustom.java b/src/main/java/frc/robot/swerve/SwerveModuleIOCustom.java index 80db9ec..25ac0f9 100644 --- a/src/main/java/frc/robot/swerve/SwerveModuleIOCustom.java +++ b/src/main/java/frc/robot/swerve/SwerveModuleIOCustom.java @@ -4,24 +4,18 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.SwerveModulePosition; import edu.wpi.first.math.kinematics.SwerveModuleState; -import frc.robot.swerve.AzimuthEncoderIO.AzimuthEncoderIOValues; +import frc.lib.controller.PositionControllerIO; +import frc.lib.controller.PositionControllerIO.PositionControllerIOValues; import frc.robot.swerve.DriveMotorIO.DriveMotorIOValues; -import frc.robot.swerve.SteerMotorIO.SteerMotorIOValues; /** Custom swerve module. */ public class SwerveModuleIOCustom implements SwerveModuleIO { - /** Azimuth encoder. */ - private final AzimuthEncoderIO azimuthEncoder; - - /** Azimuth encoder values. */ - private final AzimuthEncoderIOValues azimuthEncoderValues = new AzimuthEncoderIOValues(); - /** Steer motor. */ - private final SteerMotorIO steerMotor; + private final PositionControllerIO steerMotor; /** Steer motor values. */ - private final SteerMotorIOValues steerMotorValues = new SteerMotorIOValues(); + private final PositionControllerIOValues steerMotorValues = new PositionControllerIOValues(); /** Drive motor. */ private final DriveMotorIO driveMotor; @@ -41,9 +35,6 @@ public class SwerveModuleIOCustom implements SwerveModuleIO { * @param config the swerve module's configuration. */ public SwerveModuleIOCustom(SwerveModuleConfig config) { - azimuthEncoder = SwerveFactory.createAzimuthEncoder(config); - azimuthEncoder.configure(); - steerMotor = SwerveFactory.createSteerMotor(config); steerMotor.configure(); @@ -51,14 +42,6 @@ public SwerveModuleIOCustom(SwerveModuleConfig config) { driveMotor.configure(); setpoint = new SwerveModuleState(); - - syncSteerPosition(); - } - - @Override - public void syncSteerPosition() { - azimuthEncoder.update(azimuthEncoderValues); - steerMotor.setPosition(azimuthEncoderValues.positionRotations); } @Override @@ -71,13 +54,6 @@ public SwerveModuleState getState() { Rotation2d.fromRotations(steerMotorValues.positionRotations)); } - @Override - public Rotation2d getAzimuth() { - azimuthEncoder.update(azimuthEncoderValues); - - return Rotation2d.fromRotations(azimuthEncoderValues.positionRotations); - } - @Override public SwerveModuleState getSetpoint() { return setpoint; @@ -87,7 +63,7 @@ public SwerveModuleState getSetpoint() { public void setSetpoint(SwerveModuleState setpoint, boolean lazy) { setpoint = optimize(setpoint, getState(), lazy); - steerMotor.setSetpoint(setpoint.angle.getRotations()); + steerMotor.setSetpoint(setpoint.angle.getRotations(), 0); driveMotor.setSetpoint(setpoint.speedMetersPerSecond); this.setpoint = setpoint; @@ -132,7 +108,6 @@ private SwerveModuleState optimize( @Override public SwerveModulePosition getPosition() { - azimuthEncoder.update(azimuthEncoderValues); steerMotor.update(steerMotorValues); driveMotor.update(driveMotorValues);