File tree Expand file tree Collapse file tree 6 files changed +28
-12
lines changed
main/java/org/photonvision
test/java/org/photonvision
photon-targeting/src/main/java/org/photonvision/estimation Expand file tree Collapse file tree 6 files changed +28
-12
lines changed Original file line number Diff line number Diff line change 25
25
package org .photonvision ;
26
26
27
27
import edu .wpi .first .apriltag .AprilTagFieldLayout ;
28
+ import edu .wpi .first .cscore .OpenCvLoader ;
28
29
import edu .wpi .first .hal .FRCNetComm .tResourceType ;
29
30
import edu .wpi .first .hal .HAL ;
30
31
import edu .wpi .first .math .Matrix ;
@@ -159,6 +160,11 @@ public PhotonPoseEstimator(
159
160
this .primaryStrategy = strategy ;
160
161
this .robotToCamera = robotToCamera ;
161
162
163
+ if (strategy == PoseStrategy .MULTI_TAG_PNP_ON_RIO
164
+ || strategy == PoseStrategy .CONSTRAINED_SOLVEPNP ) {
165
+ OpenCvLoader .forceStaticLoad ();
166
+ }
167
+
162
168
HAL .report (tResourceType .kResourceType_PhotonPoseEstimator , InstanceCount );
163
169
InstanceCount ++;
164
170
}
@@ -231,6 +237,11 @@ public PoseStrategy getPrimaryStrategy() {
231
237
*/
232
238
public void setPrimaryStrategy (PoseStrategy strategy ) {
233
239
checkUpdate (this .primaryStrategy , strategy );
240
+
241
+ if (strategy == PoseStrategy .MULTI_TAG_PNP_ON_RIO
242
+ || strategy == PoseStrategy .CONSTRAINED_SOLVEPNP ) {
243
+ OpenCvLoader .forceStaticLoad ();
244
+ }
234
245
this .primaryStrategy = strategy ;
235
246
}
236
247
Original file line number Diff line number Diff line change 28
28
import edu .wpi .first .apriltag .AprilTagFields ;
29
29
import edu .wpi .first .cameraserver .CameraServer ;
30
30
import edu .wpi .first .cscore .CvSource ;
31
+ import edu .wpi .first .cscore .OpenCvLoader ;
31
32
import edu .wpi .first .cscore .VideoSource .ConnectionStrategy ;
32
33
import edu .wpi .first .math .MathUtil ;
33
34
import edu .wpi .first .math .Pair ;
@@ -94,7 +95,7 @@ public class PhotonCameraSim implements AutoCloseable {
94
95
private boolean videoSimProcEnabled = true ;
95
96
96
97
static {
97
- OpenCVHelp . forceLoadOpenCV ();
98
+ OpenCvLoader . forceStaticLoad ();
98
99
}
99
100
100
101
@ Override
Original file line number Diff line number Diff line change 26
26
27
27
import edu .wpi .first .apriltag .AprilTag ;
28
28
import edu .wpi .first .cscore .CvSource ;
29
+ import edu .wpi .first .cscore .OpenCvLoader ;
29
30
import edu .wpi .first .math .geometry .Pose3d ;
30
31
import edu .wpi .first .math .geometry .Translation3d ;
31
32
import edu .wpi .first .math .util .Units ;
@@ -62,7 +63,7 @@ public class VideoSimUtil {
62
63
private static double fieldWidth = 8.0137 ;
63
64
64
65
static {
65
- OpenCVHelp . forceLoadOpenCV ();
66
+ OpenCvLoader . forceStaticLoad ();
66
67
67
68
// create Mats of 10x10 apriltag images
68
69
for (int i = 0 ; i < VideoSimUtil .kNumTags36h11 ; i ++) {
Original file line number Diff line number Diff line change 33
33
34
34
import edu .wpi .first .apriltag .AprilTag ;
35
35
import edu .wpi .first .apriltag .AprilTagFieldLayout ;
36
+ import edu .wpi .first .cscore .OpenCvLoader ;
36
37
import edu .wpi .first .hal .HAL ;
37
38
import edu .wpi .first .math .geometry .Pose2d ;
38
39
import edu .wpi .first .math .geometry .Pose3d ;
57
58
import org .junit .jupiter .params .provider .Arguments ;
58
59
import org .junit .jupiter .params .provider .MethodSource ;
59
60
import org .junit .jupiter .params .provider .ValueSource ;
60
- import org .photonvision .estimation .OpenCVHelp ;
61
61
import org .photonvision .estimation .TargetModel ;
62
62
import org .photonvision .estimation .VisionEstimation ;
63
63
import org .photonvision .jni .PhotonTargetingJniLoader ;
@@ -84,7 +84,7 @@ public static void setUp() {
84
84
fail (e );
85
85
}
86
86
87
- OpenCVHelp . forceLoadOpenCV ();
87
+ OpenCvLoader . forceStaticLoad ();
88
88
89
89
// See #1574 - test flakey, disabled until we address this
90
90
assumeTrue (false );
Original file line number Diff line number Diff line change 17
17
18
18
package org .photonvision .estimation ;
19
19
20
- import edu .wpi .first .cscore .CvSink ;
20
+ import edu .wpi .first .cscore .OpenCvLoader ;
21
21
import edu .wpi .first .math .MatBuilder ;
22
22
import edu .wpi .first .math .Matrix ;
23
23
import edu .wpi .first .math .Nat ;
@@ -54,14 +54,12 @@ public final class OpenCVHelp {
54
54
private static final Rotation3d NWU_TO_EDN ;
55
55
private static final Rotation3d EDN_TO_NWU ;
56
56
57
- // Creating a cscore object is sufficient to load opencv, per
58
- // https://www.chiefdelphi.com/t/unsatisfied- link-error-when-simulating-java-robot-code-using-opencv/426731/4
59
- private static CvSink dummySink = null ;
60
-
57
+ /**
58
+ * @deprecated Replaced by {@ link OpenCvLoader#forceStaticLoad()}
59
+ */
60
+ @ Deprecated ( since = "2025" , forRemoval = true )
61
61
public static void forceLoadOpenCV () {
62
- if (dummySink != null ) return ;
63
- dummySink = new CvSink ("ignored" );
64
- dummySink .close ();
62
+ OpenCvLoader .forceStaticLoad ();
65
63
}
66
64
67
65
static {
Original file line number Diff line number Diff line change 19
19
20
20
import edu .wpi .first .apriltag .AprilTag ;
21
21
import edu .wpi .first .apriltag .AprilTagFieldLayout ;
22
+ import edu .wpi .first .cscore .OpenCvLoader ;
22
23
import edu .wpi .first .math .MatBuilder ;
23
24
import edu .wpi .first .math .Matrix ;
24
25
import edu .wpi .first .math .Nat ;
@@ -105,6 +106,8 @@ public static Optional<PnpResult> estimateCamPosePNP(
105
106
if (knownTags .isEmpty () || corners .isEmpty () || corners .size () % 4 != 0 ) {
106
107
return Optional .empty ();
107
108
}
109
+ OpenCvLoader .forceStaticLoad ();
110
+
108
111
Point [] points = OpenCVHelp .cornersToPoints (corners );
109
112
110
113
// single-tag pnp
@@ -200,6 +203,8 @@ public static Optional<PnpResult> estimateRobotPoseConstrainedSolvepnp(
200
203
if (knownTags .isEmpty () || corners .isEmpty () || corners .size () % 4 != 0 ) {
201
204
return Optional .empty ();
202
205
}
206
+ OpenCvLoader .forceStaticLoad ();
207
+
203
208
Point [] points = OpenCVHelp .cornersToPoints (corners );
204
209
205
210
// Undistort
You can’t perform that action at this time.
0 commit comments