Reenable and fix flaky tests (#1837)

This commit is contained in:
Gold856
2025-07-10 00:16:44 -04:00
committed by GitHub
parent 78f57600cc
commit dbbb00f955
5 changed files with 20 additions and 22 deletions

View File

@@ -89,7 +89,7 @@ jobs:
- name: Gradle Build
run: ./gradlew photon-targeting:build photon-core:build photon-server:build -x check
- name: Gradle Tests
run: ./gradlew testHeadless -i --stacktrace
run: ./gradlew testHeadless --stacktrace
- name: Gradle Coverage
run: ./gradlew jacocoTestReport
- name: Publish Coverage Report
@@ -185,7 +185,7 @@ jobs:
distribution: temurin
architecture: ${{ matrix.architecture }}
- run: git fetch --tags --force
- run: ./gradlew photon-targeting:build photon-lib:build -i
- run: ./gradlew photon-targeting:build photon-lib:build
name: Build with Gradle
- run: ./gradlew photon-lib:publish photon-targeting:publish
name: Publish
@@ -226,7 +226,7 @@ jobs:
git config --global --add safe.directory /__w/photonvision/photonvision
- name: Build PhotonLib
# We don't need to run tests, since we specify only non-native platforms
run: ./gradlew photon-targeting:build photon-lib:build ${{ matrix.build-options }} -i -x test
run: ./gradlew photon-targeting:build photon-lib:build ${{ matrix.build-options }} -x test
- name: Publish
run: ./gradlew photon-lib:publish photon-targeting:publish ${{ matrix.build-options }}
env:

View File

@@ -28,7 +28,6 @@ import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
import static org.junit.jupiter.api.Assertions.assertFalse;
import static org.junit.jupiter.api.Assertions.assertNull;
import static org.junit.jupiter.api.Assertions.assertTrue;
import static org.junit.jupiter.api.Assumptions.assumeTrue;
import static org.photonvision.UnitTestUtils.waitForCondition;
import static org.photonvision.UnitTestUtils.waitForSequenceNumber;
@@ -48,7 +47,10 @@ import java.util.stream.Stream;
import org.junit.jupiter.api.AfterEach;
import org.junit.jupiter.api.BeforeAll;
import org.junit.jupiter.api.BeforeEach;
import org.junit.jupiter.api.MethodOrderer;
import org.junit.jupiter.api.Order;
import org.junit.jupiter.api.Test;
import org.junit.jupiter.api.TestMethodOrder;
import org.junit.jupiter.params.ParameterizedTest;
import org.junit.jupiter.params.provider.Arguments;
import org.junit.jupiter.params.provider.MethodSource;
@@ -60,6 +62,7 @@ import org.photonvision.simulation.PhotonCameraSim;
import org.photonvision.targeting.PhotonPipelineMetadata;
import org.photonvision.targeting.PhotonPipelineResult;
@TestMethodOrder(MethodOrderer.OrderAnnotation.class)
class PhotonCameraTest {
// A test-scoped, local-only NT instance
NetworkTableInstance inst = null;
@@ -76,6 +79,7 @@ class PhotonCameraTest {
HAL.initialize(500, 0);
inst = NetworkTableInstance.create();
assertTrue(inst.isValid());
inst.stopClient();
inst.stopServer();
inst.startLocal();
@@ -105,6 +109,7 @@ class PhotonCameraTest {
// Just a smoketest for dev use -- don't run by default
@Test
@Order(3)
public void testTimeSyncServerWithPhotonCamera() throws InterruptedException, IOException {
load_wpilib();
PhotonTargetingJniLoader.load();
@@ -189,12 +194,10 @@ class PhotonCameraTest {
* check
*/
@ParameterizedTest
@Order(2)
@MethodSource("testNtOffsets")
public void testRestartingRobotAndCoproc(
int robotStart, int coprocStart, int robotRestart, int coprocRestart) throws Throwable {
// See #1574 - test flakey, disabled until we address this
assumeTrue(false);
var robotNt = NetworkTableInstance.create();
var coprocNt = NetworkTableInstance.create();
@@ -304,9 +307,8 @@ class PhotonCameraTest {
}
@Test
@Order(1) // Alerts can't be reset, need to run this test first to have a clean slate
public void testAlerts() throws InterruptedException {
// See https://github.com/PhotonVision/photonvision/pull/1969. Flaky on Linux
assumeTrue(false);
// GIVEN a fresh NT instance
var cameraName = "foobar";

View File

@@ -29,7 +29,6 @@ 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.junit.jupiter.api.Assumptions.assumeTrue;
import static org.photonvision.UnitTestUtils.waitForSequenceNumber;
import edu.wpi.first.apriltag.AprilTag;
@@ -67,7 +66,6 @@ import org.photonvision.simulation.VisionSystemSim;
import org.photonvision.simulation.VisionTargetSim;
import org.photonvision.targeting.PhotonTrackedTarget;
// See #1574 - flakey on windows and also linux, so commenting out until we bump wpilib
class VisionSystemSimTest {
private static final double kRotDeltaDeg = 0.25;
@@ -85,9 +83,6 @@ class VisionSystemSimTest {
}
OpenCvLoader.forceStaticLoad();
// See #1574 - test flakey, disabled until we address this
assumeTrue(false);
}
@BeforeEach
@@ -200,7 +195,7 @@ class VisionSystemSimTest {
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(80));
visionSysSim.addVisionTargets(new VisionTargetSim(targetPose, new TargetModel(1.0, 3.0), 3));
visionSysSim.addVisionTargets(new VisionTargetSim(targetPose, new TargetModel(3.0, 3.0), 3));
var robotPose = new Pose2d(new Translation2d(5, 0), Rotation2d.fromDegrees(5));
visionSysSim.update(robotPose);
@@ -225,7 +220,7 @@ class VisionSystemSimTest {
var cameraSim = new PhotonCameraSim(camera);
visionSysSim.addCamera(cameraSim, robotToCamera);
cameraSim.prop.setCalibration(1234, 1234, Rotation2d.fromDegrees(80));
visionSysSim.addVisionTargets(new VisionTargetSim(targetPose, new TargetModel(1.0, 0.5), 1736));
visionSysSim.addVisionTargets(new VisionTargetSim(targetPose, new TargetModel(0.5, 0.5), 1736));
var robotPose = new Pose2d(new Translation2d(13.98, 0), Rotation2d.fromDegrees(5));
visionSysSim.update(robotPose);
@@ -250,7 +245,7 @@ class VisionSystemSimTest {
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(80));
cameraSim.setMinTargetAreaPixels(20.0);
visionSysSim.addVisionTargets(new VisionTargetSim(targetPose, new TargetModel(0.1, 0.025), 24));
visionSysSim.addVisionTargets(new VisionTargetSim(targetPose, new TargetModel(0.1, 0.1), 24));
var robotPose = new Pose2d(new Translation2d(12, 0), Rotation2d.fromDegrees(5));
visionSysSim.update(robotPose);
@@ -274,7 +269,7 @@ class VisionSystemSimTest {
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(80));
cameraSim.setMaxSightRange(10);
cameraSim.setMinTargetAreaPixels(1.0);
visionSysSim.addVisionTargets(new VisionTargetSim(targetPose, new TargetModel(1.0, 0.25), 78));
visionSysSim.addVisionTargets(new VisionTargetSim(targetPose, new TargetModel(1.0, 1), 78));
var robotPose = new Pose2d(new Translation2d(10, 0), Rotation2d.fromDegrees(5));
visionSysSim.update(robotPose);
@@ -322,7 +317,7 @@ class VisionSystemSimTest {
visionSysSim.addCamera(cameraSim, new Transform3d());
cameraSim.prop.setCalibration(640, 480, Rotation2d.fromDegrees(120));
cameraSim.setMinTargetAreaPixels(0.0);
visionSysSim.addVisionTargets(new VisionTargetSim(targetPose, new TargetModel(0.5, 0.5), 23));
visionSysSim.addVisionTargets(new VisionTargetSim(targetPose, new TargetModel(0.5, 0.5), 3));
// Transform is now robot -> camera
visionSysSim.adjustCamera(

View File

@@ -220,7 +220,6 @@ TEST_P(VisionSystemSimTestWithParamsTest, YawAngles) {
const frc::Pose3d targetPose{
{15.98_m, 0_m, 0_m},
frc::Rotation3d{0_deg, 0_deg, units::radian_t{3 * std::numbers::pi / 4}}};
frc::Pose2d robotPose{{10_m, 0_m}, frc::Rotation2d{GetParam() * -1.0}};
photon::VisionSystemSim visionSysSim{"Test"};
photon::PhotonCamera camera{"camera"};
photon::PhotonCameraSim cameraSim{&camera};
@@ -231,8 +230,8 @@ TEST_P(VisionSystemSimTestWithParamsTest, YawAngles) {
targetPose, photon::TargetModel{0.5_m, 0.5_m}, 3}});
// If the robot is rotated x deg (CCW+), the target yaw should be x deg (CW+)
robotPose =
frc::Pose2d{frc::Translation2d{10_m, 0_m}, frc::Rotation2d{GetParam()}};
frc::Pose2d robotPose{frc::Translation2d{10_m, 0_m},
frc::Rotation2d{GetParam()}};
visionSysSim.Update(robotPose);
const auto result = camera.GetLatestResult();

View File

@@ -113,7 +113,9 @@ test {
testLogging {
events "failed"
exceptionFormat "full"
showStandardStreams = true
}
forkEvery = 1
finalizedBy jacocoTestReport
}