17
17
18
18
package org .photonvision .vision .frame .consumer ;
19
19
20
+ import edu .wpi .first .math .MathUtil ;
20
21
import edu .wpi .first .networktables .IntegerEntry ;
22
+ import edu .wpi .first .networktables .IntegerSubscriber ;
21
23
import edu .wpi .first .networktables .NetworkTable ;
24
+ import edu .wpi .first .networktables .StringSubscriber ;
22
25
import java .io .File ;
23
26
import java .text .DateFormat ;
24
27
import java .text .SimpleDateFormat ;
35
38
public class FileSaveFrameConsumer implements Consumer <CVMat > {
36
39
private final Logger logger = new Logger (FileSaveFrameConsumer .class , LogGroup .General );
37
40
41
+ // match type's values from the FMS.
42
+ private static final String [] matchTypes = {"N/A" , "P" , "Q" , "E" , "EV" };
43
+
38
44
// Formatters to generate unique, timestamped file names
39
45
private static final String FILE_PATH = ConfigManager .getInstance ().getImageSavePath ().toString ();
40
46
private static final String FILE_EXTENSION = ".jpg" ;
@@ -48,6 +54,10 @@ public class FileSaveFrameConsumer implements Consumer<CVMat> {
48
54
private final String ntEntryName ;
49
55
private IntegerEntry saveFrameEntry ;
50
56
57
+ private StringSubscriber ntEventName ;
58
+ private IntegerSubscriber ntMatchNum ;
59
+ private IntegerSubscriber ntMatchType ;
60
+
51
61
private final String cameraUniqueName ;
52
62
private String cameraNickname ;
53
63
private final String streamType ;
@@ -61,6 +71,12 @@ public FileSaveFrameConsumer(String camNickname, String cameraUniqueName, String
61
71
this .streamType = streamPrefix ;
62
72
63
73
this .rootTable = NetworkTablesManager .getInstance ().kRootTable ;
74
+
75
+ NetworkTable fmsTable = NetworkTablesManager .getInstance ().getNTInst ().getTable ("FMSInfo" );
76
+ this .ntEventName = fmsTable .getStringTopic ("EventName" ).subscribe ("UNKNOWN" );
77
+ this .ntMatchNum = fmsTable .getIntegerTopic ("MatchNumber" ).subscribe (-1 );
78
+ this .ntMatchType = fmsTable .getIntegerTopic ("MatchType" ).subscribe (0 );
79
+
64
80
updateCameraNickname (camNickname );
65
81
}
66
82
@@ -75,7 +91,15 @@ public void accept(CVMat image) {
75
91
Date now = new Date ();
76
92
77
93
String fileName =
78
- cameraNickname + "_" + streamType + "_" + df .format (now ) + "T" + tf .format (now );
94
+ cameraNickname
95
+ + "_"
96
+ + streamType
97
+ + "_"
98
+ + df .format (now )
99
+ + "T"
100
+ + tf .format (now )
101
+ + "_"
102
+ + getMatchData ();
79
103
80
104
// Check if the Unique Camera directory exists and create it if it doesn't
81
105
String cameraPath = FILE_PATH + File .separator + this .cameraUniqueName ;
@@ -119,4 +143,30 @@ public void overrideTakeSnapshot() {
119
143
// Simulate NT change
120
144
saveFrameEntry .set (saveFrameEntry .get () + 1 );
121
145
}
146
+
147
+ /**
148
+ * Returns the match Data collected from the NT. eg : Q58 for qualfication match 58. If not in
149
+ * event, returns N/A-0-EVENTNAME
150
+ */
151
+ private String getMatchData () {
152
+ var matchType = ntMatchType .getAtomic ();
153
+ if (matchType .timestamp == 0 ) {
154
+ // no NT info yet
155
+ logger .warn ("Did not recieve match type, defaulting to 0" );
156
+ }
157
+
158
+ var matchNum = ntMatchNum .getAtomic ();
159
+ if (matchNum .timestamp == 0 ) {
160
+ logger .warn ("Did not recieve match num, defaulting to -1" );
161
+ }
162
+
163
+ var eventName = ntEventName .getAtomic ();
164
+ if (eventName .timestamp == 0 ) {
165
+ logger .warn ("Did not recieve event name, defaulting to 'UNKNOWN'" );
166
+ }
167
+
168
+ String matchTypeStr =
169
+ matchTypes [MathUtil .clamp ((int ) matchType .value , 0 , matchTypes .length - 1 )];
170
+ return matchTypeStr + "-" + matchNum .value + "-" + eventName .value ;
171
+ }
122
172
}
0 commit comments