diff --git a/src/main/java/frc4388/robot/commands/alignment/DriveToReef.java b/src/main/java/frc4388/robot/commands/alignment/DriveToReef.java index 6a11e85..8b6e407 100644 --- a/src/main/java/frc4388/robot/commands/alignment/DriveToReef.java +++ b/src/main/java/frc4388/robot/commands/alignment/DriveToReef.java @@ -1,5 +1,7 @@ package frc4388.robot.commands.alignment; +import org.littletonrobotics.junction.Logger; + import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.util.Units; @@ -60,6 +62,8 @@ public class DriveToReef extends Command { Units.inchesToMeters(AutoConstants.X_OFFSET_TRIM.get()), distance + Units.inchesToMeters(AutoConstants.Y_OFFSET_TRIM.get()) ); + + Logger.recordOutput("SwerveDrive", targetpos); } double xerr; diff --git a/src/main/java/frc4388/robot/constants/BuildConstants.java b/src/main/java/frc4388/robot/constants/BuildConstants.java index bfbf8d0..3ec7d30 100644 --- a/src/main/java/frc4388/robot/constants/BuildConstants.java +++ b/src/main/java/frc4388/robot/constants/BuildConstants.java @@ -7,12 +7,12 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "2025RidgeScape"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 182; - public static final String GIT_SHA = "88a4a00c29a2e2bdd9c14715807a8fd26499f9cf"; - public static final String GIT_DATE = "2025-10-10 20:22:54 MDT"; + public static final int GIT_REVISION = 183; + public static final String GIT_SHA = "4d20c5064279d9e0ac890c93e644e81dbabf929c"; + public static final String GIT_DATE = "2025-10-11 15:24:47 MDT"; public static final String GIT_BRANCH = "advantagekit"; - public static final String BUILD_DATE = "2025-10-11 14:12:35 MDT"; - public static final long BUILD_UNIX_TIME = 1760213555484L; + public static final String BUILD_DATE = "2025-10-11 16:46:07 MDT"; + public static final long BUILD_UNIX_TIME = 1760222767896L; public static final int DIRTY = 1; private BuildConstants(){} diff --git a/src/main/java/frc4388/robot/constants/Constants.java b/src/main/java/frc4388/robot/constants/Constants.java index 85cdaaa..22e0068 100644 --- a/src/main/java/frc4388/robot/constants/Constants.java +++ b/src/main/java/frc4388/robot/constants/Constants.java @@ -66,7 +66,7 @@ public final class Constants { public static final Trim ARM_OFFSET_TRIM = new Trim("ARM Offset Trim", -ElevatorConstants.COMPLETLY_TOP_ENDEFFECTOR, ElevatorConstants.COMPLETLY_TOP_ENDEFFECTOR, 1, 0); public static final double XY_TOLERANCE = 0.07; // Meters - public static final double ROT_TOLERANCE = 5; // Degrees + public static final double ROT_TOLERANCE = 3; // Degrees public static final double MIN_XY_PID_OUTPUT = 0.0; public static final double MIN_ROT_PID_OUTPUT = 0.0;