Skip to content

Commit

Permalink
fix module offsets to make seedFieldRelative think intake side is the…
Browse files Browse the repository at this point in the history
… front
  • Loading branch information
IanShiii committed Aug 2, 2024
1 parent 5e8516a commit 0661322
Showing 1 changed file with 8 additions and 8 deletions.
16 changes: 8 additions & 8 deletions src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -251,31 +251,31 @@ public interface Drive {
}

public interface FrontRight {
boolean DRIVE_INVERTED = false;
boolean DRIVE_INVERTED = true;
String ID = "Front Right";
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromRotations(0.1318359375);
Translation2d MODULE_OFFSET = new Translation2d(LENGTH * +0.5, WIDTH * -0.5);
Translation2d MODULE_OFFSET = new Translation2d(LENGTH * -0.5, WIDTH * +0.5);
}

public interface FrontLeft {
boolean DRIVE_INVERTED = true;
boolean DRIVE_INVERTED = false;
String ID = "Front Left";
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromRotations(0.052734375);
Translation2d MODULE_OFFSET = new Translation2d(LENGTH * +0.5, WIDTH * +0.5);
Translation2d MODULE_OFFSET = new Translation2d(LENGTH * -0.5, WIDTH * -0.5);
}

public interface BackLeft {
boolean DRIVE_INVERTED = true;
boolean DRIVE_INVERTED = false;
String ID = "Back Left";
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromRotations(0.33154296875);
Translation2d MODULE_OFFSET = new Translation2d(LENGTH * -0.5, WIDTH * +0.5);
Translation2d MODULE_OFFSET = new Translation2d(LENGTH * +0.5, WIDTH * -0.5);
}

public interface BackRight {
boolean DRIVE_INVERTED = true;
boolean DRIVE_INVERTED = false;
String ID = "Back Right";
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromRotations(0.192138671875 + 0.5);
Translation2d MODULE_OFFSET = new Translation2d(LENGTH * -0.5, WIDTH * -0.5);
Translation2d MODULE_OFFSET = new Translation2d(LENGTH * +0.5, WIDTH * +0.5);
}

public interface Simulation {
Expand Down

0 comments on commit 0661322

Please sign in to comment.