Skip to content

Commit

Permalink
Adjust scoring pose w.r.t. the REEF tags
Browse files Browse the repository at this point in the history
	modified:   src/main/java/frc/robot/Constants.java
  • Loading branch information
tbowers7 committed Feb 21, 2025
1 parent 1c61a56 commit 994ded1
Showing 1 changed file with 6 additions and 4 deletions.
10 changes: 6 additions & 4 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -626,13 +626,15 @@ public static class CANandPowerPorts {

public static class DriveToPositionConstatnts {

// The robot is facing AWAY from the tag, so it's pose angle matches that of the tag
// The robot is facing AWAY from the tag, so its pose angle matches that of the tag.
// Scoring position has the bumpers 3" from the tag. Bumper-to-center distance is 18", ergo the
// robot pose is 21" from the tag.
public static Translation2d kLeftReefPost =
new Translation2d(Units.inchesToMeters(16.0), Units.inchesToMeters(-7.0));
new Translation2d(Units.inchesToMeters(21.0), Units.inchesToMeters(-6.5));
public static Translation2d kRightReefPost =
new Translation2d(Units.inchesToMeters(16.0), Units.inchesToMeters(+7.0));
new Translation2d(Units.inchesToMeters(21.0), Units.inchesToMeters(+6.5));
public static Translation2d kAlgaeGrab =
new Translation2d(Units.inchesToMeters(16.0), Units.inchesToMeters(0.0));
new Translation2d(Units.inchesToMeters(21.0), Units.inchesToMeters(0.0));

public static Pose2d k11r = new Pose2d(12.55, 2.71, Rotation2d.fromDegrees(-118.22));
public static Pose2d k11l = new Pose2d(12.22, 2.94, Rotation2d.fromDegrees(-120.6));
Expand Down

0 comments on commit 994ded1

Please sign in to comment.