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:
Matt
2024-11-01 20:50:21 -07:00
committed by GitHub
parent 5e1a93950e
commit 7a4ea3dd56
13 changed files with 305 additions and 67 deletions

View File

@@ -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();
}
}