From 994ded1e2989690990a34ec559834897230fab9d Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Thu, 20 Feb 2025 17:40:12 -0700 Subject: [PATCH] Adjust scoring pose w.r.t. the REEF tags modified: src/main/java/frc/robot/Constants.java --- src/main/java/frc/robot/Constants.java | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index ddc43f9..e803928 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -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));