diff --git a/src/main/java/org/team5924/frc2026/Constants.java b/src/main/java/org/team5924/frc2026/Constants.java index 536c0ea6..fa17baa5 100644 --- a/src/main/java/org/team5924/frc2026/Constants.java +++ b/src/main/java/org/team5924/frc2026/Constants.java @@ -30,7 +30,7 @@ import com.ctre.phoenix6.signals.SensorDirectionValue; import edu.wpi.first.math.util.Units; - +import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.apriltag.AprilTagFieldLayout; @@ -80,6 +80,16 @@ public final class Field { public static final double CENTER_X = WIDTH / 2; public static final double CENTER_Y = LENGTH / 2; public static final double HUB_X = CENTER_X - 143.50; + + public static final double TRENCH_X_ALLIANCE = Units.inchesToMeters(182.11); + public static final double TRENCH_X_OPPONENT = Units.inchesToMeters(469.11); + public static final double TRENCH_Y_LEFT = Units.inchesToMeters(292.718); + public static final double TRENCH_Y_RIGHT = Units.inchesToMeters(25.7); + public static final Translation2d[] TRENCH_TRANSLATIONS = { + new Translation2d(TRENCH_X_ALLIANCE, TRENCH_Y_RIGHT), + new Translation2d(TRENCH_X_ALLIANCE, TRENCH_Y_LEFT), + new Translation2d(TRENCH_X_OPPONENT, TRENCH_Y_RIGHT), + new Translation2d(TRENCH_X_OPPONENT, TRENCH_Y_LEFT)}; } public final class GenericRollerSystem { diff --git a/src/main/java/org/team5924/frc2026/RobotState.java b/src/main/java/org/team5924/frc2026/RobotState.java index 20a4e9ea..9a8aff1b 100644 --- a/src/main/java/org/team5924/frc2026/RobotState.java +++ b/src/main/java/org/team5924/frc2026/RobotState.java @@ -18,6 +18,7 @@ import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.kinematics.ChassisSpeeds; import lombok.Getter; import lombok.Setter; import org.littletonrobotics.junction.AutoLogOutput; @@ -52,6 +53,8 @@ public static double getTime() { @Setter private Pose2d odometryPose = new Pose2d(); + @Getter @Setter private ChassisSpeeds robotChassisSpeeds = new ChassisSpeeds(); + @Getter @Setter @AutoLogOutput private Pose2d estimatedPose = Pose2d.kZero; public void resetPose(Pose2d pose) { diff --git a/src/main/java/org/team5924/frc2026/subsystems/awareness/FieldAwareness.java b/src/main/java/org/team5924/frc2026/subsystems/awareness/FieldAwareness.java new file mode 100644 index 00000000..f34f20ea --- /dev/null +++ b/src/main/java/org/team5924/frc2026/subsystems/awareness/FieldAwareness.java @@ -0,0 +1,37 @@ +package org.team5924.frc2026.subsystems.awareness; + +import org.team5924.frc2026.Constants; +import org.team5924.frc2026.RobotState; + +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.kinematics.ChassisSpeeds; + +public class FieldAwareness { + private static FieldAwareness instance; + + + public static FieldAwareness getInstance() { + if (instance == null) instance = new FieldAwareness(); + return instance; + } + + private Translation2d[] getOffsetsToTrenches(){ + Translation2d[] offsets = new Translation2d[4]; + Translation2d robotPosition = RobotState.getInstance().getOdometryPose().getTranslation(); + + for (int i = 0; i < 4; i++) { + offsets[i] = Constants.Field.TRENCH_TRANSLATIONS[i].minus(robotPosition); + } + + return offsets; + } + + private void tdfyguijoi() { // TODO: name later + ChassisSpeeds speeds = RobotState.getInstance().getRobotChassisSpeeds(); + Translation2d velocity = new Translation2d(speeds.vxMetersPerSecond, speeds.vyMetersPerSecond); + + for (int i = 0; i < 4; i++) { + + } + } +} diff --git a/src/main/java/org/team5924/frc2026/subsystems/drive/Drive.java b/src/main/java/org/team5924/frc2026/subsystems/drive/Drive.java index 743bb44a..17a99597 100644 --- a/src/main/java/org/team5924/frc2026/subsystems/drive/Drive.java +++ b/src/main/java/org/team5924/frc2026/subsystems/drive/Drive.java @@ -207,7 +207,7 @@ public Drive( // setpointGenerator = new SwerveSetpointGenerator(kinematics, // getModuleTranslations()); - // previousSetpoint = new SwerveSetpoint(getChassisSpeeds(), getModuleStates()); + // previousSetpoint = new SwerveSetpoint(getSpeeds(), getModuleStates()); SmartDashboard.putData( "Swerve Drive", @@ -305,6 +305,7 @@ public void periodic() { // Update RobotState RobotState.getInstance().setOdometryPose(getPose()); RobotState.getInstance().setEstimatedPose(getPose()); + RobotState.getInstance().setRobotChassisSpeeds(getChassisSpeeds()); // prevents error spam if (!gyroInputs.connected && wasGyroConnected) {