mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
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
This commit is contained in:
@@ -17,7 +17,7 @@
|
||||
|
||||
package org.photonvision.estimation;
|
||||
|
||||
import edu.wpi.first.cscore.CvSink;
|
||||
import edu.wpi.first.cscore.OpenCvLoader;
|
||||
import edu.wpi.first.math.MatBuilder;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Nat;
|
||||
@@ -54,14 +54,12 @@ public final class OpenCVHelp {
|
||||
private static final Rotation3d NWU_TO_EDN;
|
||||
private static final Rotation3d EDN_TO_NWU;
|
||||
|
||||
// Creating a cscore object is sufficient to load opencv, per
|
||||
// https://www.chiefdelphi.com/t/unsatisfied-link-error-when-simulating-java-robot-code-using-opencv/426731/4
|
||||
private static CvSink dummySink = null;
|
||||
|
||||
/**
|
||||
* @deprecated Replaced by {@link OpenCvLoader#forceStaticLoad()}
|
||||
*/
|
||||
@Deprecated(since = "2025", forRemoval = true)
|
||||
public static void forceLoadOpenCV() {
|
||||
if (dummySink != null) return;
|
||||
dummySink = new CvSink("ignored");
|
||||
dummySink.close();
|
||||
OpenCvLoader.forceStaticLoad();
|
||||
}
|
||||
|
||||
static {
|
||||
|
||||
@@ -19,6 +19,7 @@ package org.photonvision.estimation;
|
||||
|
||||
import edu.wpi.first.apriltag.AprilTag;
|
||||
import edu.wpi.first.apriltag.AprilTagFieldLayout;
|
||||
import edu.wpi.first.cscore.OpenCvLoader;
|
||||
import edu.wpi.first.math.MatBuilder;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Nat;
|
||||
@@ -105,6 +106,8 @@ public class VisionEstimation {
|
||||
if (knownTags.isEmpty() || corners.isEmpty() || corners.size() % 4 != 0) {
|
||||
return Optional.empty();
|
||||
}
|
||||
OpenCvLoader.forceStaticLoad();
|
||||
|
||||
Point[] points = OpenCVHelp.cornersToPoints(corners);
|
||||
|
||||
// single-tag pnp
|
||||
@@ -200,6 +203,8 @@ public class VisionEstimation {
|
||||
if (knownTags.isEmpty() || corners.isEmpty() || corners.size() % 4 != 0) {
|
||||
return Optional.empty();
|
||||
}
|
||||
OpenCvLoader.forceStaticLoad();
|
||||
|
||||
Point[] points = OpenCVHelp.cornersToPoints(corners);
|
||||
|
||||
// Undistort
|
||||
|
||||
Reference in New Issue
Block a user