|
10 | 10 |
|
11 | 11 | import edu.wpi.first.math.geometry.Transform3d;
|
12 | 12 | import edu.wpi.first.math.util.Units;
|
| 13 | +import edu.wpi.first.util.PixelFormat; |
| 14 | +import edu.wpi.first.util.RawFrame; |
13 | 15 | import edu.wpi.first.util.RuntimeLoader;
|
14 | 16 | import java.io.ByteArrayOutputStream;
|
15 | 17 | import java.io.IOException;
|
16 | 18 | import java.io.InputStream;
|
| 19 | +import java.nio.ByteBuffer; |
17 | 20 | import org.junit.jupiter.api.AfterEach;
|
18 | 21 | import org.junit.jupiter.api.BeforeAll;
|
19 | 22 | import org.junit.jupiter.api.BeforeEach;
|
@@ -143,8 +146,12 @@ void testDecodeAndPose() {
|
143 | 146 | fail(ex);
|
144 | 147 | return;
|
145 | 148 | }
|
| 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); |
146 | 153 | try {
|
147 |
| - AprilTagDetection[] results = detector.detect(image); |
| 154 | + AprilTagDetection[] results = detector.detect(frame); |
148 | 155 | assertEquals(1, results.length);
|
149 | 156 | assertEquals("tag36h11", results[0].getFamily());
|
150 | 157 | assertEquals(1, results[0].getId());
|
@@ -176,8 +183,12 @@ void testPoseRotatedX() {
|
176 | 183 | fail(ex);
|
177 | 184 | return;
|
178 | 185 | }
|
| 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); |
179 | 190 | try {
|
180 |
| - AprilTagDetection[] results = detector.detect(image); |
| 191 | + AprilTagDetection[] results = detector.detect(frame); |
181 | 192 | assertEquals(1, results.length);
|
182 | 193 |
|
183 | 194 | var estimator =
|
@@ -209,8 +220,12 @@ void testPoseRotatedY() {
|
209 | 220 | fail(ex);
|
210 | 221 | return;
|
211 | 222 | }
|
| 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); |
212 | 227 | try {
|
213 |
| - AprilTagDetection[] results = detector.detect(image); |
| 228 | + AprilTagDetection[] results = detector.detect(frame); |
214 | 229 | assertEquals(1, results.length);
|
215 | 230 |
|
216 | 231 | var estimator =
|
@@ -239,8 +254,12 @@ void testPoseStraightOn() {
|
239 | 254 | fail(ex);
|
240 | 255 | return;
|
241 | 256 | }
|
| 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); |
242 | 261 | try {
|
243 |
| - AprilTagDetection[] results = detector.detect(image); |
| 262 | + AprilTagDetection[] results = detector.detect(frame); |
244 | 263 | assertEquals(1, results.length);
|
245 | 264 |
|
246 | 265 | var estimator =
|
|
0 commit comments