Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix OpenCV load in simuated robot projects #1001

Merged
merged 4 commits into from
Nov 5, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -33,13 +33,11 @@
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;
Expand Down Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
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;
Expand Down Expand Up @@ -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++) {
Expand Down
1 change: 1 addition & 0 deletions photon-targeting/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -26,7 +27,6 @@
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;
Expand All @@ -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));
}
Expand Down