Skip to content

Commit

Permalink
ahh?
Browse files Browse the repository at this point in the history
  • Loading branch information
Juniormunk committed Oct 31, 2024
1 parent a15564a commit 9d86a3d
Showing 1 changed file with 27 additions and 17 deletions.
44 changes: 27 additions & 17 deletions photon-lib/src/test/java/org/photonvision/VisionSystemSimTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,10 @@
import java.util.List;
import java.util.stream.Stream;
import org.junit.jupiter.api.AfterAll;
import org.junit.jupiter.api.AfterEach;
import org.junit.jupiter.api.Assertions;
import org.junit.jupiter.api.BeforeAll;
import org.junit.jupiter.api.BeforeEach;
import org.junit.jupiter.api.Test;
import org.junit.jupiter.params.ParameterizedTest;
import org.junit.jupiter.params.provider.Arguments;
Expand All @@ -65,6 +67,8 @@
class VisionSystemSimTest {
private static final double kTrlDelta = 0.005;
private static final double kRotDeltaDeg = 0.25;
private static NetworkTableInstance inst;


private PhotonPipelineResult waitForSequenceNumber(PhotonCamera camera, int seq) {
assertTrue(camera.heartbeatEntry.getTopic().getHandle() != 0);
Expand Down Expand Up @@ -108,19 +112,25 @@ public static void setUp() {
e.printStackTrace();
fail(e);
}
PhotonCamera.setVersionCheckEnabled(false);

// NT live for debug purposes
NetworkTableInstance.getDefault().stopClient();
NetworkTableInstance.getDefault().stopServer();
NetworkTableInstance.getDefault().startServer();

// No version check for testing
PhotonCamera.setVersionCheckEnabled(false);
}

@AfterAll
public static void shutDown() {}

@BeforeEach
public void init() {
// NT live for debug purposes
inst = NetworkTableInstance.create();
inst.startServer();
}
@AfterEach()
public void tearDown() {
inst.stopServer();
inst.stopClient();
}

// @ParameterizedTest
// @ValueSource(doubles = {5, 10, 15, 20, 25, 30})
// public void testDistanceAligned(double dist) {
Expand All @@ -143,7 +153,7 @@ public void testVisibilityCupidShuffle() {
final var targetPose =
new Pose3d(new Translation3d(15.98, 0, 2), new Rotation3d(0, 0, Math.PI));
var visionSysSim = new VisionSystemSim("Test");
var camera = new PhotonCamera("camera");
var camera = new PhotonCamera(inst,"camera");
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(80));
Expand Down Expand Up @@ -212,7 +222,7 @@ public void testNotVisibleVert1() {
final var targetPose =
new Pose3d(new Translation3d(15.98, 0, 1), new Rotation3d(0, 0, Math.PI));
var visionSysSim = new VisionSystemSim("Test");
var camera = new PhotonCamera("camera");
var camera = new PhotonCamera(inst,"camera");
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(80));
Expand All @@ -237,7 +247,7 @@ public void testNotVisibleVert2() {
var robotToCamera =
new Transform3d(new Translation3d(0, 0, 1), new Rotation3d(0, -Math.PI / 4, 0));
var visionSysSim = new VisionSystemSim("Test");
var camera = new PhotonCamera("camera");
var camera = new PhotonCamera(inst,"camera");
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, robotToCamera);
cameraSim.prop.setCalibration(1234, 1234, Rotation2d.fromDegrees(80));
Expand All @@ -260,7 +270,7 @@ public void testNotVisibleTgtSize() {
final var targetPose =
new Pose3d(new Translation3d(15.98, 0, 1), new Rotation3d(0, 0, Math.PI));
var visionSysSim = new VisionSystemSim("Test");
var camera = new PhotonCamera("camera");
var camera = new PhotonCamera(inst,"camera");
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(80));
Expand All @@ -283,7 +293,7 @@ public void testNotVisibleTooFarForLEDs() {
final var targetPose =
new Pose3d(new Translation3d(15.98, 0, 1), new Rotation3d(0, 0, Math.PI));
var visionSysSim = new VisionSystemSim("Test");
var camera = new PhotonCamera("camera");
var camera = new PhotonCamera(inst,"camera");
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(80));
Expand All @@ -308,7 +318,7 @@ public void testYawAngles(double testYaw) throws InterruptedException {
final var targetPose =
new Pose3d(new Translation3d(15.98, 0, 1), new Rotation3d(0, 0, 3 * Math.PI / 4));
var visionSysSim = new VisionSystemSim("Test");
var camera = new PhotonCamera("camera");
var camera = new PhotonCamera(inst,"camera");
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(80));
Expand All @@ -333,7 +343,7 @@ public void testPitchAngles(double testPitch) throws InterruptedException {
new Pose3d(new Translation3d(15.98, 0, 0), new Rotation3d(0, 0, 3 * Math.PI / 4));
final var robotPose = new Pose2d(new Translation2d(10, 0), new Rotation2d(0));
var visionSysSim = new VisionSystemSim("Test");
var camera = new PhotonCamera("camera");
var camera = new PhotonCamera(inst,"camera");
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(120));
Expand Down Expand Up @@ -398,7 +408,7 @@ public void testDistanceCalc(double testDist, double testPitch, double testHeigh
var visionSysSim =
new VisionSystemSim(
"absurdlylongnamewhichshouldneveractuallyhappenbuteehwelltestitanywaysohowsyourdaygoingihopegoodhaveagreatrestofyourlife!");
var camera = new PhotonCamera("camera");
var camera = new PhotonCamera(inst,"camera");
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(160));
Expand Down Expand Up @@ -439,7 +449,7 @@ public void testMultipleTargets() {
new Pose3d(new Translation3d(15.98, -2, 0), new Rotation3d(0, 0, Math.PI));

var visionSysSim = new VisionSystemSim("Test");
var camera = new PhotonCamera("camera");
var camera = new PhotonCamera(inst,"camera");
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(80));
Expand Down Expand Up @@ -526,7 +536,7 @@ public void testMultipleTargets() {
@Test
public void testPoseEstimation() {
var visionSysSim = new VisionSystemSim("Test");
var camera = new PhotonCamera("camera");
var camera = new PhotonCamera(inst,"camera");
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(90));
Expand Down

0 comments on commit 9d86a3d

Please sign in to comment.