Skip to content

Commit f6736fc

Browse files
authored
Force load opencv before using OpenCV functions (#1808)
Force loads OpenCV before any OpenCV functions are used. `OpenCVLoader` has all of its loading done in a static initializer field, so it's only loaded once. Also deprecates `OpenCVHelp.forceLoadOpenCV()`, since it's functionality is the exact same. Resolves #1803
1 parent 889c73e commit f6736fc

File tree

6 files changed

+28
-12
lines changed

6 files changed

+28
-12
lines changed

photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
package org.photonvision;
2626

2727
import edu.wpi.first.apriltag.AprilTagFieldLayout;
28+
import edu.wpi.first.cscore.OpenCvLoader;
2829
import edu.wpi.first.hal.FRCNetComm.tResourceType;
2930
import edu.wpi.first.hal.HAL;
3031
import edu.wpi.first.math.Matrix;
@@ -159,6 +160,11 @@ public PhotonPoseEstimator(
159160
this.primaryStrategy = strategy;
160161
this.robotToCamera = robotToCamera;
161162

163+
if (strategy == PoseStrategy.MULTI_TAG_PNP_ON_RIO
164+
|| strategy == PoseStrategy.CONSTRAINED_SOLVEPNP) {
165+
OpenCvLoader.forceStaticLoad();
166+
}
167+
162168
HAL.report(tResourceType.kResourceType_PhotonPoseEstimator, InstanceCount);
163169
InstanceCount++;
164170
}
@@ -231,6 +237,11 @@ public PoseStrategy getPrimaryStrategy() {
231237
*/
232238
public void setPrimaryStrategy(PoseStrategy strategy) {
233239
checkUpdate(this.primaryStrategy, strategy);
240+
241+
if (strategy == PoseStrategy.MULTI_TAG_PNP_ON_RIO
242+
|| strategy == PoseStrategy.CONSTRAINED_SOLVEPNP) {
243+
OpenCvLoader.forceStaticLoad();
244+
}
234245
this.primaryStrategy = strategy;
235246
}
236247

photon-lib/src/main/java/org/photonvision/simulation/PhotonCameraSim.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
import edu.wpi.first.apriltag.AprilTagFields;
2929
import edu.wpi.first.cameraserver.CameraServer;
3030
import edu.wpi.first.cscore.CvSource;
31+
import edu.wpi.first.cscore.OpenCvLoader;
3132
import edu.wpi.first.cscore.VideoSource.ConnectionStrategy;
3233
import edu.wpi.first.math.MathUtil;
3334
import edu.wpi.first.math.Pair;
@@ -94,7 +95,7 @@ public class PhotonCameraSim implements AutoCloseable {
9495
private boolean videoSimProcEnabled = true;
9596

9697
static {
97-
OpenCVHelp.forceLoadOpenCV();
98+
OpenCvLoader.forceStaticLoad();
9899
}
99100

100101
@Override

photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626

2727
import edu.wpi.first.apriltag.AprilTag;
2828
import edu.wpi.first.cscore.CvSource;
29+
import edu.wpi.first.cscore.OpenCvLoader;
2930
import edu.wpi.first.math.geometry.Pose3d;
3031
import edu.wpi.first.math.geometry.Translation3d;
3132
import edu.wpi.first.math.util.Units;
@@ -62,7 +63,7 @@ public class VideoSimUtil {
6263
private static double fieldWidth = 8.0137;
6364

6465
static {
65-
OpenCVHelp.forceLoadOpenCV();
66+
OpenCvLoader.forceStaticLoad();
6667

6768
// create Mats of 10x10 apriltag images
6869
for (int i = 0; i < VideoSimUtil.kNumTags36h11; i++) {

photon-lib/src/test/java/org/photonvision/VisionSystemSimTest.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333

3434
import edu.wpi.first.apriltag.AprilTag;
3535
import edu.wpi.first.apriltag.AprilTagFieldLayout;
36+
import edu.wpi.first.cscore.OpenCvLoader;
3637
import edu.wpi.first.hal.HAL;
3738
import edu.wpi.first.math.geometry.Pose2d;
3839
import edu.wpi.first.math.geometry.Pose3d;
@@ -57,7 +58,6 @@
5758
import org.junit.jupiter.params.provider.Arguments;
5859
import org.junit.jupiter.params.provider.MethodSource;
5960
import org.junit.jupiter.params.provider.ValueSource;
60-
import org.photonvision.estimation.OpenCVHelp;
6161
import org.photonvision.estimation.TargetModel;
6262
import org.photonvision.estimation.VisionEstimation;
6363
import org.photonvision.jni.PhotonTargetingJniLoader;
@@ -84,7 +84,7 @@ public static void setUp() {
8484
fail(e);
8585
}
8686

87-
OpenCVHelp.forceLoadOpenCV();
87+
OpenCvLoader.forceStaticLoad();
8888

8989
// See #1574 - test flakey, disabled until we address this
9090
assumeTrue(false);

photon-targeting/src/main/java/org/photonvision/estimation/OpenCVHelp.java

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717

1818
package org.photonvision.estimation;
1919

20-
import edu.wpi.first.cscore.CvSink;
20+
import edu.wpi.first.cscore.OpenCvLoader;
2121
import edu.wpi.first.math.MatBuilder;
2222
import edu.wpi.first.math.Matrix;
2323
import edu.wpi.first.math.Nat;
@@ -54,14 +54,12 @@ public final class OpenCVHelp {
5454
private static final Rotation3d NWU_TO_EDN;
5555
private static final Rotation3d EDN_TO_NWU;
5656

57-
// Creating a cscore object is sufficient to load opencv, per
58-
// https://www.chiefdelphi.com/t/unsatisfied-link-error-when-simulating-java-robot-code-using-opencv/426731/4
59-
private static CvSink dummySink = null;
60-
57+
/**
58+
* @deprecated Replaced by {@link OpenCvLoader#forceStaticLoad()}
59+
*/
60+
@Deprecated(since = "2025", forRemoval = true)
6161
public static void forceLoadOpenCV() {
62-
if (dummySink != null) return;
63-
dummySink = new CvSink("ignored");
64-
dummySink.close();
62+
OpenCvLoader.forceStaticLoad();
6563
}
6664

6765
static {

photon-targeting/src/main/java/org/photonvision/estimation/VisionEstimation.java

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
import edu.wpi.first.apriltag.AprilTag;
2121
import edu.wpi.first.apriltag.AprilTagFieldLayout;
22+
import edu.wpi.first.cscore.OpenCvLoader;
2223
import edu.wpi.first.math.MatBuilder;
2324
import edu.wpi.first.math.Matrix;
2425
import edu.wpi.first.math.Nat;
@@ -105,6 +106,8 @@ public static Optional<PnpResult> estimateCamPosePNP(
105106
if (knownTags.isEmpty() || corners.isEmpty() || corners.size() % 4 != 0) {
106107
return Optional.empty();
107108
}
109+
OpenCvLoader.forceStaticLoad();
110+
108111
Point[] points = OpenCVHelp.cornersToPoints(corners);
109112

110113
// single-tag pnp
@@ -200,6 +203,8 @@ public static Optional<PnpResult> estimateRobotPoseConstrainedSolvepnp(
200203
if (knownTags.isEmpty() || corners.isEmpty() || corners.size() % 4 != 0) {
201204
return Optional.empty();
202205
}
206+
OpenCvLoader.forceStaticLoad();
207+
203208
Point[] points = OpenCVHelp.cornersToPoints(corners);
204209

205210
// Undistort

0 commit comments

Comments
 (0)