Skip to content

Commit 695f5c3

Browse files
committed
fix: sim values as constants
1 parent 1bf8e01 commit 695f5c3

File tree

2 files changed

+8
-4
lines changed

2 files changed

+8
-4
lines changed

src/main/java/org/team1540/robot2024/Constants.java

+5
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,11 @@ public static class Vision {
9292
throw new RuntimeException(e);
9393
}
9494
}
95+
public static final int SIM_RES_WIDTH = 1280;
96+
public static final int SIM_RES_HEIGHT = 960;
97+
public static final Rotation2d SIM_DIAGONAL_FOV = Rotation2d.fromDegrees(100);
98+
public static final double SIM_FPS = 14.5;
99+
public static final double SIM_AVG_LATENCY_MS = 67.0;
95100
}
96101

97102
public static class Elevator {

src/main/java/org/team1540/robot2024/subsystems/vision/AprilTagVisionIOSim.java

+3-4
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,6 @@
22

33
import edu.wpi.first.math.geometry.Pose2d;
44
import edu.wpi.first.math.geometry.Pose3d;
5-
import edu.wpi.first.math.geometry.Rotation2d;
65
import edu.wpi.first.math.geometry.Transform3d;
76
import org.photonvision.EstimatedRobotPose;
87
import org.photonvision.PhotonCamera;
@@ -35,9 +34,9 @@ public AprilTagVisionIOSim(String name, Pose3d cameraOffsetMeters, Supplier<Pose
3534
visionSystemSim.addAprilTags(SIM_APRILTAG_LAYOUT);
3635

3736
SimCameraProperties cameraProps = new SimCameraProperties();
38-
cameraProps.setCalibration(1280, 960, Rotation2d.fromDegrees(100));
39-
cameraProps.setFPS(14.5);
40-
cameraProps.setAvgLatencyMs(67.0);
37+
cameraProps.setCalibration(SIM_RES_WIDTH, SIM_RES_HEIGHT, SIM_DIAGONAL_FOV);
38+
cameraProps.setFPS(SIM_FPS);
39+
cameraProps.setAvgLatencyMs(SIM_AVG_LATENCY_MS);
4140
camera = new PhotonCamera(name);
4241
cameraSim = new PhotonCameraSim(camera, cameraProps);
4342

0 commit comments

Comments
 (0)