Skip to content

Commit 34f6e98

Browse files
committed
[apriltag] Make AprilTagDetector.detect() use RawFrame instead of OpenCV Mat
1 parent f150b36 commit 34f6e98

File tree

3 files changed

+38
-9
lines changed

3 files changed

+38
-9
lines changed

apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagDetector.java

+5-4
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
package edu.wpi.first.apriltag;
66

77
import edu.wpi.first.apriltag.jni.AprilTagJNI;
8-
import org.opencv.core.Mat;
8+
import edu.wpi.first.util.RawFrame;
99

1010
/**
1111
* An AprilTag detector engine. This is expensive to set up and tear down, so most use cases should
@@ -293,11 +293,12 @@ public void clearFamilies() {
293293
*
294294
* <p>The image must be grayscale.
295295
*
296-
* @param img 8-bit OpenCV Mat image
296+
* @param frame The frame object containing an 8-bit image.
297297
* @return Results (array of AprilTagDetection)
298298
*/
299-
public AprilTagDetection[] detect(Mat img) {
300-
return AprilTagJNI.detect(m_native, img.cols(), img.rows(), img.cols(), img.dataAddr());
299+
public AprilTagDetection[] detect(RawFrame frame) {
300+
return AprilTagJNI.detect(
301+
m_native, frame.getWidth(), frame.getHeight(), frame.getWidth(), frame.getDataPtr());
301302
}
302303

303304
private long m_native;

apriltag/src/test/java/edu/wpi/first/apriltag/AprilTagDetectorTest.java

+23-4
Original file line numberDiff line numberDiff line change
@@ -10,10 +10,13 @@
1010

1111
import edu.wpi.first.math.geometry.Transform3d;
1212
import edu.wpi.first.math.util.Units;
13+
import edu.wpi.first.util.PixelFormat;
14+
import edu.wpi.first.util.RawFrame;
1315
import edu.wpi.first.util.RuntimeLoader;
1416
import java.io.ByteArrayOutputStream;
1517
import java.io.IOException;
1618
import java.io.InputStream;
19+
import java.nio.ByteBuffer;
1720
import org.junit.jupiter.api.AfterEach;
1821
import org.junit.jupiter.api.BeforeAll;
1922
import org.junit.jupiter.api.BeforeEach;
@@ -143,8 +146,12 @@ void testDecodeAndPose() {
143146
fail(ex);
144147
return;
145148
}
149+
var frame = new RawFrame();
150+
var frameByteBuffer = ByteBuffer.allocateDirect(image.width() * image.height());
151+
image.get(0, 0, frameByteBuffer.array());
152+
frame.setData(frameByteBuffer, image.width(), image.height(), 1, PixelFormat.kGray);
146153
try {
147-
AprilTagDetection[] results = detector.detect(image);
154+
AprilTagDetection[] results = detector.detect(frame);
148155
assertEquals(1, results.length);
149156
assertEquals("tag36h11", results[0].getFamily());
150157
assertEquals(1, results[0].getId());
@@ -176,8 +183,12 @@ void testPoseRotatedX() {
176183
fail(ex);
177184
return;
178185
}
186+
var frame = new RawFrame();
187+
var frameByteBuffer = ByteBuffer.allocateDirect(image.width() * image.height());
188+
image.get(0, 0, frameByteBuffer.array());
189+
frame.setData(frameByteBuffer, image.width(), image.height(), 1, PixelFormat.kGray);
179190
try {
180-
AprilTagDetection[] results = detector.detect(image);
191+
AprilTagDetection[] results = detector.detect(frame);
181192
assertEquals(1, results.length);
182193

183194
var estimator =
@@ -209,8 +220,12 @@ void testPoseRotatedY() {
209220
fail(ex);
210221
return;
211222
}
223+
var frame = new RawFrame();
224+
var frameByteBuffer = ByteBuffer.allocateDirect(image.width() * image.height());
225+
image.get(0, 0, frameByteBuffer.array());
226+
frame.setData(frameByteBuffer, image.width(), image.height(), 1, PixelFormat.kGray);
212227
try {
213-
AprilTagDetection[] results = detector.detect(image);
228+
AprilTagDetection[] results = detector.detect(frame);
214229
assertEquals(1, results.length);
215230

216231
var estimator =
@@ -239,8 +254,12 @@ void testPoseStraightOn() {
239254
fail(ex);
240255
return;
241256
}
257+
var frame = new RawFrame();
258+
var frameByteBuffer = ByteBuffer.allocateDirect(image.width() * image.height());
259+
image.get(0, 0, frameByteBuffer.array());
260+
frame.setData(frameByteBuffer, image.width(), image.height(), 1, PixelFormat.kGray);
242261
try {
243-
AprilTagDetection[] results = detector.detect(image);
262+
AprilTagDetection[] results = detector.detect(frame);
244263
assertEquals(1, results.length);
245264

246265
var estimator =

wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/apriltagsvision/Robot.java

+10-1
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,10 @@
1616
import edu.wpi.first.networktables.IntegerArrayPublisher;
1717
import edu.wpi.first.networktables.NetworkTable;
1818
import edu.wpi.first.networktables.NetworkTableInstance;
19+
import edu.wpi.first.util.PixelFormat;
20+
import edu.wpi.first.util.RawFrame;
1921
import edu.wpi.first.wpilibj.TimedRobot;
22+
import java.nio.ByteBuffer;
2023
import java.util.ArrayList;
2124
import org.opencv.core.Mat;
2225
import org.opencv.core.Point;
@@ -65,6 +68,9 @@ void apriltagVisionThreadProc() {
6568
var mat = new Mat();
6669
var grayMat = new Mat();
6770

71+
var frame = new RawFrame();
72+
var frameByteBuffer = ByteBuffer.allocateDirect(640 * 480);
73+
6874
// Instantiate once
6975
ArrayList<Long> tags = new ArrayList<>();
7076
var outlineColor = new Scalar(0, 255, 0);
@@ -89,7 +95,10 @@ void apriltagVisionThreadProc() {
8995

9096
Imgproc.cvtColor(mat, grayMat, Imgproc.COLOR_RGB2GRAY);
9197

92-
AprilTagDetection[] detections = detector.detect(grayMat);
98+
grayMat.get(0, 0, frameByteBuffer.array());
99+
frame.setData(frameByteBuffer, grayMat.width(), grayMat.height(), 1, PixelFormat.kGray);
100+
101+
AprilTagDetection[] detections = detector.detect(frame);
93102

94103
// have not seen any tags yet
95104
tags.clear();

0 commit comments

Comments
 (0)