Skip to content

Commit

Permalink
Make forwards intake side
Browse files Browse the repository at this point in the history
  • Loading branch information
BenG49 committed Jan 23, 2024
1 parent ea2b8cb commit 6709023
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 16 deletions.
8 changes: 4 additions & 4 deletions src/main/java/com/stuypulse/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -74,10 +74,10 @@ private void configureDefaultCommands() {
/***************/

private void configureButtonBindings() {
driver.getDPadUp().onTrue(new SwerveDriveResetHeading(Rotation2d.fromDegrees(180)));
driver.getDPadDown().onTrue(new SwerveDriveResetHeading(Rotation2d.fromDegrees(0)));
driver.getDPadLeft().onTrue(new SwerveDriveResetHeading(Rotation2d.fromDegrees(270)));
driver.getDPadRight().onTrue(new SwerveDriveResetHeading(Rotation2d.fromDegrees(90)));
driver.getDPadUp().onTrue(new SwerveDriveResetHeading(Rotation2d.fromDegrees(0)));
driver.getDPadDown().onTrue(new SwerveDriveResetHeading(Rotation2d.fromDegrees(180)));
driver.getDPadLeft().onTrue(new SwerveDriveResetHeading(Rotation2d.fromDegrees(90)));
driver.getDPadRight().onTrue(new SwerveDriveResetHeading(Rotation2d.fromDegrees(270)));

driver.getRightTriggerButton()
.whileTrue(new IntakeAcquire())
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 @@ -14,25 +14,25 @@ public interface Gamepad {
}

public interface Swerve {
public interface FrontRight {
public interface BackLeft {
int DRIVE = 10;
int TURN = 11;
int ENCODER = 2;
}

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

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

public interface BackRight {
public interface FrontLeft {
int DRIVE = 16;
int TURN = 17;
int ENCODER = 3;
Expand Down
12 changes: 4 additions & 8 deletions src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -80,29 +80,25 @@ public interface Motion {

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

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

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

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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,8 @@ public void periodic() {

odometryPose2D.setPose(odometry.getPoseMeters());
estimatorPose2D.setPose(estimator.getEstimatedPosition());

updateTelemetry();
}

@Override
Expand Down

0 comments on commit 6709023

Please sign in to comment.