Skip to content

Commit

Permalink
fix: sim values as constants
Browse files Browse the repository at this point in the history
  • Loading branch information
mimizh2418 committed Feb 1, 2024
1 parent 1bf8e01 commit 695f5c3
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 4 deletions.
5 changes: 5 additions & 0 deletions src/main/java/org/team1540/robot2024/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,11 @@ public static class Vision {
throw new RuntimeException(e);
}
}
public static final int SIM_RES_WIDTH = 1280;
public static final int SIM_RES_HEIGHT = 960;
public static final Rotation2d SIM_DIAGONAL_FOV = Rotation2d.fromDegrees(100);
public static final double SIM_FPS = 14.5;
public static final double SIM_AVG_LATENCY_MS = 67.0;
}

public static class Elevator {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform3d;
import org.photonvision.EstimatedRobotPose;
import org.photonvision.PhotonCamera;
Expand Down Expand Up @@ -35,9 +34,9 @@ public AprilTagVisionIOSim(String name, Pose3d cameraOffsetMeters, Supplier<Pose
visionSystemSim.addAprilTags(SIM_APRILTAG_LAYOUT);

SimCameraProperties cameraProps = new SimCameraProperties();
cameraProps.setCalibration(1280, 960, Rotation2d.fromDegrees(100));
cameraProps.setFPS(14.5);
cameraProps.setAvgLatencyMs(67.0);
cameraProps.setCalibration(SIM_RES_WIDTH, SIM_RES_HEIGHT, SIM_DIAGONAL_FOV);
cameraProps.setFPS(SIM_FPS);
cameraProps.setAvgLatencyMs(SIM_AVG_LATENCY_MS);
camera = new PhotonCamera(name);
cameraSim = new PhotonCameraSim(camera, cameraProps);

Expand Down

0 comments on commit 695f5c3

Please sign in to comment.