Skip to content

Commit

Permalink
wip
Browse files Browse the repository at this point in the history
  • Loading branch information
agrinmanriv0537 committed Jan 25, 2024
1 parent e897024 commit bcf16ff
Show file tree
Hide file tree
Showing 9 changed files with 269 additions and 94 deletions.
114 changes: 29 additions & 85 deletions src/main/java/frc/lib/util/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
@@ -1,12 +1,8 @@
package frc.lib.util.swerve;

import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.DutyCycleOut;
import com.ctre.phoenix6.controls.PositionVoltage;
import com.ctre.phoenix6.controls.VelocityVoltage;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
Expand All @@ -20,13 +16,10 @@
public class SwerveModule {
public int moduleNumber;
private Rotation2d angleOffset;
private double lastAngle;

private TalonFX mAngleMotor;
private TalonFX mDriveMotor;
private CANcoder angleEncoder;
private TalonFXConfiguration swerveAngleFXConfig = new TalonFXConfiguration();
private TalonFXConfiguration swerveDriveFXConfig = new TalonFXConfiguration();
private CANcoderConfiguration swerveCANcoderConfig = new CANcoderConfiguration();
private SwerveModuleIO io;
private SwerveModuleInputsAutoLogged inputs = new SwerveModuleInputsAutoLogged();

private final SimpleMotorFeedforward driveFeedForward = new SimpleMotorFeedforward(
Constants.Swerve.driveKS, Constants.Swerve.driveKV, Constants.Swerve.driveKA);
Expand All @@ -48,76 +41,16 @@ public class SwerveModule {
* @param angleOffset Angle Offset of the CANCoder to align the wheels
*/
public SwerveModule(int moduleNumber, int driveMotorID, int angleMotorID, int cancoderID,
Rotation2d angleOffset) {
Rotation2d angleOffset, SwerveModuleIO io) {
this.io = io;
io.updateInputs(inputs);
resetToAbsolute();
this.moduleNumber = moduleNumber;

this.angleOffset = angleOffset;

/* Angle Encoder Config */
swerveCANcoderConfig.MagnetSensor.SensorDirection = Constants.Swerve.cancoderInvert;

angleEncoder = new CANcoder(cancoderID);
angleEncoder.getConfigurator().apply(swerveCANcoderConfig);

/* Angle Motor Config */
/* Motor Inverts and Neutral Mode */
swerveAngleFXConfig.MotorOutput.Inverted = Constants.Swerve.angleMotorInvert;
swerveAngleFXConfig.MotorOutput.NeutralMode = Constants.Swerve.angleNeutralMode;

/* Gear Ratio and Wrapping Config */
swerveAngleFXConfig.Feedback.SensorToMechanismRatio = Constants.Swerve.angleGearRatio;
swerveAngleFXConfig.ClosedLoopGeneral.ContinuousWrap = true;

/* Current Limiting */
swerveAngleFXConfig.CurrentLimits.SupplyCurrentLimitEnable =
Constants.Swerve.angleEnableCurrentLimit;
swerveAngleFXConfig.CurrentLimits.SupplyCurrentLimit = Constants.Swerve.angleCurrentLimit;
swerveAngleFXConfig.CurrentLimits.SupplyCurrentThreshold =
Constants.Swerve.angleCurrentThreshold;
swerveAngleFXConfig.CurrentLimits.SupplyTimeThreshold =
Constants.Swerve.angleCurrentThresholdTime;

/* PID Config */
swerveAngleFXConfig.Slot0.kP = Constants.Swerve.angleKP;
swerveAngleFXConfig.Slot0.kI = Constants.Swerve.angleKI;
swerveAngleFXConfig.Slot0.kD = Constants.Swerve.angleKD;
mAngleMotor = new TalonFX(angleMotorID);
mAngleMotor.getConfigurator().apply(swerveAngleFXConfig);
resetToAbsolute();
lastAngle = getState().angle.getDegrees();

/* Drive Motor Config */
/* Motor Inverts and Neutral Mode */
swerveDriveFXConfig.MotorOutput.Inverted = Constants.Swerve.driveMotorInvert;
swerveDriveFXConfig.MotorOutput.NeutralMode = Constants.Swerve.driveNeutralMode;

/* Gear Ratio Config */
swerveDriveFXConfig.Feedback.SensorToMechanismRatio = Constants.Swerve.driveGearRatio;

/* Current Limiting */
swerveDriveFXConfig.CurrentLimits.SupplyCurrentLimitEnable =
Constants.Swerve.driveEnableCurrentLimit;
swerveDriveFXConfig.CurrentLimits.SupplyCurrentLimit = Constants.Swerve.driveCurrentLimit;
swerveDriveFXConfig.CurrentLimits.SupplyCurrentThreshold =
Constants.Swerve.driveCurrentThreshold;
swerveDriveFXConfig.CurrentLimits.SupplyTimeThreshold =
Constants.Swerve.driveCurrentThresholdTime;

/* PID Config */
swerveDriveFXConfig.Slot0.kP = Constants.Swerve.driveKP;
swerveDriveFXConfig.Slot0.kI = Constants.Swerve.driveKI;
swerveDriveFXConfig.Slot0.kD = Constants.Swerve.driveKD;

/* Open and Closed Loop Ramping */
swerveDriveFXConfig.OpenLoopRamps.DutyCycleOpenLoopRampPeriod =
Constants.Swerve.openLoopRamp;
swerveDriveFXConfig.OpenLoopRamps.VoltageOpenLoopRampPeriod = Constants.Swerve.openLoopRamp;

swerveDriveFXConfig.ClosedLoopRamps.DutyCycleClosedLoopRampPeriod =
Constants.Swerve.closedLoopRamp;
swerveDriveFXConfig.ClosedLoopRamps.VoltageClosedLoopRampPeriod =
Constants.Swerve.closedLoopRamp;
mDriveMotor = new TalonFX(driveMotorID);
mDriveMotor.getConfigurator().apply(swerveDriveFXConfig);
mDriveMotor.getConfigurator().setPosition(0.0);
}

/**
Expand All @@ -128,7 +61,8 @@ public SwerveModule(int moduleNumber, int driveMotorID, int angleMotorID, int ca
*/
public void setDesiredState(SwerveModuleState desiredState, boolean isOpenLoop) {
desiredState = SwerveModuleState.optimize(desiredState, getState().angle);
mAngleMotor.setControl(anglePosition.withPosition(desiredState.angle.getRotations()));
// mAngleMotor.setControl(anglePosition.withPosition(desiredState.angle.getRotations()));
io.setAngleMotor(anglePosition.withPosition(desiredState.angle.getRotations()));
setSpeed(desiredState, isOpenLoop);
}

Expand All @@ -141,13 +75,15 @@ public void setDesiredState(SwerveModuleState desiredState, boolean isOpenLoop)
private void setSpeed(SwerveModuleState desiredState, boolean isOpenLoop) {
if (isOpenLoop) {
driveDutyCycle.Output = desiredState.speedMetersPerSecond / Constants.Swerve.maxSpeed;
mDriveMotor.setControl(driveDutyCycle);
// mDriveMotor.setControl(driveDutyCycle);
io.setDriveMotor(driveDutyCycle);
} else {
driveVelocity.Velocity = Conversions.MPSToRPS(desiredState.speedMetersPerSecond,
Constants.Swerve.wheelCircumference);
driveVelocity.FeedForward =
driveFeedForward.calculate(desiredState.speedMetersPerSecond);
mDriveMotor.setControl(driveVelocity);
// mDriveMotor.setControl(driveVelocity);
io.setDriveMotor(driveDutyCycle);
}
}

Expand All @@ -157,15 +93,16 @@ private void setSpeed(SwerveModuleState desiredState, boolean isOpenLoop) {
* @return The rotation of the CANCoder in {@link Rotation2d}
*/
public Rotation2d getCANcoder() {
return Rotation2d.fromRotations(angleEncoder.getAbsolutePosition().getValue());
return Rotation2d.fromRotations(io.getAbsolutePositionAngleEncoder().getValue());
}

/**
* Reset the Swerve Module angle to face forward
*/
public void resetToAbsolute() {
double absolutePosition = getCANcoder().getRotations() - angleOffset.getRotations();
mAngleMotor.setPosition(absolutePosition);
// mAngleMotor.setPosition(absolutePosition);
io.setPositionAngleMotor(absolutePosition);
}

/**
Expand All @@ -175,9 +112,12 @@ public void resetToAbsolute() {
*/
public SwerveModuleState getState() {
return new SwerveModuleState(
Conversions.RPSToMPS(mDriveMotor.getVelocity().getValue(),
// Conversions.RPSToMPS(mDriveMotor.getVelocity().getValue(),
// Constants.Swerve.wheelCircumference),
Conversions.RPSToMPS(io.getVelocityDriveMotor().getValue(),
Constants.Swerve.wheelCircumference),
Rotation2d.fromRotations(mAngleMotor.getPosition().getValue()));
// Rotation2d.fromRotations(mAngleMotor.getPosition().getValue()));
Rotation2d.fromRotations(io.getPositionAngleMotor().getValue()));
}

/**
Expand All @@ -187,8 +127,12 @@ public SwerveModuleState getState() {
*/
public SwerveModulePosition getPosition() {
return new SwerveModulePosition(
Conversions.rotationsToMeters(mDriveMotor.getPosition().getValue(),
// Conversions.rotationsToMeters(mDriveMotor.getPosition().getValue(),
// Constants.Swerve.wheelCircumference),
Conversions.rotationsToMeters(io.getPositionDriveMotor().getValue(),
Constants.Swerve.wheelCircumference),
Rotation2d.fromRotations(mAngleMotor.getPosition().getValue()));
// Rotation2d.fromRotations(mAngleMotor.getPosition().getValue()));
Rotation2d.fromRotations(io.getPositionAngleMotor().getValue()));

}
}
47 changes: 47 additions & 0 deletions src/main/java/frc/lib/util/swerve/SwerveModuleIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
package frc.lib.util.swerve;

import org.littletonrobotics.junction.AutoLog;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.controls.ControlRequest;

/** IO Class for SwerveModule */
public interface SwerveModuleIO {

/** Inputs Class for SwerveModule */
@AutoLog
public static class SwerveModuleInputs {
public double angleEncoderValue;
public double driveMotorSelectedPosition;
public double driveMotorSelectedSensorVelocity;
public double angleMotorSelectedPosition;
public double driveMotorTemperature;
public double angleMotorTemperature;
}

public default void updateInputs(SwerveModuleInputs inputs) {}

public default void setDriveMotor(ControlRequest request) {}

public default void setAngleMotor(ControlRequest request) {}

public default void setAngleSelectedSensorPosition(double angle) {}

public default StatusSignal<Double> getAbsolutePositionAngleEncoder() {
return null;
}

public default void setPositionAngleMotor(double absolutePosition) {}

public default StatusSignal<Double> getVelocityDriveMotor() {
return null;
}

public default StatusSignal<Double> getPositionAngleMotor() {
return null;
}

public default StatusSignal<Double> getPositionDriveMotor() {
return null;
}

}
131 changes: 131 additions & 0 deletions src/main/java/frc/lib/util/swerve/SwerveModuleReal.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,131 @@
package frc.lib.util.swerve;

import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.ControlRequest;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.math.geometry.Rotation2d;
import frc.robot.Constants;

public class SwerveModuleReal implements SwerveModuleIO {

Check warning on line 12 in src/main/java/frc/lib/util/swerve/SwerveModuleReal.java

View workflow job for this annotation

GitHub Actions / testtool

[testtool] src/main/java/frc/lib/util/swerve/SwerveModuleReal.java#L12 <com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocTypeCheck>

Missing a Javadoc comment.
Raw output
/github/workspace/./src/main/java/frc/lib/util/swerve/SwerveModuleReal.java:12:1: warning: Missing a Javadoc comment. (com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocTypeCheck)
private TalonFX mAngleMotor;
private TalonFX mDriveMotor;
private CANcoder angleEncoder;
private TalonFXConfiguration swerveAngleFXConfig = new TalonFXConfiguration();
private TalonFXConfiguration swerveDriveFXConfig = new TalonFXConfiguration();
private CANcoderConfiguration swerveCANcoderConfig = new CANcoderConfiguration();

public SwerveModuleReal(int moduleNumber, int driveMotorID, int angleMotorID, int cancoderID,

Check warning on line 20 in src/main/java/frc/lib/util/swerve/SwerveModuleReal.java

View workflow job for this annotation

GitHub Actions / testtool

[testtool] src/main/java/frc/lib/util/swerve/SwerveModuleReal.java#L20 <com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocMethodCheck>

Missing a Javadoc comment.
Raw output
/github/workspace/./src/main/java/frc/lib/util/swerve/SwerveModuleReal.java:20:5: warning: Missing a Javadoc comment. (com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocMethodCheck)
Rotation2d angleOffset, SwerveModuleIO io) {

angleEncoder = new CANcoder(cancoderID);
mDriveMotor = new TalonFX(driveMotorID);
mAngleMotor = new TalonFX(angleMotorID);

configAngleEncoder();
configAngleMotor();
configDriveMotor();
}

private void configAngleMotor() {
/* Angle Motor Config */
/* Motor Inverts and Neutral Mode */
swerveAngleFXConfig.MotorOutput.Inverted = Constants.Swerve.angleMotorInvert;
swerveAngleFXConfig.MotorOutput.NeutralMode = Constants.Swerve.angleNeutralMode;

/* Gear Ratio and Wrapping Config */
swerveAngleFXConfig.Feedback.SensorToMechanismRatio = Constants.Swerve.angleGearRatio;
swerveAngleFXConfig.ClosedLoopGeneral.ContinuousWrap = true;

/* Current Limiting */
swerveAngleFXConfig.CurrentLimits.SupplyCurrentLimitEnable =
Constants.Swerve.angleEnableCurrentLimit;
swerveAngleFXConfig.CurrentLimits.SupplyCurrentLimit = Constants.Swerve.angleCurrentLimit;
swerveAngleFXConfig.CurrentLimits.SupplyCurrentThreshold =
Constants.Swerve.angleCurrentThreshold;
swerveAngleFXConfig.CurrentLimits.SupplyTimeThreshold =
Constants.Swerve.angleCurrentThresholdTime;

/* PID Config */
swerveAngleFXConfig.Slot0.kP = Constants.Swerve.angleKP;
swerveAngleFXConfig.Slot0.kI = Constants.Swerve.angleKI;
swerveAngleFXConfig.Slot0.kD = Constants.Swerve.angleKD;

mAngleMotor.getConfigurator().apply(swerveAngleFXConfig);
}

private void configDriveMotor() {
/* Drive Motor Config */
/* Motor Inverts and Neutral Mode */
swerveDriveFXConfig.MotorOutput.Inverted = Constants.Swerve.driveMotorInvert;
swerveDriveFXConfig.MotorOutput.NeutralMode = Constants.Swerve.driveNeutralMode;

/* Gear Ratio Config */
swerveDriveFXConfig.Feedback.SensorToMechanismRatio = Constants.Swerve.driveGearRatio;

/* Current Limiting */
swerveDriveFXConfig.CurrentLimits.SupplyCurrentLimitEnable =
Constants.Swerve.driveEnableCurrentLimit;
swerveDriveFXConfig.CurrentLimits.SupplyCurrentLimit = Constants.Swerve.driveCurrentLimit;
swerveDriveFXConfig.CurrentLimits.SupplyCurrentThreshold =
Constants.Swerve.driveCurrentThreshold;
swerveDriveFXConfig.CurrentLimits.SupplyTimeThreshold =
Constants.Swerve.driveCurrentThresholdTime;

/* PID Config */
swerveDriveFXConfig.Slot0.kP = Constants.Swerve.driveKP;
swerveDriveFXConfig.Slot0.kI = Constants.Swerve.driveKI;
swerveDriveFXConfig.Slot0.kD = Constants.Swerve.driveKD;

/* Open and Closed Loop Ramping */
swerveDriveFXConfig.OpenLoopRamps.DutyCycleOpenLoopRampPeriod =
Constants.Swerve.openLoopRamp;
swerveDriveFXConfig.OpenLoopRamps.VoltageOpenLoopRampPeriod = Constants.Swerve.openLoopRamp;

swerveDriveFXConfig.ClosedLoopRamps.DutyCycleClosedLoopRampPeriod =
Constants.Swerve.closedLoopRamp;
swerveDriveFXConfig.ClosedLoopRamps.VoltageClosedLoopRampPeriod =
Constants.Swerve.closedLoopRamp;

mDriveMotor.getConfigurator().apply(swerveDriveFXConfig);
mDriveMotor.getConfigurator().setPosition(0.0);
}

private void configAngleEncoder() {
/* Angle Encoder Config */
swerveCANcoderConfig.MagnetSensor.SensorDirection = Constants.Swerve.cancoderInvert;

angleEncoder.getConfigurator().apply(swerveCANcoderConfig);
}

public void setAngleMotor(ControlRequest request) {
mAngleMotor.setControl(request);
}

public void setDriveMotor(ControlRequest request) {
mDriveMotor.setControl(request);
}

public StatusSignal<Double> getAbsolutePositionAngleEncoder() {
return angleEncoder.getAbsolutePosition();
}

public void setPositionAngleMotor(double absolutePosition) {
mAngleMotor.setPosition(absolutePosition);
}

public StatusSignal<Double> getVelocityDriveMotor() {
return mDriveMotor.getVelocity();
}

public StatusSignal<Double> getPositionAngleMotor() {
return mAngleMotor.getPosition();
}

public StatusSignal<Double> getPositionDriveMotor() {
return mDriveMotor.getPosition();
}

}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
import edu.wpi.first.wpilibj2.command.WaitCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.commands.TeleopSwerve;
import frc.robot.subsystems.Swerve;
import frc.robot.subsystems.swerve.Swerve;

/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/TeleopSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.Constants;
import frc.robot.subsystems.Swerve;
import frc.robot.subsystems.swerve.Swerve;

/**
* Creates an command for driving the swerve drive during tele-op
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants;
import frc.robot.subsystems.Swerve;
import frc.robot.subsystems.swerve.Swerve;

/**
* Zeros motors then executes normal wait command.
Expand Down
Loading

0 comments on commit bcf16ff

Please sign in to comment.