Skip to content

Commit de98f5f

Browse files
authored
Fix snapshot methods not working (#1815)
1 parent 3064580 commit de98f5f

File tree

3 files changed

+167
-19
lines changed

3 files changed

+167
-19
lines changed

photon-client/src/components/app/photon-camera-stream.vue

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
<script setup lang="ts">
22
import { computed, inject, ref, onBeforeUnmount } from "vue";
33
import { useStateStore } from "@/stores/StateStore";
4+
import { useCameraSettingsStore } from "@/stores/settings/CameraSettingsStore";
45
import loadingImage from "@/assets/images/loading-transparent.svg";
56
import type { StyleValue } from "vue/types/jsx";
67
import PvIcon from "@/components/common/pv-icon.vue";
@@ -58,9 +59,9 @@ const overlayStyle = computed<StyleValue>(() => {
5859
5960
const handleCaptureClick = () => {
6061
if (props.streamType === "Raw") {
61-
props.cameraSettings.pipelineSettings[props.cameraSettings.currentPipelineIndex].saveInputSnapshot();
62+
useCameraSettingsStore().saveInputSnapshot();
6263
} else {
63-
props.cameraSettings.pipelineSettings[props.cameraSettings.currentPipelineIndex].saveOutputSnapshot();
64+
useCameraSettingsStore().saveOutputSnapshot();
6465
}
6566
};
6667
const handlePopoutClick = () => {

photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java

Lines changed: 26 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -17,11 +17,11 @@
1717

1818
package org.photonvision.vision.frame.consumer;
1919

20-
import edu.wpi.first.math.MathUtil;
2120
import edu.wpi.first.networktables.IntegerEntry;
2221
import edu.wpi.first.networktables.IntegerSubscriber;
2322
import edu.wpi.first.networktables.NetworkTable;
2423
import edu.wpi.first.networktables.StringSubscriber;
24+
import edu.wpi.first.wpilibj.DriverStation.MatchType;
2525
import java.io.File;
2626
import java.text.DateFormat;
2727
import java.text.SimpleDateFormat;
@@ -38,21 +38,18 @@
3838
public class FileSaveFrameConsumer implements Consumer<CVMat> {
3939
private final Logger logger = new Logger(FileSaveFrameConsumer.class, LogGroup.General);
4040

41-
// match type's values from the FMS.
42-
private static final String[] matchTypes = {"N/A", "P", "Q", "E", "EV"};
43-
4441
// Formatters to generate unique, timestamped file names
4542
private static final String FILE_PATH = ConfigManager.getInstance().getImageSavePath().toString();
46-
private static final String FILE_EXTENSION = ".jpg";
43+
static final String FILE_EXTENSION = ".jpg";
4744
private static final String NT_SUFFIX = "SaveImgCmd";
4845

49-
DateFormat df = new SimpleDateFormat("yyyy-MM-dd");
50-
DateFormat tf = new SimpleDateFormat("hhmmssSS");
46+
static final DateFormat df = new SimpleDateFormat("yyyy-MM-dd");
47+
static final DateFormat tf = new SimpleDateFormat("hhmmssSS");
5148

5249
private final NetworkTable rootTable;
5350
private NetworkTable subTable;
5451
private final String ntEntryName;
55-
private IntegerEntry saveFrameEntry;
52+
IntegerEntry saveFrameEntry;
5653

5754
private StringSubscriber ntEventName;
5855
private IntegerSubscriber ntMatchNum;
@@ -74,21 +71,27 @@ public FileSaveFrameConsumer(String camNickname, String cameraUniqueName, String
7471

7572
NetworkTable fmsTable = NetworkTablesManager.getInstance().getNTInst().getTable("FMSInfo");
7673
this.ntEventName = fmsTable.getStringTopic("EventName").subscribe("UNKNOWN");
77-
this.ntMatchNum = fmsTable.getIntegerTopic("MatchNumber").subscribe(-1);
74+
this.ntMatchNum = fmsTable.getIntegerTopic("MatchNumber").subscribe(0);
7875
this.ntMatchType = fmsTable.getIntegerTopic("MatchType").subscribe(0);
7976

8077
updateCameraNickname(camNickname);
8178
}
8279

8380
public void accept(CVMat image) {
81+
accept(image, new Date());
82+
}
83+
84+
public void accept(CVMat image, Date now) {
8485
long currentCount = saveFrameEntry.get();
8586

87+
System.out.println("currentCount: " + currentCount + " savedImagesCount: " + savedImagesCount);
88+
8689
// Await save request
8790
if (currentCount == -1) return;
8891

8992
// The requested count is greater than the actual count
9093
if (savedImagesCount < currentCount) {
91-
Date now = new Date();
94+
String matchData = getMatchData();
9295

9396
String fileName =
9497
cameraNickname
@@ -99,7 +102,7 @@ public void accept(CVMat image) {
99102
+ "T"
100103
+ tf.format(now)
101104
+ "_"
102-
+ getMatchData();
105+
+ matchData;
103106

104107
// Check if the Unique Camera directory exists and create it if it doesn't
105108
String cameraPath = FILE_PATH + File.separator + this.cameraUniqueName;
@@ -110,6 +113,7 @@ public void accept(CVMat image) {
110113

111114
String saveFilePath = cameraPath + File.separator + fileName + FILE_EXTENSION;
112115

116+
logger.info("Saving image to: " + saveFilePath);
113117
if (image == null || image.getMat() == null || image.getMat().empty()) {
114118
Imgcodecs.imwrite(saveFilePath, StaticFrames.LOST_MAT);
115119
} else {
@@ -146,28 +150,33 @@ public void overrideTakeSnapshot() {
146150

147151
/**
148152
* Returns the match Data collected from the NT. eg : Q58 for qualification match 58. If not in
149-
* event, returns N/A-0-EVENTNAME
153+
* event, returns None-0-Unknown
150154
*/
151155
private String getMatchData() {
152156
var matchType = ntMatchType.getAtomic();
153157
if (matchType.timestamp == 0) {
154158
// no NT info yet
155-
logger.warn("Did not receive match type, defaulting to 0");
159+
logger.warn("Did not receive match type, defaulting to None");
156160
}
157161

158162
var matchNum = ntMatchNum.getAtomic();
159163
if (matchNum.timestamp == 0) {
160-
logger.warn("Did not receive match num, defaulting to -1");
164+
logger.warn("Did not receive match num, defaulting to 0");
161165
}
162166

163167
var eventName = ntEventName.getAtomic();
164168
if (eventName.timestamp == 0) {
165169
logger.warn("Did not receive event name, defaulting to 'UNKNOWN'");
166170
}
167171

168-
String matchTypeStr =
169-
matchTypes[MathUtil.clamp((int) matchType.value, 0, matchTypes.length - 1)];
170-
return matchTypeStr + "-" + matchNum.value + "-" + eventName.value;
172+
MatchType wpiMatchType = MatchType.None; // Default is to be unknown
173+
if (matchType.value < 0 || matchType.value >= MatchType.values().length) {
174+
logger.error("Invalid match type from FMS: " + matchType.value);
175+
} else {
176+
wpiMatchType = MatchType.values()[(int) matchType.value];
177+
}
178+
179+
return wpiMatchType.name() + "-" + matchNum.value + "-" + eventName.value;
171180
}
172181

173182
public void close() {
Lines changed: 138 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,138 @@
1+
/*
2+
* Copyright (C) Photon Vision.
3+
*
4+
* This program is free software: you can redistribute it and/or modify
5+
* it under the terms of the GNU General Public License as published by
6+
* the Free Software Foundation, either version 3 of the License, or
7+
* (at your option) any later version.
8+
*
9+
* This program is distributed in the hope that it will be useful,
10+
* but WITHOUT ANY WARRANTY; without even the implied warranty of
11+
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12+
* GNU General Public License for more details.
13+
*
14+
* You should have received a copy of the GNU General Public License
15+
* along with this program. If not, see <https://www.gnu.org/licenses/>.
16+
*/
17+
18+
package org.photonvision.vision.frame.consumer;
19+
20+
import static org.junit.jupiter.api.Assertions.assertEquals;
21+
import static org.junit.jupiter.api.Assertions.assertNull;
22+
import static org.junit.jupiter.api.Assertions.assertTrue;
23+
import static org.junit.jupiter.api.Assertions.fail;
24+
25+
import edu.wpi.first.hal.HAL;
26+
import edu.wpi.first.networktables.NetworkTableInstance;
27+
import edu.wpi.first.wpilibj.DriverStation;
28+
import edu.wpi.first.wpilibj.DriverStation.MatchType;
29+
import edu.wpi.first.wpilibj.simulation.DriverStationSim;
30+
import edu.wpi.first.wpilibj.simulation.SimHooks;
31+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
32+
import java.io.File;
33+
import java.io.IOException;
34+
import java.util.Date;
35+
import org.junit.jupiter.api.AfterEach;
36+
import org.junit.jupiter.api.BeforeAll;
37+
import org.junit.jupiter.api.BeforeEach;
38+
import org.junitpioneer.jupiter.cartesian.CartesianTest;
39+
import org.junitpioneer.jupiter.cartesian.CartesianTest.Enum;
40+
import org.junitpioneer.jupiter.cartesian.CartesianTest.Values;
41+
import org.photonvision.common.configuration.ConfigManager;
42+
import org.photonvision.common.dataflow.networktables.NetworkTablesManager;
43+
import org.photonvision.common.util.TestUtils;
44+
import org.photonvision.jni.PhotonTargetingJniLoader;
45+
import org.photonvision.jni.WpilibLoader;
46+
import org.photonvision.vision.frame.provider.FileFrameProvider;
47+
48+
public class FileSaveFrameConsumerTest {
49+
NetworkTableInstance inst = null;
50+
51+
@BeforeAll
52+
public static void init() throws UnsatisfiedLinkError, IOException {
53+
if (!WpilibLoader.loadLibraries()) {
54+
fail();
55+
}
56+
57+
try {
58+
if (!PhotonTargetingJniLoader.load()) fail();
59+
} catch (UnsatisfiedLinkError | IOException e) {
60+
e.printStackTrace();
61+
fail(e);
62+
}
63+
}
64+
65+
@BeforeEach
66+
public void setup() {
67+
assertNull(inst);
68+
69+
HAL.initialize(500, 0);
70+
71+
inst = NetworkTablesManager.getInstance().getNTInst();
72+
inst.stopClient();
73+
inst.stopServer();
74+
inst.startLocal();
75+
SmartDashboard.setNetworkTableInstance(inst);
76+
77+
// DriverStation uses the default instance internally
78+
assertEquals(NetworkTableInstance.getDefault(), inst);
79+
}
80+
81+
@AfterEach
82+
public void teardown() {
83+
SimHooks.resumeTiming();
84+
85+
HAL.shutdown();
86+
}
87+
88+
@CartesianTest
89+
public void testNoMatch(
90+
@Enum(MatchType.class) MatchType matchType, @Values(ints = {0, 1, 0xffff}) int matchNumber) {
91+
String camNickname = "foobar";
92+
String cameraUniqueName = "some_unique";
93+
String streamPrefix = "input";
94+
95+
// GIVEN an input consumer
96+
FileSaveFrameConsumer consumer =
97+
new FileSaveFrameConsumer(camNickname, cameraUniqueName, streamPrefix);
98+
99+
// AND a frameProvider giving a random test mode image
100+
var frameProvider =
101+
new FileFrameProvider(
102+
TestUtils.getWPIImagePath(TestUtils.WPI2019Image.kCargoSideStraightDark72in, false),
103+
TestUtils.WPI2019Image.FOV);
104+
105+
// AND fake FMS data
106+
String eventName = "CASJ";
107+
DriverStationSim.setMatchType(matchType);
108+
DriverStationSim.setMatchNumber(matchNumber);
109+
DriverStationSim.setEventName(eventName);
110+
DriverStation.refreshData();
111+
112+
// WHEN we save the image
113+
var currentTime = new Date();
114+
var counterPublisher = consumer.saveFrameEntry.getTopic().publish();
115+
counterPublisher.accept(1);
116+
consumer.accept(frameProvider.get().colorImage, currentTime);
117+
118+
// THEN an image will be created on disk
119+
File expectedSnapshot =
120+
ConfigManager.getInstance()
121+
.getImageSavePath()
122+
.resolve(cameraUniqueName)
123+
.resolve(
124+
camNickname
125+
+ "_"
126+
+ streamPrefix
127+
+ "_"
128+
+ FileSaveFrameConsumer.df.format(currentTime)
129+
+ "T"
130+
+ FileSaveFrameConsumer.tf.format(currentTime)
131+
+ "_"
132+
+ (matchType.name() + "-" + matchNumber + "-" + eventName)
133+
+ FileSaveFrameConsumer.FILE_EXTENSION)
134+
.toFile();
135+
System.out.println("Checking that file exists: " + expectedSnapshot.getAbsolutePath());
136+
assertTrue(expectedSnapshot.exists());
137+
}
138+
}

0 commit comments

Comments
 (0)