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:
@@ -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;
|
||||
@@ -159,6 +160,11 @@ public class 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++;
|
||||
}
|
||||
@@ -231,6 +237,11 @@ public class PhotonPoseEstimator {
|
||||
*/
|
||||
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;
|
||||
}
|
||||
|
||||
|
||||
@@ -28,6 +28,7 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout;
|
||||
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;
|
||||
@@ -94,7 +95,7 @@ public class PhotonCameraSim implements AutoCloseable {
|
||||
private boolean videoSimProcEnabled = true;
|
||||
|
||||
static {
|
||||
OpenCVHelp.forceLoadOpenCV();
|
||||
OpenCvLoader.forceStaticLoad();
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -26,6 +26,7 @@ package org.photonvision.simulation;
|
||||
|
||||
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;
|
||||
@@ -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++) {
|
||||
|
||||
Reference in New Issue
Block a user