forked from LimelightVision/limelightlib-wpijava
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathLimelightHelpers.java
1698 lines (1433 loc) · 58.6 KB
/
LimelightHelpers.java
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
//LimelightHelpers v1.12 (REQUIRES LLOS 2025.0 OR LATER)
package frc.libzodiac.hardware.limelight;
import edu.wpi.first.networktables.DoubleArrayEntry;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableEntry;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.networktables.TimestampedDoubleArray;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation2d;
import java.io.IOException;
import java.net.HttpURLConnection;
import java.net.MalformedURLException;
import java.net.URL;
import java.util.Arrays;
import java.util.Map;
import java.util.concurrent.CompletableFuture;
import com.fasterxml.jackson.annotation.JsonFormat;
import com.fasterxml.jackson.annotation.JsonFormat.Shape;
import com.fasterxml.jackson.annotation.JsonProperty;
import com.fasterxml.jackson.core.JsonProcessingException;
import com.fasterxml.jackson.databind.DeserializationFeature;
import com.fasterxml.jackson.databind.ObjectMapper;
import java.util.concurrent.ConcurrentHashMap;
/**
* LimelightHelpers provides static methods and classes for interfacing with Limelight vision cameras in FRC.
* This library supports all Limelight features including AprilTag tracking, Neural Networks, and standard color/retroreflective tracking.
*/
public class LimelightHelpers {
private static final Map<String, DoubleArrayEntry> doubleArrayEntries = new ConcurrentHashMap<>();
/**
* Represents a Color/Retroreflective Target Result extracted from JSON Output
*/
public static class LimelightTarget_Retro {
@JsonProperty("t6c_ts")
private double[] cameraPose_TargetSpace;
@JsonProperty("t6r_fs")
private double[] robotPose_FieldSpace;
@JsonProperty("t6r_ts")
private double[] robotPose_TargetSpace;
@JsonProperty("t6t_cs")
private double[] targetPose_CameraSpace;
@JsonProperty("t6t_rs")
private double[] targetPose_RobotSpace;
public Pose3d getCameraPose_TargetSpace()
{
return toPose3D(cameraPose_TargetSpace);
}
public Pose3d getRobotPose_FieldSpace()
{
return toPose3D(robotPose_FieldSpace);
}
public Pose3d getRobotPose_TargetSpace()
{
return toPose3D(robotPose_TargetSpace);
}
public Pose3d getTargetPose_CameraSpace()
{
return toPose3D(targetPose_CameraSpace);
}
public Pose3d getTargetPose_RobotSpace()
{
return toPose3D(targetPose_RobotSpace);
}
public Pose2d getCameraPose_TargetSpace2D()
{
return toPose2D(cameraPose_TargetSpace);
}
public Pose2d getRobotPose_FieldSpace2D()
{
return toPose2D(robotPose_FieldSpace);
}
public Pose2d getRobotPose_TargetSpace2D()
{
return toPose2D(robotPose_TargetSpace);
}
public Pose2d getTargetPose_CameraSpace2D()
{
return toPose2D(targetPose_CameraSpace);
}
public Pose2d getTargetPose_RobotSpace2D()
{
return toPose2D(targetPose_RobotSpace);
}
@JsonProperty("ta")
public double ta;
@JsonProperty("tx")
public double tx;
@JsonProperty("ty")
public double ty;
@JsonProperty("txp")
public double tx_pixels;
@JsonProperty("typ")
public double ty_pixels;
@JsonProperty("tx_nocross")
public double tx_nocrosshair;
@JsonProperty("ty_nocross")
public double ty_nocrosshair;
@JsonProperty("ts")
public double ts;
public LimelightTarget_Retro() {
cameraPose_TargetSpace = new double[6];
robotPose_FieldSpace = new double[6];
robotPose_TargetSpace = new double[6];
targetPose_CameraSpace = new double[6];
targetPose_RobotSpace = new double[6];
}
}
/**
* Represents an AprilTag/Fiducial Target Result extracted from JSON Output
*/
public static class LimelightTarget_Fiducial {
@JsonProperty("fID")
public double fiducialID;
@JsonProperty("fam")
public String fiducialFamily;
@JsonProperty("t6c_ts")
private double[] cameraPose_TargetSpace;
@JsonProperty("t6r_fs")
private double[] robotPose_FieldSpace;
@JsonProperty("t6r_ts")
private double[] robotPose_TargetSpace;
@JsonProperty("t6t_cs")
private double[] targetPose_CameraSpace;
@JsonProperty("t6t_rs")
private double[] targetPose_RobotSpace;
public Pose3d getCameraPose_TargetSpace()
{
return toPose3D(cameraPose_TargetSpace);
}
public Pose3d getRobotPose_FieldSpace()
{
return toPose3D(robotPose_FieldSpace);
}
public Pose3d getRobotPose_TargetSpace()
{
return toPose3D(robotPose_TargetSpace);
}
public Pose3d getTargetPose_CameraSpace()
{
return toPose3D(targetPose_CameraSpace);
}
public Pose3d getTargetPose_RobotSpace()
{
return toPose3D(targetPose_RobotSpace);
}
public Pose2d getCameraPose_TargetSpace2D()
{
return toPose2D(cameraPose_TargetSpace);
}
public Pose2d getRobotPose_FieldSpace2D()
{
return toPose2D(robotPose_FieldSpace);
}
public Pose2d getRobotPose_TargetSpace2D()
{
return toPose2D(robotPose_TargetSpace);
}
public Pose2d getTargetPose_CameraSpace2D()
{
return toPose2D(targetPose_CameraSpace);
}
public Pose2d getTargetPose_RobotSpace2D()
{
return toPose2D(targetPose_RobotSpace);
}
@JsonProperty("ta")
public double ta;
@JsonProperty("tx")
public double tx;
@JsonProperty("ty")
public double ty;
@JsonProperty("txp")
public double tx_pixels;
@JsonProperty("typ")
public double ty_pixels;
@JsonProperty("tx_nocross")
public double tx_nocrosshair;
@JsonProperty("ty_nocross")
public double ty_nocrosshair;
@JsonProperty("ts")
public double ts;
public LimelightTarget_Fiducial() {
cameraPose_TargetSpace = new double[6];
robotPose_FieldSpace = new double[6];
robotPose_TargetSpace = new double[6];
targetPose_CameraSpace = new double[6];
targetPose_RobotSpace = new double[6];
}
}
/**
* Represents a Barcode Target Result extracted from JSON Output
*/
public static class LimelightTarget_Barcode {
/**
* Barcode family type (e.g. "QR", "DataMatrix", etc.)
*/
@JsonProperty("fam")
public String family;
/**
* Gets the decoded data content of the barcode
*/
@JsonProperty("data")
public String data;
@JsonProperty("txp")
public double tx_pixels;
@JsonProperty("typ")
public double ty_pixels;
@JsonProperty("tx")
public double tx;
@JsonProperty("ty")
public double ty;
@JsonProperty("tx_nocross")
public double tx_nocrosshair;
@JsonProperty("ty_nocross")
public double ty_nocrosshair;
@JsonProperty("ta")
public double ta;
@JsonProperty("pts")
public double[][] corners;
public LimelightTarget_Barcode() {
}
public String getFamily() {
return family;
}
}
/**
* Represents a Neural Classifier Pipeline Result extracted from JSON Output
*/
public static class LimelightTarget_Classifier {
@JsonProperty("class")
public String className;
@JsonProperty("classID")
public double classID;
@JsonProperty("conf")
public double confidence;
@JsonProperty("zone")
public double zone;
@JsonProperty("tx")
public double tx;
@JsonProperty("txp")
public double tx_pixels;
@JsonProperty("ty")
public double ty;
@JsonProperty("typ")
public double ty_pixels;
public LimelightTarget_Classifier() {
}
}
/**
* Represents a Neural Detector Pipeline Result extracted from JSON Output
*/
public static class LimelightTarget_Detector {
@JsonProperty("class")
public String className;
@JsonProperty("classID")
public double classID;
@JsonProperty("conf")
public double confidence;
@JsonProperty("ta")
public double ta;
@JsonProperty("tx")
public double tx;
@JsonProperty("ty")
public double ty;
@JsonProperty("txp")
public double tx_pixels;
@JsonProperty("typ")
public double ty_pixels;
@JsonProperty("tx_nocross")
public double tx_nocrosshair;
@JsonProperty("ty_nocross")
public double ty_nocrosshair;
public LimelightTarget_Detector() {
}
}
/**
* Limelight Results object, parsed from a Limelight's JSON results output.
*/
public static class LimelightResults {
public String error;
@JsonProperty("pID")
public double pipelineID;
@JsonProperty("tl")
public double latency_pipeline;
@JsonProperty("cl")
public double latency_capture;
public double latency_jsonParse;
@JsonProperty("ts")
public double timestamp_LIMELIGHT_publish;
@JsonProperty("ts_rio")
public double timestamp_RIOFPGA_capture;
@JsonProperty("v")
@JsonFormat(shape = Shape.NUMBER)
public boolean valid;
@JsonProperty("botpose")
public double[] botpose;
@JsonProperty("botpose_wpired")
public double[] botpose_wpired;
@JsonProperty("botpose_wpiblue")
public double[] botpose_wpiblue;
@JsonProperty("botpose_tagcount")
public double botpose_tagcount;
@JsonProperty("botpose_span")
public double botpose_span;
@JsonProperty("botpose_avgdist")
public double botpose_avgdist;
@JsonProperty("botpose_avgarea")
public double botpose_avgarea;
@JsonProperty("t6c_rs")
public double[] camerapose_robotspace;
public Pose3d getBotPose3d() {
return toPose3D(botpose);
}
public Pose3d getBotPose3d_wpiRed() {
return toPose3D(botpose_wpired);
}
public Pose3d getBotPose3d_wpiBlue() {
return toPose3D(botpose_wpiblue);
}
public Pose2d getBotPose2d() {
return toPose2D(botpose);
}
public Pose2d getBotPose2d_wpiRed() {
return toPose2D(botpose_wpired);
}
public Pose2d getBotPose2d_wpiBlue() {
return toPose2D(botpose_wpiblue);
}
@JsonProperty("Retro")
public LimelightTarget_Retro[] targets_Retro;
@JsonProperty("Fiducial")
public LimelightTarget_Fiducial[] targets_Fiducials;
@JsonProperty("Classifier")
public LimelightTarget_Classifier[] targets_Classifier;
@JsonProperty("Detector")
public LimelightTarget_Detector[] targets_Detector;
@JsonProperty("Barcode")
public LimelightTarget_Barcode[] targets_Barcode;
public LimelightResults() {
botpose = new double[6];
botpose_wpired = new double[6];
botpose_wpiblue = new double[6];
camerapose_robotspace = new double[6];
targets_Retro = new LimelightTarget_Retro[0];
targets_Fiducials = new LimelightTarget_Fiducial[0];
targets_Classifier = new LimelightTarget_Classifier[0];
targets_Detector = new LimelightTarget_Detector[0];
targets_Barcode = new LimelightTarget_Barcode[0];
}
}
/**
* Represents a Limelight Raw Fiducial result from Limelight's NetworkTables output.
*/
public static class RawFiducial {
public int id = 0;
public double txnc = 0;
public double tync = 0;
public double ta = 0;
public double distToCamera = 0;
public double distToRobot = 0;
public double ambiguity = 0;
public RawFiducial(int id, double txnc, double tync, double ta, double distToCamera, double distToRobot, double ambiguity) {
this.id = id;
this.txnc = txnc;
this.tync = tync;
this.ta = ta;
this.distToCamera = distToCamera;
this.distToRobot = distToRobot;
this.ambiguity = ambiguity;
}
@Override
public boolean equals(Object obj) {
if (this == obj) return true;
if (obj == null || getClass() != obj.getClass()) return false;
RawFiducial other = (RawFiducial) obj;
return id == other.id &&
Double.compare(txnc, other.txnc) == 0 &&
Double.compare(tync, other.tync) == 0 &&
Double.compare(ta, other.ta) == 0 &&
Double.compare(distToCamera, other.distToCamera) == 0 &&
Double.compare(distToRobot, other.distToRobot) == 0 &&
Double.compare(ambiguity, other.ambiguity) == 0;
}
}
/**
* Represents a Limelight Raw Neural Detector result from Limelight's NetworkTables output.
*/
public static class RawDetection {
public int classId = 0;
public double txnc = 0;
public double tync = 0;
public double ta = 0;
public double corner0_X = 0;
public double corner0_Y = 0;
public double corner1_X = 0;
public double corner1_Y = 0;
public double corner2_X = 0;
public double corner2_Y = 0;
public double corner3_X = 0;
public double corner3_Y = 0;
public RawDetection(int classId, double txnc, double tync, double ta,
double corner0_X, double corner0_Y,
double corner1_X, double corner1_Y,
double corner2_X, double corner2_Y,
double corner3_X, double corner3_Y ) {
this.classId = classId;
this.txnc = txnc;
this.tync = tync;
this.ta = ta;
this.corner0_X = corner0_X;
this.corner0_Y = corner0_Y;
this.corner1_X = corner1_X;
this.corner1_Y = corner1_Y;
this.corner2_X = corner2_X;
this.corner2_Y = corner2_Y;
this.corner3_X = corner3_X;
this.corner3_Y = corner3_Y;
}
}
/**
* Represents a 3D Pose Estimate.
*/
public static class PoseEstimate {
public Pose2d pose;
public double timestampSeconds;
public double latency;
public int tagCount;
public double tagSpan;
public double avgTagDist;
public double avgTagArea;
public RawFiducial[] rawFiducials;
public boolean isMegaTag2;
/**
* Instantiates a PoseEstimate object with default values
*/
public PoseEstimate() {
this.pose = new Pose2d();
this.timestampSeconds = 0;
this.latency = 0;
this.tagCount = 0;
this.tagSpan = 0;
this.avgTagDist = 0;
this.avgTagArea = 0;
this.rawFiducials = new RawFiducial[]{};
this.isMegaTag2 = false;
}
public PoseEstimate(Pose2d pose, double timestampSeconds, double latency,
int tagCount, double tagSpan, double avgTagDist,
double avgTagArea, RawFiducial[] rawFiducials, boolean isMegaTag2) {
this.pose = pose;
this.timestampSeconds = timestampSeconds;
this.latency = latency;
this.tagCount = tagCount;
this.tagSpan = tagSpan;
this.avgTagDist = avgTagDist;
this.avgTagArea = avgTagArea;
this.rawFiducials = rawFiducials;
this.isMegaTag2 = isMegaTag2;
}
@Override
public boolean equals(Object obj) {
if (this == obj) return true;
if (obj == null || getClass() != obj.getClass()) return false;
PoseEstimate that = (PoseEstimate) obj;
// We don't compare the timestampSeconds as it isn't relevant for equality and makes
// unit testing harder
return Double.compare(that.latency, latency) == 0
&& tagCount == that.tagCount
&& Double.compare(that.tagSpan, tagSpan) == 0
&& Double.compare(that.avgTagDist, avgTagDist) == 0
&& Double.compare(that.avgTagArea, avgTagArea) == 0
&& pose.equals(that.pose)
&& Arrays.equals(rawFiducials, that.rawFiducials);
}
}
/**
* Encapsulates the state of an internal Limelight IMU.
*/
public static class IMUData {
public double robotYaw = 0.0;
public double Roll = 0.0;
public double Pitch = 0.0;
public double Yaw = 0.0;
public double gyroX = 0.0;
public double gyroY = 0.0;
public double gyroZ = 0.0;
public double accelX = 0.0;
public double accelY = 0.0;
public double accelZ = 0.0;
public IMUData() {}
public IMUData(double[] imuData) {
if (imuData != null && imuData.length >= 10) {
this.robotYaw = imuData[0];
this.Roll = imuData[1];
this.Pitch = imuData[2];
this.Yaw = imuData[3];
this.gyroX = imuData[4];
this.gyroY = imuData[5];
this.gyroZ = imuData[6];
this.accelX = imuData[7];
this.accelY = imuData[8];
this.accelZ = imuData[9];
}
}
}
private static ObjectMapper mapper;
/**
* Print JSON Parse time to the console in milliseconds
*/
static boolean profileJSON = false;
static final String sanitizeName(String name) {
if ("".equals(name) || name == null) {
return "limelight";
}
return name;
}
/**
* Takes a 6-length array of pose data and converts it to a Pose3d object.
* Array format: [x, y, z, roll, pitch, yaw] where angles are in degrees.
* @param inData Array containing pose data [x, y, z, roll, pitch, yaw]
* @return Pose3d object representing the pose, or empty Pose3d if invalid data
*/
public static Pose3d toPose3D(double[] inData){
if(inData.length < 6)
{
//System.err.println("Bad LL 3D Pose Data!");
return new Pose3d();
}
return new Pose3d(
new Translation3d(inData[0], inData[1], inData[2]),
new Rotation3d(Units.degreesToRadians(inData[3]), Units.degreesToRadians(inData[4]),
Units.degreesToRadians(inData[5])));
}
/**
* Takes a 6-length array of pose data and converts it to a Pose2d object.
* Uses only x, y, and yaw components, ignoring z, roll, and pitch.
* Array format: [x, y, z, roll, pitch, yaw] where angles are in degrees.
* @param inData Array containing pose data [x, y, z, roll, pitch, yaw]
* @return Pose2d object representing the pose, or empty Pose2d if invalid data
*/
public static Pose2d toPose2D(double[] inData){
if(inData.length < 6)
{
//System.err.println("Bad LL 2D Pose Data!");
return new Pose2d();
}
Translation2d tran2d = new Translation2d(inData[0], inData[1]);
Rotation2d r2d = new Rotation2d(Units.degreesToRadians(inData[5]));
return new Pose2d(tran2d, r2d);
}
/**
* Converts a Pose3d object to an array of doubles in the format [x, y, z, roll, pitch, yaw].
* Translation components are in meters, rotation components are in degrees.
*
* @param pose The Pose3d object to convert
* @return A 6-element array containing [x, y, z, roll, pitch, yaw]
*/
public static double[] pose3dToArray(Pose3d pose) {
double[] result = new double[6];
result[0] = pose.getTranslation().getX();
result[1] = pose.getTranslation().getY();
result[2] = pose.getTranslation().getZ();
result[3] = Units.radiansToDegrees(pose.getRotation().getX());
result[4] = Units.radiansToDegrees(pose.getRotation().getY());
result[5] = Units.radiansToDegrees(pose.getRotation().getZ());
return result;
}
/**
* Converts a Pose2d object to an array of doubles in the format [x, y, z, roll, pitch, yaw].
* Translation components are in meters, rotation components are in degrees.
* Note: z, roll, and pitch will be 0 since Pose2d only contains x, y, and yaw.
*
* @param pose The Pose2d object to convert
* @return A 6-element array containing [x, y, 0, 0, 0, yaw]
*/
public static double[] pose2dToArray(Pose2d pose) {
double[] result = new double[6];
result[0] = pose.getTranslation().getX();
result[1] = pose.getTranslation().getY();
result[2] = 0;
result[3] = Units.radiansToDegrees(0);
result[4] = Units.radiansToDegrees(0);
result[5] = Units.radiansToDegrees(pose.getRotation().getRadians());
return result;
}
private static double extractArrayEntry(double[] inData, int position){
if(inData.length < position+1)
{
return 0;
}
return inData[position];
}
private static PoseEstimate getBotPoseEstimate(String limelightName, String entryName, boolean isMegaTag2) {
DoubleArrayEntry poseEntry = LimelightHelpers.getLimelightDoubleArrayEntry(limelightName, entryName);
TimestampedDoubleArray tsValue = poseEntry.getAtomic();
double[] poseArray = tsValue.value;
long timestamp = tsValue.timestamp;
if (poseArray.length == 0) {
// Handle the case where no data is available
return null; // or some default PoseEstimate
}
var pose = toPose2D(poseArray);
double latency = extractArrayEntry(poseArray, 6);
int tagCount = (int)extractArrayEntry(poseArray, 7);
double tagSpan = extractArrayEntry(poseArray, 8);
double tagDist = extractArrayEntry(poseArray, 9);
double tagArea = extractArrayEntry(poseArray, 10);
// Convert server timestamp from microseconds to seconds and adjust for latency
double adjustedTimestamp = (timestamp / 1000000.0) - (latency / 1000.0);
RawFiducial[] rawFiducials = new RawFiducial[tagCount];
int valsPerFiducial = 7;
int expectedTotalVals = 11 + valsPerFiducial * tagCount;
if (poseArray.length != expectedTotalVals) {
// Don't populate fiducials
} else {
for(int i = 0; i < tagCount; i++) {
int baseIndex = 11 + (i * valsPerFiducial);
int id = (int)poseArray[baseIndex];
double txnc = poseArray[baseIndex + 1];
double tync = poseArray[baseIndex + 2];
double ta = poseArray[baseIndex + 3];
double distToCamera = poseArray[baseIndex + 4];
double distToRobot = poseArray[baseIndex + 5];
double ambiguity = poseArray[baseIndex + 6];
rawFiducials[i] = new RawFiducial(id, txnc, tync, ta, distToCamera, distToRobot, ambiguity);
}
}
return new PoseEstimate(pose, adjustedTimestamp, latency, tagCount, tagSpan, tagDist, tagArea, rawFiducials, isMegaTag2);
}
/**
* Gets the latest raw fiducial/AprilTag detection results from NetworkTables.
*
* @param limelightName Name/identifier of the Limelight
* @return Array of RawFiducial objects containing detection details
*/
public static RawFiducial[] getRawFiducials(String limelightName) {
var entry = LimelightHelpers.getLimelightNTTableEntry(limelightName, "rawfiducials");
var rawFiducialArray = entry.getDoubleArray(new double[0]);
int valsPerEntry = 7;
if (rawFiducialArray.length % valsPerEntry != 0) {
return new RawFiducial[0];
}
int numFiducials = rawFiducialArray.length / valsPerEntry;
RawFiducial[] rawFiducials = new RawFiducial[numFiducials];
for (int i = 0; i < numFiducials; i++) {
int baseIndex = i * valsPerEntry;
int id = (int) extractArrayEntry(rawFiducialArray, baseIndex);
double txnc = extractArrayEntry(rawFiducialArray, baseIndex + 1);
double tync = extractArrayEntry(rawFiducialArray, baseIndex + 2);
double ta = extractArrayEntry(rawFiducialArray, baseIndex + 3);
double distToCamera = extractArrayEntry(rawFiducialArray, baseIndex + 4);
double distToRobot = extractArrayEntry(rawFiducialArray, baseIndex + 5);
double ambiguity = extractArrayEntry(rawFiducialArray, baseIndex + 6);
rawFiducials[i] = new RawFiducial(id, txnc, tync, ta, distToCamera, distToRobot, ambiguity);
}
return rawFiducials;
}
/**
* Gets the latest raw neural detector results from NetworkTables
*
* @param limelightName Name/identifier of the Limelight
* @return Array of RawDetection objects containing detection details
*/
public static RawDetection[] getRawDetections(String limelightName) {
var entry = LimelightHelpers.getLimelightNTTableEntry(limelightName, "rawdetections");
var rawDetectionArray = entry.getDoubleArray(new double[0]);
int valsPerEntry = 12;
if (rawDetectionArray.length % valsPerEntry != 0) {
return new RawDetection[0];
}
int numDetections = rawDetectionArray.length / valsPerEntry;
RawDetection[] rawDetections = new RawDetection[numDetections];
for (int i = 0; i < numDetections; i++) {
int baseIndex = i * valsPerEntry; // Starting index for this detection's data
int classId = (int) extractArrayEntry(rawDetectionArray, baseIndex);
double txnc = extractArrayEntry(rawDetectionArray, baseIndex + 1);
double tync = extractArrayEntry(rawDetectionArray, baseIndex + 2);
double ta = extractArrayEntry(rawDetectionArray, baseIndex + 3);
double corner0_X = extractArrayEntry(rawDetectionArray, baseIndex + 4);
double corner0_Y = extractArrayEntry(rawDetectionArray, baseIndex + 5);
double corner1_X = extractArrayEntry(rawDetectionArray, baseIndex + 6);
double corner1_Y = extractArrayEntry(rawDetectionArray, baseIndex + 7);
double corner2_X = extractArrayEntry(rawDetectionArray, baseIndex + 8);
double corner2_Y = extractArrayEntry(rawDetectionArray, baseIndex + 9);
double corner3_X = extractArrayEntry(rawDetectionArray, baseIndex + 10);
double corner3_Y = extractArrayEntry(rawDetectionArray, baseIndex + 11);
rawDetections[i] = new RawDetection(classId, txnc, tync, ta, corner0_X, corner0_Y, corner1_X, corner1_Y, corner2_X, corner2_Y, corner3_X, corner3_Y);
}
return rawDetections;
}
/**
* Prints detailed information about a PoseEstimate to standard output.
* Includes timestamp, latency, tag count, tag span, average tag distance,
* average tag area, and detailed information about each detected fiducial.
*
* @param pose The PoseEstimate object to print. If null, prints "No PoseEstimate available."
*/
public static void printPoseEstimate(PoseEstimate pose) {
if (pose == null) {
System.out.println("No PoseEstimate available.");
return;
}
System.out.printf("Pose Estimate Information:%n");
System.out.printf("Timestamp (Seconds): %.3f%n", pose.timestampSeconds);
System.out.printf("Latency: %.3f ms%n", pose.latency);
System.out.printf("Tag Count: %d%n", pose.tagCount);
System.out.printf("Tag Span: %.2f meters%n", pose.tagSpan);
System.out.printf("Average Tag Distance: %.2f meters%n", pose.avgTagDist);
System.out.printf("Average Tag Area: %.2f%% of image%n", pose.avgTagArea);
System.out.printf("Is MegaTag2: %b%n", pose.isMegaTag2);
System.out.println();
if (pose.rawFiducials == null || pose.rawFiducials.length == 0) {
System.out.println("No RawFiducials data available.");
return;
}
System.out.println("Raw Fiducials Details:");
for (int i = 0; i < pose.rawFiducials.length; i++) {
RawFiducial fiducial = pose.rawFiducials[i];
System.out.printf(" Fiducial #%d:%n", i + 1);
System.out.printf(" ID: %d%n", fiducial.id);
System.out.printf(" TXNC: %.2f%n", fiducial.txnc);
System.out.printf(" TYNC: %.2f%n", fiducial.tync);
System.out.printf(" TA: %.2f%n", fiducial.ta);
System.out.printf(" Distance to Camera: %.2f meters%n", fiducial.distToCamera);
System.out.printf(" Distance to Robot: %.2f meters%n", fiducial.distToRobot);
System.out.printf(" Ambiguity: %.2f%n", fiducial.ambiguity);
System.out.println();
}
}
public static Boolean validPoseEstimate(PoseEstimate pose) {
return pose != null && pose.rawFiducials != null && pose.rawFiducials.length != 0;
}
public static NetworkTable getLimelightNTTable(String tableName) {
return NetworkTableInstance.getDefault().getTable(sanitizeName(tableName));
}
public static void Flush() {
NetworkTableInstance.getDefault().flush();
}
public static NetworkTableEntry getLimelightNTTableEntry(String tableName, String entryName) {
return getLimelightNTTable(tableName).getEntry(entryName);
}
public static DoubleArrayEntry getLimelightDoubleArrayEntry(String tableName, String entryName) {
String key = tableName + "/" + entryName;
return doubleArrayEntries.computeIfAbsent(key, k -> {
NetworkTable table = getLimelightNTTable(tableName);
return table.getDoubleArrayTopic(entryName).getEntry(new double[0]);
});
}
public static double getLimelightNTDouble(String tableName, String entryName) {
return getLimelightNTTableEntry(tableName, entryName).getDouble(0.0);
}
public static void setLimelightNTDouble(String tableName, String entryName, double val) {
getLimelightNTTableEntry(tableName, entryName).setDouble(val);
}
public static void setLimelightNTDoubleArray(String tableName, String entryName, double[] val) {
getLimelightNTTableEntry(tableName, entryName).setDoubleArray(val);
}
public static double[] getLimelightNTDoubleArray(String tableName, String entryName) {
return getLimelightNTTableEntry(tableName, entryName).getDoubleArray(new double[0]);
}
public static String getLimelightNTString(String tableName, String entryName) {
return getLimelightNTTableEntry(tableName, entryName).getString("");
}
public static String[] getLimelightNTStringArray(String tableName, String entryName) {
return getLimelightNTTableEntry(tableName, entryName).getStringArray(new String[0]);
}
public static URL getLimelightURLString(String tableName, String request) {
String urlString = "http://" + sanitizeName(tableName) + ".local:5807/" + request;
URL url;
try {
url = new URL(urlString);
return url;
} catch (MalformedURLException e) {
System.err.println("bad LL URL");
}
return null;
}
/////
/////
/**
* Does the Limelight have a valid target?
* @param limelightName Name of the Limelight camera ("" for default)
* @return True if a valid target is present, false otherwise
*/
public static boolean getTV(String limelightName) {
return 1.0 == getLimelightNTDouble(limelightName, "tv");
}
/**
* Gets the horizontal offset from the crosshair to the target in degrees.
* @param limelightName Name of the Limelight camera ("" for default)
* @return Horizontal offset angle in degrees
*/
public static double getTX(String limelightName) {
return getLimelightNTDouble(limelightName, "tx");
}
/**
* Gets the vertical offset from the crosshair to the target in degrees.
* @param limelightName Name of the Limelight camera ("" for default)
* @return Vertical offset angle in degrees
*/
public static double getTY(String limelightName) {
return getLimelightNTDouble(limelightName, "ty");
}
/**
* Gets the horizontal offset from the principal pixel/point to the target in degrees. This is the most accurate 2d metric if you are using a calibrated camera and you don't need adjustable crosshair functionality.
* @param limelightName Name of the Limelight camera ("" for default)
* @return Horizontal offset angle in degrees
*/
public static double getTXNC(String limelightName) {
return getLimelightNTDouble(limelightName, "txnc");
}
/**
* Gets the vertical offset from the principal pixel/point to the target in degrees. This is the most accurate 2d metric if you are using a calibrated camera and you don't need adjustable crosshair functionality.
* @param limelightName Name of the Limelight camera ("" for default)
* @return Vertical offset angle in degrees
*/
public static double getTYNC(String limelightName) {