Skip to content

Commit

Permalink
Fused CANCoder works
Browse files Browse the repository at this point in the history
  • Loading branch information
legoguy1000 committed Dec 15, 2024
1 parent 9ccc49d commit 447101c
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 15 deletions.
4 changes: 1 addition & 3 deletions src/main/java/frc/lib/util/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@ public SwerveModule(int moduleNumber, Rotation2d angleOffset, SwerveModuleIO io)

// lastAngle = getState().angle.getDegrees();
io.updateInputs(inputs);
resetToAbsolute();
Logger.processInputs("SwerveModule" + moduleNumber, inputs);
}

Expand Down Expand Up @@ -119,8 +118,7 @@ public SwerveModuleState getStateAbs() {
return new SwerveModuleState(
Conversions.rotationPerSecondToMetersPerSecond(inputs.driveMotorSelectedSensorVelocity,
Constants.Swerve.wheelCircumference),
Rotation2d.fromRotations(
inputs.absolutePositionAngleEncoder - this.angleOffset.getRotations()));
Rotation2d.fromRotations(inputs.absolutePositionAngleEncoder));
}

/**
Expand Down
16 changes: 14 additions & 2 deletions src/main/java/frc/lib/util/swerve/SwerveModuleReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@
import com.ctre.phoenix6.controls.VelocityVoltage;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.FeedbackSensorSourceValue;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.AngularVelocity;
import frc.lib.math.Conversions;
Expand Down Expand Up @@ -40,9 +42,13 @@ public class SwerveModuleReal implements SwerveModuleIO {
/* angle motor control requests */
private final PositionVoltage anglePosition = new PositionVoltage(0);

private final Rotation2d angleOffset;

/** Instantiating motors and Encoders */
public SwerveModuleReal(int driveMotorID, int angleMotorID, int cancoderID) {
public SwerveModuleReal(int driveMotorID, int angleMotorID, int cancoderID,
Rotation2d cancoderOffset) {

this.angleOffset = cancoderOffset;
angleEncoder = new CANcoder(cancoderID);
mDriveMotor = new TalonFX(driveMotorID);
mAngleMotor = new TalonFX(angleMotorID);
Expand All @@ -63,8 +69,12 @@ private void configAngleMotor() {
swerveAngleFXConfig.MotorOutput.Inverted = Constants.Swerve.angleMotorInvert;
swerveAngleFXConfig.MotorOutput.NeutralMode = Constants.Swerve.angleNeutralMode;


/* Gear Ratio and Wrapping Config */
swerveAngleFXConfig.Feedback.SensorToMechanismRatio = Constants.Swerve.angleGearRatio;
swerveAngleFXConfig.Feedback.FeedbackRemoteSensorID = angleEncoder.getDeviceID();
swerveAngleFXConfig.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.FusedCANcoder;
swerveAngleFXConfig.Feedback.SensorToMechanismRatio = 1.0;
swerveAngleFXConfig.Feedback.RotorToSensorRatio = Constants.Swerve.angleGearRatio;
swerveAngleFXConfig.ClosedLoopGeneral.ContinuousWrap = true;

/* Current Limiting */
Expand Down Expand Up @@ -127,6 +137,8 @@ private void configDriveMotor() {
private void configAngleEncoder() {
/* Angle Encoder Config */
swerveCANcoderConfig.MagnetSensor.SensorDirection = Constants.Swerve.cancoderInvert;
swerveCANcoderConfig.MagnetSensor.AbsoluteSensorDiscontinuityPoint = 0.5;
swerveCANcoderConfig.MagnetSensor.MagnetOffset = -angleOffset.getRotations();

angleEncoder.getConfigurator().apply(swerveCANcoderConfig);
}
Expand Down
9 changes: 0 additions & 9 deletions src/main/java/frc/robot/subsystems/swerve/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -236,15 +236,6 @@ public void resetFieldRelativeOffset() {
fieldOffset = getGyroYaw().getDegrees() + 180;
}

/**
* Reset all modules to their front facing position
*/
public void resetModulesToAbsolute() {
for (SwerveModule mod : swerveMods) {
mod.resetToAbsolute();
}
}

@Override
public void periodic() {
// Robot.profiler.push("swerve_periodic");
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/swerve/SwerveReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ public void updateInputs(SwerveInputs inputs) {
public SwerveModule createSwerveModule(int moduleNumber, int driveMotorID, int angleMotorID,
int cancoderID, Rotation2d angleOffset) {
return new SwerveModule(moduleNumber, angleOffset,
new SwerveModuleReal(driveMotorID, angleMotorID, cancoderID));
new SwerveModuleReal(driveMotorID, angleMotorID, cancoderID, angleOffset));
}

@Override
Expand Down

0 comments on commit 447101c

Please sign in to comment.