mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
Assert that version checking won't throw on startup (#1512)
# Overview Previously if the coproc came up later, getProperty would return the string literal "null", which made us print the BFW. Add tests to make sure that we don't do that anymore by rebooting a sim coproc + robot in a combination of different orders.
This commit is contained in:
@@ -24,17 +24,30 @@
|
||||
|
||||
package org.photonvision;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.photonvision.UnitTestUtils.waitForCondition;
|
||||
import static org.photonvision.UnitTestUtils.waitForSequenceNumber;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.networktables.NetworkTablesJNI;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import java.io.IOException;
|
||||
import java.util.stream.Stream;
|
||||
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;
|
||||
import org.junit.jupiter.params.provider.MethodSource;
|
||||
import org.photonvision.common.dataflow.structures.Packet;
|
||||
import org.photonvision.jni.PhotonTargetingJniLoader;
|
||||
import org.photonvision.jni.TimeSyncClient;
|
||||
import org.photonvision.jni.WpilibLoader;
|
||||
import org.photonvision.simulation.PhotonCameraSim;
|
||||
import org.photonvision.targeting.PhotonPipelineResult;
|
||||
|
||||
class PhotonCameraTest {
|
||||
@@ -43,6 +56,16 @@ class PhotonCameraTest {
|
||||
WpilibLoader.loadLibraries();
|
||||
}
|
||||
|
||||
@BeforeEach
|
||||
public void setup() {
|
||||
HAL.initialize(500, 0);
|
||||
}
|
||||
|
||||
@AfterEach
|
||||
public void teardown() {
|
||||
HAL.shutdown();
|
||||
}
|
||||
|
||||
@Test
|
||||
public void testEmpty() {
|
||||
Assertions.assertDoesNotThrow(
|
||||
@@ -92,4 +115,119 @@ class PhotonCameraTest {
|
||||
|
||||
HAL.shutdown();
|
||||
}
|
||||
|
||||
private static Stream<Arguments> testNtOffsets() {
|
||||
return Stream.of(
|
||||
// various initializaiton orders
|
||||
Arguments.of(1, 10, 30, 30),
|
||||
Arguments.of(10, 2, 30, 30),
|
||||
Arguments.of(10, 10, 30, 30),
|
||||
// Reboot just the robot
|
||||
Arguments.of(1, 1, 10, 30),
|
||||
// Reboot just the coproc
|
||||
Arguments.of(1, 1, 30, 10));
|
||||
}
|
||||
|
||||
/**
|
||||
* Try starting client before server and vice-versa, making sure that we never fail the version
|
||||
* check
|
||||
*/
|
||||
@ParameterizedTest
|
||||
@MethodSource("testNtOffsets")
|
||||
public void testRestartingRobotAndCoproc(
|
||||
int robotStart, int coprocStart, int robotRestart, int coprocRestart) throws Throwable {
|
||||
var robotNt = NetworkTableInstance.create();
|
||||
var coprocNt = NetworkTableInstance.create();
|
||||
|
||||
robotNt.addLogger(10, 255, (it) -> System.out.println("ROBOT: " + it.logMessage.message));
|
||||
coprocNt.addLogger(10, 255, (it) -> System.out.println("CLIENT: " + it.logMessage.message));
|
||||
|
||||
TimeSyncClient tspClient = null;
|
||||
|
||||
var robotCamera = new PhotonCamera(robotNt, "MY_CAMERA");
|
||||
|
||||
// apparently need a PhotonCamera to hand down
|
||||
var fakePhotonCoprocCam = new PhotonCamera(coprocNt, "MY_CAMERA");
|
||||
var coprocSim = new PhotonCameraSim(fakePhotonCoprocCam);
|
||||
coprocSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(90));
|
||||
coprocSim.prop.setFPS(30);
|
||||
coprocSim.setMinTargetAreaPixels(20.0);
|
||||
|
||||
for (int i = 0; i < 20; i++) {
|
||||
int seq = i + 1;
|
||||
|
||||
if (i == coprocRestart) {
|
||||
System.out.println("Restarting coprocessor NT client");
|
||||
|
||||
fakePhotonCoprocCam.close();
|
||||
coprocNt.close();
|
||||
coprocNt = NetworkTableInstance.create();
|
||||
|
||||
coprocNt.addLogger(10, 255, (it) -> System.out.println("CLIENT: " + it.logMessage.message));
|
||||
|
||||
fakePhotonCoprocCam = new PhotonCamera(coprocNt, "MY_CAMERA");
|
||||
coprocSim = new PhotonCameraSim(fakePhotonCoprocCam);
|
||||
coprocSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(90));
|
||||
coprocSim.prop.setFPS(30);
|
||||
coprocSim.setMinTargetAreaPixels(20.0);
|
||||
}
|
||||
if (i == robotRestart) {
|
||||
System.out.println("Restarting robot NT server");
|
||||
|
||||
robotNt.close();
|
||||
robotNt = NetworkTableInstance.create();
|
||||
robotNt.addLogger(10, 255, (it) -> System.out.println("ROBOT: " + it.logMessage.message));
|
||||
robotCamera = new PhotonCamera(robotNt, "MY_CAMERA");
|
||||
}
|
||||
|
||||
if (i == coprocStart || i == coprocRestart) {
|
||||
coprocNt.setServer("127.0.0.1", 5940);
|
||||
coprocNt.startClient4("testClient");
|
||||
|
||||
// PhotonCamera makes a server by default - connect to it
|
||||
tspClient = new TimeSyncClient("127.0.0.1", 5810, 0.5);
|
||||
}
|
||||
|
||||
if (i == robotStart || i == robotRestart) {
|
||||
robotNt.startServer("networktables_random.json", "", 5941, 5940);
|
||||
}
|
||||
|
||||
Thread.sleep(100);
|
||||
|
||||
if (i == Math.max(coprocStart, robotStart)) {
|
||||
final var c = coprocNt;
|
||||
final var r = robotNt;
|
||||
waitForCondition("Coproc connection", () -> c.getConnections().length == 1);
|
||||
waitForCondition("Rio connection", () -> r.getConnections().length == 1);
|
||||
}
|
||||
|
||||
var result1 = new PhotonPipelineResult();
|
||||
result1.metadata.captureTimestampMicros = seq * 100;
|
||||
result1.metadata.publishTimestampMicros = seq * 150;
|
||||
result1.metadata.sequenceID = seq;
|
||||
if (tspClient != null) {
|
||||
result1.metadata.timeSinceLastPong = tspClient.getPingMetadata().timeSinceLastPong();
|
||||
} else {
|
||||
result1.metadata.timeSinceLastPong = Long.MAX_VALUE;
|
||||
}
|
||||
|
||||
coprocSim.submitProcessedFrame(result1, NetworkTablesJNI.now());
|
||||
coprocNt.flush();
|
||||
|
||||
if (i > robotStart && i > coprocStart) {
|
||||
var ret = waitForSequenceNumber(robotCamera, seq);
|
||||
System.out.println(ret);
|
||||
}
|
||||
|
||||
// force verifyVersion to do checks
|
||||
robotCamera.lastVersionCheckTime = -100;
|
||||
robotCamera.prevTimeSyncWarnTime = -100;
|
||||
assertDoesNotThrow(robotCamera::verifyVersion);
|
||||
}
|
||||
|
||||
coprocSim.close();
|
||||
coprocNt.close();
|
||||
robotNt.close();
|
||||
tspClient.stop();
|
||||
}
|
||||
}
|
||||
|
||||
74
photon-lib/src/test/java/org/photonvision/UnitTestUtils.java
Normal file
74
photon-lib/src/test/java/org/photonvision/UnitTestUtils.java
Normal file
@@ -0,0 +1,74 @@
|
||||
/*
|
||||
* MIT License
|
||||
*
|
||||
* Copyright (c) PhotonVision
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in all
|
||||
* copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
* SOFTWARE.
|
||||
*/
|
||||
|
||||
package org.photonvision;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.junit.jupiter.api.Assertions.fail;
|
||||
|
||||
import java.util.function.BooleanSupplier;
|
||||
import org.photonvision.targeting.PhotonPipelineResult;
|
||||
|
||||
public class UnitTestUtils {
|
||||
static void waitForCondition(String name, BooleanSupplier condition) {
|
||||
// wait up to 1 second for satisfaction
|
||||
for (int i = 0; i < 100; i++) {
|
||||
if (condition.getAsBoolean()) {
|
||||
System.out.println(name + " satisfied on iteration " + i);
|
||||
return;
|
||||
}
|
||||
|
||||
try {
|
||||
Thread.sleep(60);
|
||||
} catch (InterruptedException e) {
|
||||
e.printStackTrace();
|
||||
fail(e);
|
||||
}
|
||||
}
|
||||
throw new RuntimeException(name + " was never satisfied");
|
||||
}
|
||||
|
||||
static PhotonPipelineResult waitForSequenceNumber(PhotonCamera camera, int seq) {
|
||||
assertTrue(camera.heartbeatEntry.getTopic().getHandle() != 0);
|
||||
|
||||
System.out.println(
|
||||
"Waiting for seq=" + seq + " on " + camera.heartbeatEntry.getTopic().getName());
|
||||
// wait up to 1 second for a new result
|
||||
for (int i = 0; i < 100; i++) {
|
||||
var res = camera.getLatestResult();
|
||||
System.out.println(res);
|
||||
if (res.metadata.sequenceID == seq) {
|
||||
return res;
|
||||
}
|
||||
|
||||
try {
|
||||
Thread.sleep(60);
|
||||
} catch (InterruptedException e) {
|
||||
e.printStackTrace();
|
||||
fail(e);
|
||||
}
|
||||
}
|
||||
throw new RuntimeException("Never saw sequence number " + seq);
|
||||
}
|
||||
}
|
||||
@@ -28,6 +28,7 @@ import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.junit.jupiter.api.Assertions.fail;
|
||||
import static org.photonvision.UnitTestUtils.waitForSequenceNumber;
|
||||
|
||||
import edu.wpi.first.apriltag.AprilTag;
|
||||
import edu.wpi.first.apriltag.AprilTagFieldLayout;
|
||||
@@ -63,7 +64,6 @@ import org.photonvision.jni.WpilibLoader;
|
||||
import org.photonvision.simulation.PhotonCameraSim;
|
||||
import org.photonvision.simulation.VisionSystemSim;
|
||||
import org.photonvision.simulation.VisionTargetSim;
|
||||
import org.photonvision.targeting.PhotonPipelineResult;
|
||||
import org.photonvision.targeting.PhotonTrackedTarget;
|
||||
|
||||
class VisionSystemSimTest {
|
||||
@@ -110,27 +110,6 @@ class VisionSystemSimTest {
|
||||
HAL.shutdown();
|
||||
}
|
||||
|
||||
private PhotonPipelineResult waitForSequenceNumber(PhotonCamera camera, int seq) {
|
||||
assertTrue(camera.heartbeatEntry.getTopic().getHandle() != 0);
|
||||
|
||||
System.out.println(
|
||||
"Waiting for seq=" + seq + " on " + camera.heartbeatEntry.getTopic().getName());
|
||||
// wait up to 1 second for a new result
|
||||
for (int i = 0; i < 100; i++) {
|
||||
var res = camera.getLatestResult();
|
||||
if (res.metadata.sequenceID == seq) {
|
||||
return res;
|
||||
}
|
||||
|
||||
try {
|
||||
Thread.sleep(10);
|
||||
} catch (InterruptedException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
throw new RuntimeException("Never saw sequence number " + seq);
|
||||
}
|
||||
|
||||
@Test
|
||||
public void testEmpty() {
|
||||
Assertions.assertDoesNotThrow(
|
||||
@@ -247,7 +226,8 @@ class VisionSystemSimTest {
|
||||
|
||||
assertTrue(waitForSequenceNumber(camera, 1).hasTargets());
|
||||
|
||||
// Pitched back camera should mean target goes out of view below the robot as distance increases
|
||||
// Pitched back camera should mean target goes out of view below the robot as
|
||||
// distance increases
|
||||
robotPose = new Pose2d(new Translation2d(0, 0), Rotation2d.fromDegrees(5));
|
||||
visionSysSim.update(robotPose);
|
||||
|
||||
@@ -350,7 +330,8 @@ class VisionSystemSimTest {
|
||||
assertTrue(res.hasTargets());
|
||||
var tgt = res.getBestTarget();
|
||||
|
||||
// Since the camera is level with the target, a positive-upward point will mean the target is in
|
||||
// Since the camera is level with the target, a positive-upward point will mean
|
||||
// the target is in
|
||||
// the
|
||||
// lower half of the image
|
||||
// which should produce negative pitch.
|
||||
@@ -358,7 +339,8 @@ class VisionSystemSimTest {
|
||||
}
|
||||
|
||||
private static Stream<Arguments> testDistanceCalcArgs() {
|
||||
// Arbitrary and fairly random assortment of distances, camera pitches, and heights
|
||||
// Arbitrary and fairly random assortment of distances, camera pitches, and
|
||||
// heights
|
||||
return Stream.of(
|
||||
Arguments.of(5, -15.98, 0),
|
||||
Arguments.of(6, -15.98, 1),
|
||||
@@ -382,7 +364,8 @@ class VisionSystemSimTest {
|
||||
@ParameterizedTest
|
||||
@MethodSource("testDistanceCalcArgs")
|
||||
public void testDistanceCalc(double testDist, double testPitch, double testHeight) {
|
||||
// Assume dist along ground and tgt height the same. Iterate over other parameters.
|
||||
// Assume dist along ground and tgt height the same. Iterate over other
|
||||
// parameters.
|
||||
|
||||
final var targetPose =
|
||||
new Pose3d(new Translation3d(15.98, 0, 1), new Rotation3d(0, 0, Math.PI * 0.98));
|
||||
@@ -406,10 +389,13 @@ class VisionSystemSimTest {
|
||||
|
||||
visionSysSim.update(robotPose);
|
||||
|
||||
// Note that target 2d yaw/pitch accuracy is hindered by two factors in photonvision:
|
||||
// 1. These are calculated with the average of the minimum area rectangle, which does not
|
||||
// Note that target 2d yaw/pitch accuracy is hindered by two factors in
|
||||
// photonvision:
|
||||
// 1. These are calculated with the average of the minimum area rectangle, which
|
||||
// does not
|
||||
// actually find the target center because of perspective distortion.
|
||||
// 2. Yaw and pitch are calculated separately which gives incorrect pitch values.
|
||||
// 2. Yaw and pitch are calculated separately which gives incorrect pitch
|
||||
// values.
|
||||
|
||||
var res = waitForSequenceNumber(camera, 1);
|
||||
assertTrue(res.hasTargets());
|
||||
|
||||
Reference in New Issue
Block a user