Skip to content

Commit

Permalink
Update ports + recalibrate modules + remove redundant rate limits
Browse files Browse the repository at this point in the history
  • Loading branch information
anivanchen committed Jan 27, 2024
1 parent ae6197f commit 6856802
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 13 deletions.
6 changes: 3 additions & 3 deletions src/main/java/com/stuypulse/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -93,14 +93,14 @@ private void configureButtonBindings() {
.onFalse(new IntakeDeacquire())
.onFalse(new IntakeStop());

// driver.getLeftButton().whileTrue(new SwerveDriveToPose(new Pose2d(4, 5.5, new Rotation2d())));
driver.getBottomButton().whileTrue(new SwerveDriveToPose(new Pose2d(2, 5.5, new Rotation2d(Units.degreesToRadians(180)))));
// driver.getRightButton().whileTrue(new SwerveDriveToPose(new Pose2d(1.5, 5.5, new Rotation2d())));

// driver.getTopButton().whileTrue(new SwerveDriveWithAiming(Field.getFiducial(7).getPose().toPose2d(), driver));
driver.getTopButton().whileTrue(new SwerveDriveWithAiming(Field.getFiducial(7).getPose().toPose2d(), driver));
// driver.getBottomButton().whileTrue(new SwerveDriveWithAiming(Field.getFiducial(8).getPose().toPose2d(), driver));
driver.getLeftButton().whileTrue(new SwerveDriveToScore());
driver.getRightButton().whileTrue(new SwerveDriveDriveToScore(driver));
driver.getBottomButton().whileTrue(AutoBuilder.pathfindToPose(new Pose2d(), new PathConstraints(3, 4, Units.degreesToRadians(540), Units.degreesToRadians(720)), 0, 0));
// driver.getBottomButton().whileTrue(AutoBuilder.pathfindToPose(new Pose2d(), new PathConstraints(3, 4, Units.degreesToRadians(540), Units.degreesToRadians(720)), 0, 0));
}

/**************/
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/com/stuypulse/robot/constants/Cameras.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

public interface Cameras {

public static final CameraConfig DEFAULT_CAMERA = new CameraConfig("default",
public static final CameraConfig DEFAULT_CAMERA = new CameraConfig("samera1",
new Pose3d(-Units.inchesToMeters(12),
-Units.inchesToMeters(0),
+Units.inchesToMeters(5),
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/com/stuypulse/robot/constants/Ports.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,16 +17,16 @@ 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;
Expand All @@ -35,7 +35,7 @@ public interface FrontRight {
public interface FrontLeft {
int DRIVE = 16;
int TURN = 17;
int ENCODER = 3;
int ENCODER = 2;
}
}

Expand Down
10 changes: 5 additions & 5 deletions src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -79,25 +79,25 @@ public interface Motion {

public interface FrontRight {
String ID = "Front Right";
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(208.212891 + 180);
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(154.511719 + 180);
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(65.566406 + 180);
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(47.197266 + 180);
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(-2.02184 + 180);
Translation2d MODULE_OFFSET = new Translation2d(WIDTH * -0.5, LENGTH * -0.5);
}

Expand Down Expand Up @@ -130,7 +130,7 @@ public interface Turn {
SmartNumber RC = new SmartNumber("Driver Settings/Turn/RC", 0.1);
SmartNumber POWER = new SmartNumber("Driver Settings/Turn/Power", 2);

SmartNumber MAX_TELEOP_TURNING = new SmartNumber("Driver Settings/Turn/Max Turning", 6.0);
SmartNumber MAX_TELEOP_TURNING = new SmartNumber("Driver Settings/Turn/Max Turning", 6.28);

public interface GyroFeedback {
SmartBoolean GYRO_FEEDBACK_ENABLED = new SmartBoolean("Driver Settings/Gyro Feedback/Enabled", true);
Expand Down

0 comments on commit 6856802

Please sign in to comment.