Skip to content
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 @@ -25,6 +25,7 @@
package org.photonvision;

import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.cscore.OpenCvLoader;
import edu.wpi.first.hal.FRCNetComm.tResourceType;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.math.Matrix;
Expand Down Expand Up @@ -159,6 +160,11 @@ public PhotonPoseEstimator(
this.primaryStrategy = strategy;
this.robotToCamera = robotToCamera;

if (strategy == PoseStrategy.MULTI_TAG_PNP_ON_RIO
|| strategy == PoseStrategy.CONSTRAINED_SOLVEPNP) {
OpenCvLoader.forceStaticLoad();
}

HAL.report(tResourceType.kResourceType_PhotonPoseEstimator, InstanceCount);
InstanceCount++;
}
Expand Down Expand Up @@ -231,6 +237,11 @@ public PoseStrategy getPrimaryStrategy() {
*/
public void setPrimaryStrategy(PoseStrategy strategy) {
checkUpdate(this.primaryStrategy, strategy);

if (strategy == PoseStrategy.MULTI_TAG_PNP_ON_RIO
|| strategy == PoseStrategy.CONSTRAINED_SOLVEPNP) {
OpenCvLoader.forceStaticLoad();
}
this.primaryStrategy = strategy;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.cscore.CvSource;
import edu.wpi.first.cscore.OpenCvLoader;
import edu.wpi.first.cscore.VideoSource.ConnectionStrategy;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.Pair;
Expand Down Expand Up @@ -94,7 +95,7 @@ public class PhotonCameraSim implements AutoCloseable {
private boolean videoSimProcEnabled = true;

static {
OpenCVHelp.forceLoadOpenCV();
OpenCvLoader.forceStaticLoad();
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@

import edu.wpi.first.apriltag.AprilTag;
import edu.wpi.first.cscore.CvSource;
import edu.wpi.first.cscore.OpenCvLoader;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.util.Units;
Expand Down Expand Up @@ -62,7 +63,7 @@ public class VideoSimUtil {
private static double fieldWidth = 8.0137;

static {
OpenCVHelp.forceLoadOpenCV();
OpenCvLoader.forceStaticLoad();

// create Mats of 10x10 apriltag images
for (int i = 0; i < VideoSimUtil.kNumTags36h11; i++) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@

import edu.wpi.first.apriltag.AprilTag;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.cscore.OpenCvLoader;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Pose3d;
Expand All @@ -57,7 +58,6 @@
import org.junit.jupiter.params.provider.Arguments;
import org.junit.jupiter.params.provider.MethodSource;
import org.junit.jupiter.params.provider.ValueSource;
import org.photonvision.estimation.OpenCVHelp;
import org.photonvision.estimation.TargetModel;
import org.photonvision.estimation.VisionEstimation;
import org.photonvision.jni.PhotonTargetingJniLoader;
Expand All @@ -84,7 +84,7 @@ public static void setUp() {
fail(e);
}

OpenCVHelp.forceLoadOpenCV();
OpenCvLoader.forceStaticLoad();

// See #1574 - test flakey, disabled until we address this
assumeTrue(false);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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 {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

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;
Expand Down Expand Up @@ -105,6 +106,8 @@ public static Optional<PnpResult> estimateCamPosePNP(
if (knownTags.isEmpty() || corners.isEmpty() || corners.size() % 4 != 0) {
return Optional.empty();
}
OpenCvLoader.forceStaticLoad();

Point[] points = OpenCVHelp.cornersToPoints(corners);

// single-tag pnp
Expand Down Expand Up @@ -200,6 +203,8 @@ public static Optional<PnpResult> estimateRobotPoseConstrainedSolvepnp(
if (knownTags.isEmpty() || corners.isEmpty() || corners.size() % 4 != 0) {
return Optional.empty();
}
OpenCvLoader.forceStaticLoad();

Point[] points = OpenCVHelp.cornersToPoints(corners);

// Undistort
Expand Down
Loading