mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
Fix vendordep including all wpilib libraries (#1155)
* Fix vendordep including all wpilib libraries. Without this fix, users were consuming a massively oversized .jar
This commit is contained in:
@@ -26,31 +26,23 @@ package org.photonvision;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.*;
|
||||
|
||||
import edu.wpi.first.apriltag.jni.AprilTagJNI;
|
||||
import edu.wpi.first.cscore.CameraServerCvJNI;
|
||||
import edu.wpi.first.cscore.CameraServerJNI;
|
||||
import edu.wpi.first.hal.JNIWrapper;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.math.geometry.Pose3d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Rotation3d;
|
||||
import edu.wpi.first.math.geometry.Transform3d;
|
||||
import edu.wpi.first.math.geometry.Translation3d;
|
||||
import edu.wpi.first.net.WPINetJNI;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.networktables.NetworkTablesJNI;
|
||||
import edu.wpi.first.util.CombinedRuntimeLoader;
|
||||
import edu.wpi.first.util.WPIUtilJNI;
|
||||
import java.io.IOException;
|
||||
import java.util.List;
|
||||
import org.junit.jupiter.api.BeforeAll;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.opencv.core.Core;
|
||||
import org.photonvision.estimation.CameraTargetRelation;
|
||||
import org.photonvision.estimation.OpenCVHelp;
|
||||
import org.photonvision.estimation.RotTrlTransform3d;
|
||||
import org.photonvision.estimation.TargetModel;
|
||||
import org.photonvision.simulation.SimCameraProperties;
|
||||
import org.photonvision.simulation.VisionSystemSim;
|
||||
import org.photonvision.simulation.VisionTargetSim;
|
||||
|
||||
public class OpenCVTest {
|
||||
@@ -84,28 +76,8 @@ public class OpenCVTest {
|
||||
private static final SimCameraProperties prop = new SimCameraProperties();
|
||||
|
||||
@BeforeAll
|
||||
public static void setUp() {
|
||||
JNIWrapper.Helper.setExtractOnStaticLoad(false);
|
||||
WPIUtilJNI.Helper.setExtractOnStaticLoad(false);
|
||||
NetworkTablesJNI.Helper.setExtractOnStaticLoad(false);
|
||||
WPINetJNI.Helper.setExtractOnStaticLoad(false);
|
||||
CameraServerJNI.Helper.setExtractOnStaticLoad(false);
|
||||
CameraServerCvJNI.Helper.setExtractOnStaticLoad(false);
|
||||
AprilTagJNI.Helper.setExtractOnStaticLoad(false);
|
||||
|
||||
try {
|
||||
CombinedRuntimeLoader.loadLibraries(
|
||||
VisionSystemSim.class,
|
||||
"wpiutiljni",
|
||||
"ntcorejni",
|
||||
"wpinetjni",
|
||||
"wpiHaljni",
|
||||
Core.NATIVE_LIBRARY_NAME,
|
||||
"cscorejni",
|
||||
"apriltagjni");
|
||||
} catch (Exception e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
public static void setUp() throws IOException {
|
||||
CameraServerCvJNI.forceLoad();
|
||||
|
||||
// NT live for debug purposes
|
||||
NetworkTableInstance.getDefault().startServer();
|
||||
|
||||
@@ -30,17 +30,11 @@ import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.apriltag.AprilTag;
|
||||
import edu.wpi.first.apriltag.AprilTagFieldLayout;
|
||||
import edu.wpi.first.hal.JNIWrapper;
|
||||
import edu.wpi.first.math.geometry.Pose3d;
|
||||
import edu.wpi.first.math.geometry.Rotation3d;
|
||||
import edu.wpi.first.math.geometry.Transform3d;
|
||||
import edu.wpi.first.math.geometry.Translation3d;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.net.WPINetJNI;
|
||||
import edu.wpi.first.networktables.NetworkTablesJNI;
|
||||
import edu.wpi.first.util.CombinedRuntimeLoader;
|
||||
import edu.wpi.first.util.WPIUtilJNI;
|
||||
import java.io.IOException;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import java.util.Optional;
|
||||
@@ -56,19 +50,6 @@ class PhotonPoseEstimatorTest {
|
||||
|
||||
@BeforeAll
|
||||
public static void init() {
|
||||
JNIWrapper.Helper.setExtractOnStaticLoad(false);
|
||||
WPIUtilJNI.Helper.setExtractOnStaticLoad(false);
|
||||
NetworkTablesJNI.Helper.setExtractOnStaticLoad(false);
|
||||
WPINetJNI.Helper.setExtractOnStaticLoad(false);
|
||||
|
||||
try {
|
||||
CombinedRuntimeLoader.loadLibraries(
|
||||
PhotonPoseEstimatorTest.class, "wpiutiljni", "ntcorejni", "wpinetjni", "wpiHaljni");
|
||||
} catch (IOException e) {
|
||||
// TODO Auto-generated catch block
|
||||
e.printStackTrace();
|
||||
}
|
||||
|
||||
List<AprilTag> tagList = new ArrayList<>(2);
|
||||
tagList.add(new AprilTag(0, new Pose3d(3, 3, 3, new Rotation3d())));
|
||||
tagList.add(new AprilTag(1, new Pose3d(5, 5, 5, new Rotation3d())));
|
||||
|
||||
@@ -30,10 +30,6 @@ import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.apriltag.AprilTag;
|
||||
import edu.wpi.first.apriltag.AprilTagFieldLayout;
|
||||
import edu.wpi.first.apriltag.jni.AprilTagJNI;
|
||||
import edu.wpi.first.cscore.CameraServerCvJNI;
|
||||
import edu.wpi.first.cscore.CameraServerJNI;
|
||||
import edu.wpi.first.hal.JNIWrapper;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Pose3d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
@@ -42,11 +38,7 @@ import edu.wpi.first.math.geometry.Transform3d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.geometry.Translation3d;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.net.WPINetJNI;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.networktables.NetworkTablesJNI;
|
||||
import edu.wpi.first.util.CombinedRuntimeLoader;
|
||||
import edu.wpi.first.util.WPIUtilJNI;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import java.util.stream.Stream;
|
||||
@@ -58,7 +50,6 @@ import org.junit.jupiter.params.ParameterizedTest;
|
||||
import org.junit.jupiter.params.provider.Arguments;
|
||||
import org.junit.jupiter.params.provider.MethodSource;
|
||||
import org.junit.jupiter.params.provider.ValueSource;
|
||||
import org.opencv.core.Core;
|
||||
import org.photonvision.estimation.TargetModel;
|
||||
import org.photonvision.estimation.VisionEstimation;
|
||||
import org.photonvision.simulation.PhotonCameraSim;
|
||||
@@ -85,28 +76,6 @@ class VisionSystemSimTest {
|
||||
|
||||
@BeforeAll
|
||||
public static void setUp() {
|
||||
JNIWrapper.Helper.setExtractOnStaticLoad(false);
|
||||
WPIUtilJNI.Helper.setExtractOnStaticLoad(false);
|
||||
NetworkTablesJNI.Helper.setExtractOnStaticLoad(false);
|
||||
WPINetJNI.Helper.setExtractOnStaticLoad(false);
|
||||
CameraServerJNI.Helper.setExtractOnStaticLoad(false);
|
||||
CameraServerCvJNI.Helper.setExtractOnStaticLoad(false);
|
||||
AprilTagJNI.Helper.setExtractOnStaticLoad(false);
|
||||
|
||||
try {
|
||||
CombinedRuntimeLoader.loadLibraries(
|
||||
VisionSystemSim.class,
|
||||
"wpiutiljni",
|
||||
"ntcorejni",
|
||||
"wpinetjni",
|
||||
"wpiHaljni",
|
||||
Core.NATIVE_LIBRARY_NAME,
|
||||
"cscorejni",
|
||||
"apriltagjni");
|
||||
} catch (Exception e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
|
||||
// NT live for debug purposes
|
||||
NetworkTableInstance.getDefault().startServer();
|
||||
|
||||
|
||||
@@ -26,14 +26,8 @@ package org.photonvision.estimation;
|
||||
|
||||
import edu.wpi.first.apriltag.AprilTagFieldLayout;
|
||||
import edu.wpi.first.apriltag.AprilTagFields;
|
||||
import edu.wpi.first.cscore.CameraServerCvJNI;
|
||||
import edu.wpi.first.hal.JNIWrapper;
|
||||
import edu.wpi.first.math.geometry.Transform3d;
|
||||
import edu.wpi.first.net.WPINetJNI;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.networktables.NetworkTablesJNI;
|
||||
import edu.wpi.first.util.CombinedRuntimeLoader;
|
||||
import edu.wpi.first.util.WPIUtilJNI;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import java.io.IOException;
|
||||
@@ -44,25 +38,6 @@ import org.photonvision.PhotonPoseEstimator;
|
||||
public class ApriltagWorkbenchTest {
|
||||
@BeforeAll
|
||||
public static void setUp() {
|
||||
JNIWrapper.Helper.setExtractOnStaticLoad(false);
|
||||
WPIUtilJNI.Helper.setExtractOnStaticLoad(false);
|
||||
NetworkTablesJNI.Helper.setExtractOnStaticLoad(false);
|
||||
WPINetJNI.Helper.setExtractOnStaticLoad(false);
|
||||
CameraServerCvJNI.Helper.setExtractOnStaticLoad(false);
|
||||
|
||||
try {
|
||||
CombinedRuntimeLoader.loadLibraries(
|
||||
ApriltagWorkbenchTest.class,
|
||||
"wpiutiljni",
|
||||
"ntcorejni",
|
||||
"wpinetjni",
|
||||
"wpiHaljni",
|
||||
"cscorejnicvstatic");
|
||||
} catch (Exception e) {
|
||||
// TODO Auto-generated catch block
|
||||
e.printStackTrace();
|
||||
}
|
||||
|
||||
// No version check for testing
|
||||
PhotonCamera.setVersionCheckEnabled(false);
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user