Skip to content

Commit

Permalink
Add cancoders + update ports
Browse files Browse the repository at this point in the history
  • Loading branch information
anivanchen committed Jan 27, 2024
1 parent 619c3eb commit cc11727
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 16 deletions.
12 changes: 6 additions & 6 deletions src/main/java/com/stuypulse/robot/constants/Ports.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,25 +40,25 @@ public interface Swerve {
public interface BackLeft {
int DRIVE = 10;
int TURN = 11;
int ENCODER = 2;
int ENCODER = 3;
}

public interface BackRight {
public interface BackRight {
int DRIVE = 12;
int TURN = 13;
int ENCODER = 1;
}

public interface FrontRight {
public interface FrontRight {
int DRIVE = 14;
int TURN = 15;
int ENCODER = 4;
}

public interface FrontLeft {
int DRIVE = 16;
int TURN = 17;
int ENCODER = 3;
int ENCODER = 2;
}
}
}
18 changes: 9 additions & 9 deletions src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ public enum Mechanism {
DOUBLE_JOINTED_ARM_JOINT_TWO
}

public Mechanism ROUTINE = Mechanism.FLYWHEEL;
public Mechanism ROUTINE = Mechanism.SWERVE_DRIVE;
}

public interface Flywheel {
Expand Down Expand Up @@ -116,9 +116,9 @@ public interface Drive {
SmartNumber kI = new SmartNumber("Swerve/Drive/kI", 0.0);
SmartNumber kD = new SmartNumber("Swerve/Drive/kD", 0.0);

SmartNumber kS = new SmartNumber("Swerve/Drive/kS", 0.36493);
SmartNumber kV = new SmartNumber("Swerve/Drive/kV", 2.448);
SmartNumber kA = new SmartNumber("Swerve/Drive/kA", 0.16408);
SmartNumber kS = new SmartNumber("Swerve/Drive/kS", 0.2021);
SmartNumber kV = new SmartNumber("Swerve/Drive/kV", 0.0017542);
SmartNumber kA = new SmartNumber("Swerve/Drive/kA", 0.00013496);
}

public interface Motion {
Expand All @@ -129,25 +129,25 @@ public interface Motion {

public interface FrontRight {
String ID = "Front Right";
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(-153.984375);
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(-153.632812 + 180);
Translation2d MODULE_OFFSET = new Translation2d(WIDTH * +0.5, LENGTH * -0.5);
}

public interface FrontLeft {
String ID = "Front Left";
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(149.326172);
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(147.919922 + 180);
Translation2d MODULE_OFFSET = new Translation2d(WIDTH * +0.5, LENGTH * +0.5);
}

public interface BackLeft {
String ID = "Back Left";
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(71.191406);
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(73.125 + 180);
Translation2d MODULE_OFFSET = new Translation2d(WIDTH * -0.5, LENGTH * +0.5);
}

public interface BackRight {
String ID = "Back Right";
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(45.351562);
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(-2.02184 + 180);
Translation2d MODULE_OFFSET = new Translation2d(WIDTH * -0.5, LENGTH * -0.5);
}

Expand All @@ -157,7 +157,7 @@ public interface Drive {
double WHEEL_CIRCUMFERENCE = WHEEL_DIAMETER * Math.PI;
double GEAR_RATIO = 1.0 / 6.12;

double POSITION_CONVERSION = WHEEL_CIRCUMFERENCE * GEAR_RATIO;
double POSITION_CONVERSION = WHEEL_CIRCUMFERENCE * GEAR_RATIO / 1000;
double VELOCITY_CONVERSION = POSITION_CONVERSION / 60.0;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,6 @@ public SwerveModule(String id, Rotation2d angleOffset, int turnID, int driveID,
driveController =
new PIDController(Drive.kP, Drive.kI, Drive.kD)
.add(new MotorFeedforward(Drive.kS, Drive.kV, Drive.kA).velocity());
;

turnMotor = new CANSparkMax(turnID, MotorType.kBrushless);
turnMotor.setIdleMode(IdleMode.kBrake);
Expand Down

0 comments on commit cc11727

Please sign in to comment.