Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions photon-client/src/components/app/photon-camera-stream.vue
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
<script setup lang="ts">
import { computed, inject, ref, onBeforeUnmount } from "vue";
import { useStateStore } from "@/stores/StateStore";
import { useCameraSettingsStore } from "@/stores/settings/CameraSettingsStore";
import loadingImage from "@/assets/images/loading-transparent.svg";
import type { StyleValue } from "vue/types/jsx";
import PvIcon from "@/components/common/pv-icon.vue";
Expand Down Expand Up @@ -58,9 +59,9 @@ const overlayStyle = computed<StyleValue>(() => {

const handleCaptureClick = () => {
if (props.streamType === "Raw") {
props.cameraSettings.pipelineSettings[props.cameraSettings.currentPipelineIndex].saveInputSnapshot();
useCameraSettingsStore().saveInputSnapshot();
} else {
props.cameraSettings.pipelineSettings[props.cameraSettings.currentPipelineIndex].saveOutputSnapshot();
useCameraSettingsStore().saveOutputSnapshot();
}
};
const handlePopoutClick = () => {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,11 @@

package org.photonvision.vision.frame.consumer;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.networktables.IntegerEntry;
import edu.wpi.first.networktables.IntegerSubscriber;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.StringSubscriber;
import edu.wpi.first.wpilibj.DriverStation.MatchType;
import java.io.File;
import java.text.DateFormat;
import java.text.SimpleDateFormat;
Expand All @@ -38,21 +38,18 @@
public class FileSaveFrameConsumer implements Consumer<CVMat> {
private final Logger logger = new Logger(FileSaveFrameConsumer.class, LogGroup.General);

// match type's values from the FMS.
private static final String[] matchTypes = {"N/A", "P", "Q", "E", "EV"};

// Formatters to generate unique, timestamped file names
private static final String FILE_PATH = ConfigManager.getInstance().getImageSavePath().toString();
private static final String FILE_EXTENSION = ".jpg";
static final String FILE_EXTENSION = ".jpg";
private static final String NT_SUFFIX = "SaveImgCmd";

DateFormat df = new SimpleDateFormat("yyyy-MM-dd");
DateFormat tf = new SimpleDateFormat("hhmmssSS");
static final DateFormat df = new SimpleDateFormat("yyyy-MM-dd");
static final DateFormat tf = new SimpleDateFormat("hhmmssSS");

private final NetworkTable rootTable;
private NetworkTable subTable;
private final String ntEntryName;
private IntegerEntry saveFrameEntry;
IntegerEntry saveFrameEntry;

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

NetworkTable fmsTable = NetworkTablesManager.getInstance().getNTInst().getTable("FMSInfo");
this.ntEventName = fmsTable.getStringTopic("EventName").subscribe("UNKNOWN");
this.ntMatchNum = fmsTable.getIntegerTopic("MatchNumber").subscribe(-1);
this.ntMatchNum = fmsTable.getIntegerTopic("MatchNumber").subscribe(0);
this.ntMatchType = fmsTable.getIntegerTopic("MatchType").subscribe(0);

updateCameraNickname(camNickname);
}

public void accept(CVMat image) {
accept(image, new Date());
}

public void accept(CVMat image, Date now) {
long currentCount = saveFrameEntry.get();

System.out.println("currentCount: " + currentCount + " savedImagesCount: " + savedImagesCount);

// Await save request
if (currentCount == -1) return;

// The requested count is greater than the actual count
if (savedImagesCount < currentCount) {
Date now = new Date();
String matchData = getMatchData();

String fileName =
cameraNickname
Expand All @@ -99,7 +102,7 @@ public void accept(CVMat image) {
+ "T"
+ tf.format(now)
+ "_"
+ getMatchData();
+ matchData;

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

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

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

/**
* Returns the match Data collected from the NT. eg : Q58 for qualification match 58. If not in
* event, returns N/A-0-EVENTNAME
* event, returns None-0-Unknown
*/
private String getMatchData() {
var matchType = ntMatchType.getAtomic();
if (matchType.timestamp == 0) {
// no NT info yet
logger.warn("Did not receive match type, defaulting to 0");
logger.warn("Did not receive match type, defaulting to None");
}

var matchNum = ntMatchNum.getAtomic();
if (matchNum.timestamp == 0) {
logger.warn("Did not receive match num, defaulting to -1");
logger.warn("Did not receive match num, defaulting to 0");
}

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

String matchTypeStr =
matchTypes[MathUtil.clamp((int) matchType.value, 0, matchTypes.length - 1)];
return matchTypeStr + "-" + matchNum.value + "-" + eventName.value;
MatchType wpiMatchType = MatchType.None; // Default is to be unknown
if (matchType.value < 0 || matchType.value >= MatchType.values().length) {
logger.error("Invalid match type from FMS: " + matchType.value);
} else {
wpiMatchType = MatchType.values()[(int) matchType.value];
}

return wpiMatchType.name() + "-" + matchNum.value + "-" + eventName.value;
}

public void close() {
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,138 @@
/*
* Copyright (C) Photon Vision.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/

package org.photonvision.vision.frame.consumer;

import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertNull;
import static org.junit.jupiter.api.Assertions.assertTrue;
import static org.junit.jupiter.api.Assertions.fail;

import edu.wpi.first.hal.HAL;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.MatchType;
import edu.wpi.first.wpilibj.simulation.DriverStationSim;
import edu.wpi.first.wpilibj.simulation.SimHooks;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import java.io.File;
import java.io.IOException;
import java.util.Date;
import org.junit.jupiter.api.AfterEach;
import org.junit.jupiter.api.BeforeAll;
import org.junit.jupiter.api.BeforeEach;
import org.junitpioneer.jupiter.cartesian.CartesianTest;
import org.junitpioneer.jupiter.cartesian.CartesianTest.Enum;
import org.junitpioneer.jupiter.cartesian.CartesianTest.Values;
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.dataflow.networktables.NetworkTablesManager;
import org.photonvision.common.util.TestUtils;
import org.photonvision.jni.PhotonTargetingJniLoader;
import org.photonvision.jni.WpilibLoader;
import org.photonvision.vision.frame.provider.FileFrameProvider;

public class FileSaveFrameConsumerTest {
NetworkTableInstance inst = null;

@BeforeAll
public static void init() throws UnsatisfiedLinkError, IOException {
if (!WpilibLoader.loadLibraries()) {
fail();
}

try {
if (!PhotonTargetingJniLoader.load()) fail();
} catch (UnsatisfiedLinkError | IOException e) {
e.printStackTrace();
fail(e);
}
}

@BeforeEach
public void setup() {
assertNull(inst);

HAL.initialize(500, 0);

inst = NetworkTablesManager.getInstance().getNTInst();
inst.stopClient();
inst.stopServer();
inst.startLocal();
SmartDashboard.setNetworkTableInstance(inst);

// DriverStation uses the default instance internally
assertEquals(NetworkTableInstance.getDefault(), inst);
}

@AfterEach
public void teardown() {
SimHooks.resumeTiming();

HAL.shutdown();
}

@CartesianTest
public void testNoMatch(
@Enum(MatchType.class) MatchType matchType, @Values(ints = {0, 1, 0xffff}) int matchNumber) {
String camNickname = "foobar";
String cameraUniqueName = "some_unique";
String streamPrefix = "input";

// GIVEN an input consumer
FileSaveFrameConsumer consumer =
new FileSaveFrameConsumer(camNickname, cameraUniqueName, streamPrefix);

// AND a frameProvider giving a random test mode image
var frameProvider =
new FileFrameProvider(
TestUtils.getWPIImagePath(TestUtils.WPI2019Image.kCargoSideStraightDark72in, false),
TestUtils.WPI2019Image.FOV);

// AND fake FMS data
String eventName = "CASJ";
DriverStationSim.setMatchType(matchType);
DriverStationSim.setMatchNumber(matchNumber);
DriverStationSim.setEventName(eventName);
DriverStation.refreshData();

// WHEN we save the image
var currentTime = new Date();
var counterPublisher = consumer.saveFrameEntry.getTopic().publish();
counterPublisher.accept(1);
consumer.accept(frameProvider.get().colorImage, currentTime);

// THEN an image will be created on disk
File expectedSnapshot =
ConfigManager.getInstance()
.getImageSavePath()
.resolve(cameraUniqueName)
.resolve(
camNickname
+ "_"
+ streamPrefix
+ "_"
+ FileSaveFrameConsumer.df.format(currentTime)
+ "T"
+ FileSaveFrameConsumer.tf.format(currentTime)
+ "_"
+ (matchType.name() + "-" + matchNumber + "-" + eventName)
+ FileSaveFrameConsumer.FILE_EXTENSION)
.toFile();
System.out.println("Checking that file exists: " + expectedSnapshot.getAbsolutePath());
assertTrue(expectedSnapshot.exists());
}
}
Loading