From 524b135142babaea9417a111f405e30e3c2ba3ca Mon Sep 17 00:00:00 2001 From: Matt Date: Sun, 5 Nov 2023 18:13:00 -0500 Subject: [PATCH] Fix OpenCV load in simuated robot projects (#1001) --- .../simulation/PhotonCameraSim.java | 8 +------- .../photonvision/simulation/VideoSimUtil.java | 7 +------ photon-targeting/build.gradle | 1 + .../photonvision/estimation/OpenCVHelp.java | 18 +++++++++++------- 4 files changed, 14 insertions(+), 20 deletions(-) diff --git a/photon-lib/src/main/java/org/photonvision/simulation/PhotonCameraSim.java b/photon-lib/src/main/java/org/photonvision/simulation/PhotonCameraSim.java index 4880adaa8..f725837e1 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/PhotonCameraSim.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/PhotonCameraSim.java @@ -33,13 +33,11 @@ import edu.wpi.first.cscore.VideoSource.ConnectionStrategy; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.Pair; import edu.wpi.first.math.geometry.Pose3d; -import edu.wpi.first.util.CombinedRuntimeLoader; import edu.wpi.first.util.WPIUtilJNI; import java.util.ArrayList; import java.util.List; import java.util.Optional; import java.util.stream.Collectors; -import org.opencv.core.Core; import org.opencv.core.CvType; import org.opencv.core.Mat; import org.opencv.core.Point; @@ -95,11 +93,7 @@ public class PhotonCameraSim implements AutoCloseable { private boolean videoSimProcEnabled = true; static { - try { - CombinedRuntimeLoader.loadLibraries(OpenCVHelp.class, Core.NATIVE_LIBRARY_NAME, "cscorejni"); - } catch (Exception e) { - throw new RuntimeException("Failed to load native libraries!", e); - } + OpenCVHelp.forceLoadOpenCV(); } @Override diff --git a/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java b/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java index cc9ead27f..1bbe92100 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java @@ -28,7 +28,6 @@ import edu.wpi.first.cscore.CvSource; import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.util.Units; -import edu.wpi.first.util.CombinedRuntimeLoader; import java.awt.image.BufferedImage; import java.io.IOException; import java.util.ArrayList; @@ -67,11 +66,7 @@ public class VideoSimUtil { private static double fieldWidth = 8.0137; static { - try { - CombinedRuntimeLoader.loadLibraries(OpenCVHelp.class, Core.NATIVE_LIBRARY_NAME, "cscorejni"); - } catch (Exception e) { - throw new RuntimeException("Failed to load native libraries!", e); - } + OpenCVHelp.forceLoadOpenCV(); // create Mats of 8x8 apriltag images for (int i = 0; i < VideoSimUtil.kNumTags16h5; i++) { diff --git a/photon-targeting/build.gradle b/photon-targeting/build.gradle index 256b66ce7..7d3bcddaa 100644 --- a/photon-targeting/build.gradle +++ b/photon-targeting/build.gradle @@ -8,6 +8,7 @@ apply from: "${rootDir}/shared/common.gradle" dependencies { implementation wpilibTools.deps.wpilibJava("wpimath") implementation wpilibTools.deps.wpilibJava("apriltag") + implementation wpilibTools.deps.wpilibJava("cscore") implementation wpilibTools.deps.wpilibOpenCvJava("frc" + wpi.frcYear.get(), wpi.versions.opencvVersion.get()) implementation group: "org.ejml", name: "ejml-simple", version: wpi.versions.ejmlVersion.get() diff --git a/photon-targeting/src/main/java/org/photonvision/estimation/OpenCVHelp.java b/photon-targeting/src/main/java/org/photonvision/estimation/OpenCVHelp.java index 1f3b8b976..84e5d8d7c 100644 --- a/photon-targeting/src/main/java/org/photonvision/estimation/OpenCVHelp.java +++ b/photon-targeting/src/main/java/org/photonvision/estimation/OpenCVHelp.java @@ -17,6 +17,7 @@ package org.photonvision.estimation; +import edu.wpi.first.cscore.CvSink; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.Nat; import edu.wpi.first.math.Num; @@ -26,7 +27,6 @@ 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.numbers.*; -import edu.wpi.first.util.CombinedRuntimeLoader; import java.util.ArrayList; import java.util.Arrays; import java.util.List; @@ -52,13 +52,17 @@ public final class OpenCVHelp { private static Rotation3d NWU_TO_EDN; private static Rotation3d EDN_TO_NWU; - static { - try { - CombinedRuntimeLoader.loadLibraries(OpenCVHelp.class, Core.NATIVE_LIBRARY_NAME, "cscorejni"); - } catch (Exception e) { - throw new RuntimeException("Failed to load native libraries!", e); - } + // 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; + public static void forceLoadOpenCV() { + if (dummySink != null) return; + dummySink = new CvSink("ignored"); + dummySink.close(); + } + + static { NWU_TO_EDN = new Rotation3d(Matrix.mat(Nat.N3(), Nat.N3()).fill(0, -1, 0, 0, 0, -1, 1, 0, 0)); EDN_TO_NWU = new Rotation3d(Matrix.mat(Nat.N3(), Nat.N3()).fill(0, 0, 1, -1, 0, 0, 0, -1, 0)); }