-
Notifications
You must be signed in to change notification settings - Fork 3
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
e897024
commit bcf16ff
Showing
9 changed files
with
269 additions
and
94 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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
131
src/main/java/frc/lib/util/swerve/SwerveModuleReal.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 GitHub Actions / testtool[testtool] src/main/java/frc/lib/util/swerve/SwerveModuleReal.java#L12 <com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocTypeCheck>
Raw output
|
||
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 GitHub Actions / testtool[testtool] src/main/java/frc/lib/util/swerve/SwerveModuleReal.java#L20 <com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocMethodCheck>
Raw output
|
||
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(); | ||
} | ||
|
||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.