Skip to content
This repository has been archived by the owner on Nov 2, 2024. It is now read-only.

Commit

Permalink
still not works
Browse files Browse the repository at this point in the history
  • Loading branch information
gvaldez7206 committed Jan 26, 2024
1 parent 20e362c commit 282eb24
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 4 deletions.
6 changes: 3 additions & 3 deletions src/main/java/frc/lib/util/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ public SwerveModule(int moduleNumber, int driveMotorID, int angleMotorID, int ca
/* Angle Encoder Config */
swerveCANcoderConfig.MagnetSensor.SensorDirection = Constants.Swerve.CAN_CODER_INVERT;

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

/* Angle Motor Config */
Expand All @@ -81,7 +81,7 @@ public SwerveModule(int moduleNumber, int driveMotorID, int angleMotorID, int ca
swerveAngleFXConfig.Slot0.kP = Constants.Swerve.ANGLE_KP;
swerveAngleFXConfig.Slot0.kI = Constants.Swerve.ANGLE_KI;
swerveAngleFXConfig.Slot0.kD = Constants.Swerve.ANGLE_KD;
mAngleMotor = new TalonFX(angleMotorID);
mAngleMotor = new TalonFX(angleMotorID, "canivore");
mAngleMotor.getConfigurator().apply(swerveAngleFXConfig);
resetToAbsolute();

Expand Down Expand Up @@ -118,7 +118,7 @@ public SwerveModule(int moduleNumber, int driveMotorID, int angleMotorID, int ca
Constants.Swerve.CLOSED_LOOP_RAMP;
swerveDriveFXConfig.ClosedLoopRamps.VoltageClosedLoopRampPeriod =
Constants.Swerve.CLOSED_LOOP_RAMP;
mDriveMotor = new TalonFX(driveMotorID);
mDriveMotor = new TalonFX(driveMotorID, "canivore");
mDriveMotor.getConfigurator().apply(swerveDriveFXConfig);
mDriveMotor.getConfigurator().setPosition(0.0);
}
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,8 @@ public static final class Swerve {
/* Motor Inverts */
public static final InvertedValue DRIVE_MOTOR_INVERT =
InvertedValue.CounterClockwise_Positive;
public static final InvertedValue ANGLE_MOTOT_INVERT = InvertedValue.Clockwise_Positive;
public static final InvertedValue ANGLE_MOTOT_INVERT =
InvertedValue.CounterClockwise_Positive;

/* Angle Encoder Invert */
public static final SensorDirectionValue CAN_CODER_INVERT =
Expand Down

0 comments on commit 282eb24

Please sign in to comment.