Skip to content
Draft
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
Original file line number Diff line number Diff line change
Expand Up @@ -23,14 +23,19 @@
import java.nio.file.Path;
import java.util.HashMap;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.vision.frame.FrameProvider;
import org.photonvision.vision.frame.FrameStaticProperties;
import org.photonvision.vision.frame.provider.FileFrameProvider;
import org.photonvision.vision.frame.provider.VideoFrameProvider;
import org.photonvision.vision.processes.VisionSource;
import org.photonvision.vision.processes.VisionSourceSettables;

public class FileVisionSource extends VisionSource {
private final FileFrameProvider frameProvider;
private static final Logger logger = new Logger(FileVisionSource.class, LogGroup.Camera);

private final FrameProvider frameProvider;
private final FileSourceSettables settables;

public FileVisionSource(CameraConfiguration cameraConfiguration) {
Expand All @@ -39,13 +44,20 @@ public FileVisionSource(CameraConfiguration cameraConfiguration) {
!cameraConfiguration.calibrations.isEmpty()
? cameraConfiguration.calibrations.get(0)
: null;
frameProvider =
new FileFrameProvider(
// TODO - create new File/replay camera info type
Path.of(cameraConfiguration.getDevicePath()),
cameraConfiguration.FOV,
FileFrameProvider.MAX_FPS,
calibration);

var path = Path.of(cameraConfiguration.getDevicePath());

if (path.endsWith(".png") || path.endsWith(".jpg") || path.endsWith(".jpeg")) {
logger.info("Using image file: " + path.toAbsolutePath());

frameProvider =
new FileFrameProvider(
// TODO - create new File/replay camera info type
path, cameraConfiguration.FOV, FileFrameProvider.MAX_FPS, calibration);
} else {
logger.info("Looks like a video file, using as replay: " + path.toAbsolutePath());
frameProvider = new VideoFrameProvider(path, cameraConfiguration.FOV, calibration);
}

if (getCameraConfiguration().cameraQuirks == null)
getCameraConfiguration().cameraQuirks = QuirkyCamera.DefaultCamera;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,12 @@
import org.photonvision.vision.frame.FrameProvider;
import org.photonvision.vision.frame.FrameStaticProperties;
import org.photonvision.vision.opencv.CVMat;
import org.photonvision.vision.opencv.Releasable;

/**
* A {@link FrameProvider} that will read and provide an image from a {@link java.nio.file.Path
* path}.
*/
public class FileFrameProvider extends CpuImageProcessor implements Releasable {
public class FileFrameProvider extends CpuImageProcessor {
public static final int MAX_FPS = 10;
private static int count = 0;

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,129 @@
/*
* 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.provider;

import java.nio.file.Path;
import org.opencv.videoio.VideoCapture;
import org.opencv.videoio.Videoio;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.common.util.math.MathUtils;
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
import org.photonvision.vision.frame.FrameProvider;
import org.photonvision.vision.frame.FrameStaticProperties;
import org.photonvision.vision.opencv.CVMat;

/**
* A {@link FrameProvider} that will read and provide an image from a {@link java.nio.file.Path
* path}.
*/
public class VideoFrameProvider extends CpuImageProcessor {
private static final Logger logger = new Logger(VideoFrameProvider.class, LogGroup.Camera);

private final FrameStaticProperties properties;
private Path path;
private VideoCapture reader;

private long lastGetMillis = System.currentTimeMillis();
private final int millisDelay;

public VideoFrameProvider(Path path, double fov, CameraCalibrationCoefficients calibration) {
this.path = path;

String absPath = path.toAbsolutePath().toString();
this.reader = new VideoCapture(absPath);

if (!reader.isOpened()) {
logger.error("Failed to open video file: " + absPath);
throw new IllegalArgumentException("Cannot open video file: " + absPath);
}

logger.info(
"Opened video file: "
+ path.toAbsolutePath()
+ " using backend "
+ reader.getBackendName());

// Get FPS
var fps = reader.get(Videoio.CAP_PROP_FPS);
if (fps <= 0) {
logger.warn("Could not determine FPS, defaulting to 30");
}
this.millisDelay = (int) (1000 / fps);

// Figure out resolution of the video file
var rawImage = new CVMat();
reader.read(rawImage.getMat());
this.properties =
new FrameStaticProperties(
rawImage.getMat().width(), rawImage.getMat().height(), fov, calibration);
rawImage.release();
}

@Override
public CapturedFrame getInputMat() {
// sleep to match fps
if (System.currentTimeMillis() - lastGetMillis < millisDelay) {
try {
Thread.sleep(millisDelay);
} catch (InterruptedException e) {
System.err.println("FileFrameProvider interrupted - not busywaiting");
// throw back up the stack
throw new RuntimeException(e);
}
}
lastGetMillis = System.currentTimeMillis();

var out = new CVMat();

boolean read = reader.read(out.getMat());
if (!read) {
// loop
logger.info("Rewinding video file for next tick: " + path.toAbsolutePath());
reader.release();
reader = new VideoCapture(path.toAbsolutePath().toString());
}

return new CapturedFrame(out, properties, MathUtils.wpiNanoTime());
}

@Override
public String getName() {
return "FileFrameProvider-" + this.path;
}

@Override
public void release() {
reader.release();
}

@Override
public boolean checkCameraConnected() {
return true;
}

@Override
public boolean isConnected() {
return true;
}

@Override
public boolean hasConnected() {
return true;
}
}
61 changes: 22 additions & 39 deletions photon-server/src/main/java/org/photonvision/Main.java
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,6 @@ public class Main {

private static boolean isTestMode = false;
private static boolean isSmoketest = false;
private static Path testModeFolder = null;
private static boolean printDebugLogs;

private static boolean handleArgs(String[] args) throws ParseException {
Expand All @@ -72,7 +71,6 @@ private static boolean handleArgs(String[] args) throws ParseException {
false,
"Run in test mode with 2019 and 2020 WPI field images in place of cameras");

options.addOption("p", "path", true, "Point test mode to a specific folder");
options.addOption("n", "disable-networking", false, "Disables control device network settings");
options.addOption(
"c",
Expand Down Expand Up @@ -101,12 +99,6 @@ private static boolean handleArgs(String[] args) throws ParseException {
if (cmd.hasOption("test-mode")) {
isTestMode = true;
logger.info("Running in test mode - Cameras will not be used");

if (cmd.hasOption("path")) {
Path p = Path.of(System.getProperty("PATH_PREFIX", "") + cmd.getOptionValue("path"));
logger.info("Loading from Path " + p.toAbsolutePath().toString());
testModeFolder = p;
}
}

if (cmd.hasOption("disable-networking")) {
Expand All @@ -127,34 +119,27 @@ private static boolean handleArgs(String[] args) throws ParseException {
private static void addTestModeSources() {
ConfigManager.getInstance().load();

CameraConfiguration camConf2024 =
ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2024");
if (camConf2024 == null || true) {
camConf2024 =
new CameraConfiguration(
PVCameraInfo.fromFileInfo(
TestUtils.getResourcesFolderPath(true)
.resolve("testimages")
.resolve(TestUtils.WPI2024Images.kSpeakerCenter_143in.path)
.toString(),
"WPI2024"));

camConf2024.FOV = TestUtils.WPI2024Images.FOV;
// same camera as 2023
camConf2024.calibrations.add(TestUtils.get2023LifeCamCoeffs(true));

var pipeline2024 = new AprilTagPipelineSettings();
var path_split = Path.of(camConf2024.matchedCameraInfo.path()).getFileName().toString();
pipeline2024.pipelineNickname = path_split.replace(".jpg", "");
pipeline2024.targetModel = TargetModel.kAprilTag6p5in_36h11;
pipeline2024.tagFamily = AprilTagFamily.kTag36h11;
pipeline2024.inputShouldShow = true;
pipeline2024.solvePNPEnabled = true;

var psList2024 = new ArrayList<CVPipelineSettings>();
psList2024.add(pipeline2024);
camConf2024.pipelineSettings = psList2024;
}
var camConf2024 =
new CameraConfiguration(
PVCameraInfo.fromFileInfo(
// "C:\\Users\\Matt\\Documents\\GitHub\\photonvision\\test-video\\poseest_demo.mp4",
"C:\\Users\\Matt\\Videos\\Captures\\inception.mp4", "foobar"));

camConf2024.FOV = TestUtils.WPI2024Images.FOV;
// same camera as 2023
camConf2024.calibrations.add(TestUtils.get2023LifeCamCoeffs(true));

var pipeline2024 = new AprilTagPipelineSettings();
var path_split = Path.of(camConf2024.matchedCameraInfo.path()).getFileName().toString();
pipeline2024.pipelineNickname = path_split.replace(".jpg", "");
pipeline2024.targetModel = TargetModel.kAprilTag6p5in_36h11;
pipeline2024.tagFamily = AprilTagFamily.kTag36h11;
pipeline2024.inputShouldShow = true;
pipeline2024.solvePNPEnabled = true;

var psList2024 = new ArrayList<CVPipelineSettings>();
psList2024.add(pipeline2024);
camConf2024.pipelineSettings = psList2024;

var cameraConfigs = List.of(camConf2024);

Expand Down Expand Up @@ -306,9 +291,7 @@ public static void main(String[] args) {
.registerLoadedConfigs(
ConfigManager.getInstance().getConfig().getCameraConfigurations().values());
} else {
if (testModeFolder == null) {
addTestModeSources();
}
addTestModeSources();
}

VisionSourceManager.getInstance().registerTimedTasks();
Expand Down
Loading