Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 11 additions & 1 deletion src/main/java/org/team5924/frc2026/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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 {
Expand Down
3 changes: 3 additions & 0 deletions src/main/java/org/team5924/frc2026/RobotState.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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) {
Expand Down
Original file line number Diff line number Diff line change
@@ -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;
}
Comment on lines +13 to +16
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

⚠️ Potential issue | 🟡 Minor

Singleton can still be instantiated directly.

getInstance() implies singleton usage, but without a private constructor, other code can still call new FieldAwareness() and bypass this contract.

Proposed fix
 public class FieldAwareness {
   private static FieldAwareness instance;
 
+  private FieldAwareness() {}
+
 
   public static FieldAwareness getInstance() {
     if (instance == null) instance = new FieldAwareness();
     return instance;
   }
📝 Committable suggestion

‼️ IMPORTANT
Carefully review the code before committing. Ensure that it accurately replaces the highlighted code, contains no missing lines, and has no issues with indentation. Thoroughly test & benchmark the code to ensure it meets the requirements.

Suggested change
public static FieldAwareness getInstance() {
if (instance == null) instance = new FieldAwareness();
return instance;
}
public class FieldAwareness {
private static FieldAwareness instance;
private FieldAwareness() {}
public static FieldAwareness getInstance() {
if (instance == null) instance = new FieldAwareness();
return instance;
}
🤖 Prompt for AI Agents
Verify each finding against the current code and only fix it if needed.

In `@src/main/java/org/team5924/frc2026/subsystems/awareness/FieldAwareness.java`
around lines 13 - 16, The FieldAwareness class exposes getInstance() but the
constructor is not private so callers can bypass the singleton; make the
FieldAwareness constructor private (or package-private with controlled factory)
to enforce the singleton, keep the existing public static FieldAwareness
getInstance() as the sole accessor, and if desired add lazy-init thread-safety
(e.g., synchronized block or use an initialization-on-demand holder) to the
singleton pattern.


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++) {

}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand Down Expand Up @@ -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) {
Expand Down