settings) {
@@ -163,54 +190,43 @@ public void addCalibration(CameraCalibrationCoefficients calibration) {
}
/**
- * Get a unique descriptor of the USB port this camera is attached to. EG
- * "/dev/v4l/by-path/platform-fc800000.usb-usb-0:1.3:1.0-video-index0"
+ * cscore will auto-reconnect to the camera path we give it. v4l does not guarantee that if i swap
+ * cameras around, the same /dev/videoN ID will be assigned to that camera. So instead default to
+ * pinning to a particular USB port, or by "path" (appears to be a global identifier on Windows).
*
- * @return
+ * This represents our best guess at an immutable path to detect a camera at.
*/
@JsonIgnore
- public Optional getUSBPath() {
- return Arrays.stream(otherPaths).filter(path -> path.contains("/by-path/")).findFirst();
+ public String getDevicePath() {
+ return matchedCameraInfo.uniquePath();
}
public String toShortString() {
- return "CameraConfiguration [baseName="
- + baseName
- + ", uniqueName="
+ return "CameraConfiguration [uniqueName="
+ uniqueName
+ + ", matchedCameraInfo="
+ + matchedCameraInfo
+ ", nickname="
+ nickname
- + ", path="
- + path
- + ", otherPaths="
- + Arrays.toString(otherPaths)
- + ", cameraType="
- + cameraType
+ + ", deactivated="
+ + deactivated
+ ", cameraQuirks="
+ cameraQuirks
+ ", FOV="
+ FOV
- + "]"
- + ", PID="
- + usbPID
- + ", VID="
- + usbVID;
+ + "]";
}
@Override
public String toString() {
- return "CameraConfiguration [baseName="
- + baseName
- + ", uniqueName="
+ return "CameraConfiguration [uniqueName="
+ uniqueName
+ + ", matchedCameraInfo="
+ + matchedCameraInfo
+ ", nickname="
+ nickname
- + ", path="
- + path
- + ", otherPaths="
- + Arrays.toString(otherPaths)
- + ", cameraType="
- + cameraType
+ + ", deactivated="
+ + deactivated
+ ", cameraQuirks="
+ cameraQuirks
+ ", FOV="
@@ -227,4 +243,25 @@ public String toString() {
+ driveModeSettings
+ "]";
}
+
+ /**
+ * UICameraConfiguration has some stuff particular to VisionModule, but enough of it's common to
+ * warrant this helper
+ */
+ public UICameraConfiguration toUiConfig() {
+ var ret = new UICameraConfiguration();
+
+ ret.matchedCameraInfo = matchedCameraInfo;
+ ret.cameraPath = getDevicePath();
+ ret.nickname = nickname;
+ ret.uniqueName = uniqueName;
+ ret.deactivated = deactivated;
+ ret.isCSICamera = matchedCameraInfo.type() == CameraType.ZeroCopyPicam;
+ ret.pipelineNicknames = pipelineSettings.stream().map(it -> it.pipelineNickname).toList();
+ ret.cameraQuirks = cameraQuirks;
+ ret.calibrations =
+ calibrations.stream().map(CameraCalibrationCoefficients::cloneWithoutObservations).toList();
+
+ return ret;
+ }
}
diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java b/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java
index 1c485d6af3..02de8fb799 100644
--- a/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java
+++ b/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java
@@ -197,6 +197,11 @@ public void addCameraConfigurations(List sources) {
requestSave();
}
+ public void addCameraConfiguration(CameraConfiguration config) {
+ getConfig().addCameraConfig(config);
+ requestSave();
+ }
+
public void saveModule(CameraConfiguration config, String uniqueName) {
getConfig().addCameraConfig(uniqueName, config);
requestSave();
diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/NetworkConfig.java b/photon-core/src/main/java/org/photonvision/common/configuration/NetworkConfig.java
index c18768f7b2..f0023dd13d 100644
--- a/photon-core/src/main/java/org/photonvision/common/configuration/NetworkConfig.java
+++ b/photon-core/src/main/java/org/photonvision/common/configuration/NetworkConfig.java
@@ -34,14 +34,6 @@ public class NetworkConfig {
public boolean shouldManage;
public boolean shouldPublishProto = false;
- /**
- * If we should ONLY match cameras by path, and NEVER only by base-name. For now default to false
- * to preserve old matching logic.
- *
- * This also disables creating new CameraConfigurations for detected "new" cameras.
- */
- public boolean matchCamerasOnlyByPath = false;
-
@JsonIgnore public static final String NM_IFACE_STRING = "${interface}";
@JsonIgnore public static final String NM_IP_STRING = "${ipaddr}";
@@ -70,8 +62,7 @@ public NetworkConfig(
@JsonProperty("shouldPublishProto") boolean shouldPublishProto,
@JsonProperty("networkManagerIface") String networkManagerIface,
@JsonProperty("setStaticCommand") String setStaticCommand,
- @JsonProperty("setDHCPcommand") String setDHCPcommand,
- @JsonProperty("matchCamerasOnlyByPath") boolean matchCamerasOnlyByPath) {
+ @JsonProperty("setDHCPcommand") String setDHCPcommand) {
this.ntServerAddress = ntServerAddress;
this.connectionType = connectionType;
this.staticIp = staticIp;
@@ -81,7 +72,6 @@ public NetworkConfig(
this.networkManagerIface = networkManagerIface;
this.setStaticCommand = setStaticCommand;
this.setDHCPcommand = setDHCPcommand;
- this.matchCamerasOnlyByPath = matchCamerasOnlyByPath;
setShouldManage(shouldManage);
}
@@ -96,8 +86,7 @@ public NetworkConfig(NetworkConfig config) {
config.shouldPublishProto,
config.networkManagerIface,
config.setStaticCommand,
- config.setDHCPcommand,
- config.matchCamerasOnlyByPath);
+ config.setDHCPcommand);
}
@JsonIgnore
diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java b/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java
index 658a617b1f..d2808bb3cc 100644
--- a/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java
+++ b/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java
@@ -19,6 +19,7 @@
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
+import edu.wpi.first.cscore.UsbCameraInfo;
import java.io.File;
import java.io.IOException;
import java.io.UncheckedIOException;
@@ -30,6 +31,7 @@
import java.util.List;
import java.util.Objects;
import java.util.stream.Collectors;
+import org.photonvision.common.configuration.CameraConfiguration.LegacyCameraConfigStruct;
import org.photonvision.common.configuration.DatabaseSchema.Columns;
import org.photonvision.common.configuration.DatabaseSchema.Tables;
import org.photonvision.common.logging.LogGroup;
@@ -165,7 +167,8 @@ private void initDatabase() {
if (userVersion < expectedVersion) {
// older database, run migrations
- // first, check to see if this is one of the ones from 2024 beta that need special handling
+ // first, check to see if this is one of the ones from 2024 beta that need
+ // special handling
if (userVersion == 0 && getSchemaVersion() > 0) {
String sql =
"SELECT COUNT(*) AS CNTREC FROM pragma_table_info('cameras') WHERE name='otherpaths_json';";
@@ -238,7 +241,8 @@ public boolean saveToDisk() {
try {
conn.close();
} catch (SQLException e) {
- // TODO, does the file still save if the SQL connection isn't closed correctly? If so,
+ // TODO, does the file still save if the SQL connection isn't closed correctly?
+ // If so,
// return false here.
logger.error("SQL Err closing connection while saving to disk: ", e);
}
@@ -365,12 +369,11 @@ private void saveCameras(Connection conn) {
// Replace this camera's row with the new settings
var sqlString =
String.format(
- "REPLACE INTO %s (%s, %s, %s, %s, %s) VALUES (?,?,?,?,?);",
+ "REPLACE INTO %s (%s, %s, %s, %s) VALUES (?,?,?,?);",
Tables.CAMERAS,
Columns.CAM_UNIQUE_NAME,
Columns.CAM_CONFIG_JSON,
Columns.CAM_DRIVERMODE_JSON,
- Columns.CAM_OTHERPATHS_JSON,
Columns.CAM_PIPELINE_JSONS);
for (var c : config.getCameraConfigurations().entrySet()) {
@@ -380,7 +383,6 @@ private void saveCameras(Connection conn) {
statement.setString(1, c.getKey());
statement.setString(2, JacksonUtils.serializeToString(config));
statement.setString(3, JacksonUtils.serializeToString(config.driveModeSettings));
- statement.setString(4, JacksonUtils.serializeToString(config.otherPaths));
// Serializing a list of abstract classes sucks. Instead, make it into an array
// of strings, which we can later unpack back into individual settings
@@ -397,7 +399,7 @@ private void saveCameras(Connection conn) {
})
.filter(Objects::nonNull)
.collect(Collectors.toList());
- statement.setString(5, JacksonUtils.serializeToString(settings));
+ statement.setString(4, JacksonUtils.serializeToString(settings));
statement.executeUpdate();
}
@@ -433,7 +435,8 @@ private void addFile(PreparedStatement ps, String key, String value) throws SQLE
// In the future, this may not be needed. A better architecture would involve
// manipulating the RAM representation of configuration when new .json files
// are uploaded in the UI, and eliminate all other usages of saveOneFile().
- // But, seeing as it's Dec 28 and kickoff is nigh, we put this here and moved on.
+ // But, seeing as it's Dec 28 and kickoff is nigh, we put this here and moved
+ // on.
// Thank you for coming to my TED talk.
private boolean skipSavingHWCfg = false;
private boolean skipSavingHWSet = false;
@@ -586,14 +589,32 @@ private HashMap loadCameraConfigs(Connection conn)
List dummyList = new ArrayList<>();
var uniqueName = result.getString(Columns.CAM_UNIQUE_NAME);
- var config =
- JacksonUtils.deserialize(
- result.getString(Columns.CAM_CONFIG_JSON), CameraConfiguration.class);
+
+ // A horrifying hack to keep backward compat with otherpaths
+ // We -really- need to delete this -stupid- otherpaths column. I hate it.
+ var configStr = result.getString(Columns.CAM_CONFIG_JSON);
+ CameraConfiguration config = JacksonUtils.deserialize(configStr, CameraConfiguration.class);
+
+ if (config.matchedCameraInfo == null) {
+ logger.info("Legacy CameraConfiguration detected - upgrading");
+
+ // manually create the matchedCameraInfo ourselves. Need to upgrade:
+ // baseName, path, otherPaths, cameraType, usbvid/pid -> matchedCameraInfo
+ config.matchedCameraInfo =
+ JacksonUtils.deserialize(configStr, LegacyCameraConfigStruct.class).matchedCameraInfo;
+
+ // Except that otherPaths used to be its own column. so hack that in here as well
+ var otherPaths =
+ JacksonUtils.deserialize(
+ result.getString(Columns.CAM_OTHERPATHS_JSON), String[].class);
+ if (config.matchedCameraInfo instanceof UsbCameraInfo usbInfo) {
+ usbInfo.otherPaths = otherPaths;
+ }
+ }
+
var driverMode =
JacksonUtils.deserialize(
result.getString(Columns.CAM_DRIVERMODE_JSON), DriverModePipelineSettings.class);
- var otherPaths =
- JacksonUtils.deserialize(result.getString(Columns.CAM_OTHERPATHS_JSON), String[].class);
List> pipelineSettings =
JacksonUtils.deserialize(
result.getString(Columns.CAM_PIPELINE_JSONS), dummyList.getClass());
@@ -607,7 +628,6 @@ private HashMap loadCameraConfigs(Connection conn)
config.pipelineSettings = loadedSettings;
config.driveModeSettings = driverMode;
- config.otherPaths = otherPaths;
loadedConfigurations.put(uniqueName, config);
}
} catch (SQLException | IOException e) {
diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/DataChangeService.java b/photon-core/src/main/java/org/photonvision/common/dataflow/DataChangeService.java
index 9d49e94290..8c6f4e9982 100644
--- a/photon-core/src/main/java/org/photonvision/common/dataflow/DataChangeService.java
+++ b/photon-core/src/main/java/org/photonvision/common/dataflow/DataChangeService.java
@@ -29,6 +29,25 @@
public class DataChangeService {
private static final Logger logger = new Logger(DataChangeService.class, LogGroup.WebServer);
+ public static class SubscriberHandle {
+ private final int[] idxs;
+
+ private SubscriberHandle(int[] idxs) {
+ this.idxs = idxs;
+ }
+
+ private SubscriberHandle(int idx) {
+ this.idxs = new int[] {idx};
+ }
+
+ public void stop() {
+ for (int idx : idxs) {
+ if (idx < 0) continue;
+ getInstance().subscribers.set(idx, null);
+ }
+ }
+ }
+
private static class ThreadSafeSingleton {
private static final DataChangeService INSTANCE = new DataChangeService();
}
@@ -60,6 +79,7 @@ private void dispatchFromQueue() {
try {
var taken = eventQueue.take();
for (var sub : subscribers) {
+ if (sub == null) continue;
if (sub.wantedSources.contains(taken.sourceType)
&& sub.wantedDestinations.contains(taken.destType)) {
sub.onDataChangeEvent(taken);
@@ -72,9 +92,10 @@ private void dispatchFromQueue() {
}
}
- public void addSubscriber(DataChangeSubscriber subscriber) {
+ public SubscriberHandle addSubscriber(DataChangeSubscriber subscriber) {
if (!subscribers.addIfAbsent(subscriber)) {
logger.warn("Attempted to add already added subscriber!");
+ return new SubscriberHandle(-1);
} else {
logger.debug(
() -> {
@@ -89,13 +110,16 @@ public void addSubscriber(DataChangeSubscriber subscriber) {
return "Added subscriber - " + "Sources: " + sources + ", Destinations: " + dests;
});
+ return new SubscriberHandle(subscribers.size() - 1);
}
}
- public void addSubscribers(DataChangeSubscriber... subs) {
- for (var sub : subs) {
- addSubscriber(sub);
+ public SubscriberHandle addSubscribers(DataChangeSubscriber... subs) {
+ int[] idxs = new int[subs.length];
+ for (int i = 0; i < subs.length; i++) {
+ idxs[i] = addSubscriber(subs[i]).idxs[0];
}
+ return new SubscriberHandle(idxs);
}
public void publishEvent(DataChangeEvent event) {
diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UICameraConfiguration.java b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UICameraConfiguration.java
index f8e5a114ae..cad3d43b43 100644
--- a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UICameraConfiguration.java
+++ b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UICameraConfiguration.java
@@ -19,15 +19,24 @@
import java.util.HashMap;
import java.util.List;
+import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.vision.calibration.UICameraCalibrationCoefficients;
+import org.photonvision.vision.camera.PVCameraInfo;
import org.photonvision.vision.camera.QuirkyCamera;
public class UICameraConfiguration {
- @SuppressWarnings("unused")
- public double fov;
+ // Path to the camera device. On Linux, this is a special file in /dev/v4l/by-id
+ // or /dev/videoN.
+ // This is the path we hand to CSCore to do auto-reconnect on
+ public String cameraPath;
+
+ /** See {@link CameraConfiguration #deactivated} */
+ public boolean deactivated;
public String nickname;
public String uniqueName;
+
+ public double fov;
public HashMap currentPipelineSettings;
public int currentPipelineIndex;
public List pipelineNicknames;
@@ -42,4 +51,9 @@ public class UICameraConfiguration {
public double maxExposureRaw;
public double minWhiteBalanceTemp;
public double maxWhiteBalanceTemp;
+ public PVCameraInfo matchedCameraInfo;
+
+ // Status for if the underlying device is present and such
+ public boolean isConnected;
+ public boolean hasConnected;
}
diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIDataPublisher.java b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIDataPublisher.java
index a376ed7d2d..17bdf8fd86 100644
--- a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIDataPublisher.java
+++ b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIDataPublisher.java
@@ -46,6 +46,7 @@ public void accept(CVPipelineResult result) {
if (lastUIResultUpdateTime + 1000.0 / 10.0 > now) return;
var dataMap = new HashMap();
+ dataMap.put("sequenceID", result.sequenceID);
dataMap.put("fps", result.fps);
dataMap.put("latency", result.getLatencyMillis());
var uiTargets = new ArrayList>(result.targets.size());
diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java
index 0ed805e04e..97b609f3dc 100644
--- a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java
+++ b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java
@@ -28,7 +28,7 @@
import org.photonvision.mrcal.MrCalJNILoader;
import org.photonvision.raspi.LibCameraJNILoader;
import org.photonvision.vision.processes.VisionModule;
-import org.photonvision.vision.processes.VisionModuleManager;
+import org.photonvision.vision.processes.VisionSourceManager;
public class UIPhotonConfiguration {
public List cameraSettings;
@@ -62,7 +62,7 @@ public static UIPhotonConfiguration programStateToUi(PhotonConfiguration c) {
: c.getHardwareConfig().deviceName,
Platform.getPlatformName()),
c.getApriltagFieldLayout()),
- VisionModuleManager.getInstance().getModules().stream()
+ VisionSourceManager.getInstance().getVisionModules().stream()
.map(VisionModule::toUICameraConfig)
.collect(Collectors.toList()));
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/CameraInfo.java b/photon-core/src/main/java/org/photonvision/vision/camera/CameraInfo.java
deleted file mode 100644
index 750679f776..0000000000
--- a/photon-core/src/main/java/org/photonvision/vision/camera/CameraInfo.java
+++ /dev/null
@@ -1,123 +0,0 @@
-/*
- * 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 .
- */
-
-package org.photonvision.vision.camera;
-
-import edu.wpi.first.cscore.UsbCameraInfo;
-import java.util.Arrays;
-import java.util.Optional;
-import org.photonvision.common.hardware.Platform;
-
-public class CameraInfo extends UsbCameraInfo {
- public final CameraType cameraType;
-
- public CameraInfo(
- int dev, String path, String name, String[] otherPaths, int vendorId, int productId) {
- super(dev, path, name, otherPaths, vendorId, productId);
- cameraType = CameraType.UsbCamera;
- }
-
- public CameraInfo(
- int dev,
- String path,
- String name,
- String[] otherPaths,
- int vendorId,
- int productId,
- CameraType cameraType) {
- super(dev, path, name, otherPaths, vendorId, productId);
- this.cameraType = cameraType;
- }
-
- public CameraInfo(UsbCameraInfo info) {
- super(info.dev, info.path, info.name, info.otherPaths, info.vendorId, info.productId);
- cameraType = CameraType.UsbCamera;
- }
-
- /**
- * @return True, if this camera is reported from V4L and is a CSI camera.
- */
- public boolean getIsV4lCsiCamera() {
- return (Arrays.stream(otherPaths).anyMatch(it -> it.contains("csi-video"))
- || getBaseName().equals("unicam"));
- }
-
- /**
- * @return The base name of the camera aka the name as just ascii.
- */
- public String getBaseName() {
- return name.replaceAll("[^\\x00-\\x7F]", "");
- }
-
- /**
- * @return Returns a human readable name
- */
- public String getHumanReadableName() {
- return getBaseName().replaceAll(" ", "_");
- }
-
- /**
- * Get a unique descriptor of the USB port this camera is attached to. EG
- * "/dev/v4l/by-path/platform-fc800000.usb-usb-0:1.3:1.0-video-index0"
- *
- * @return
- */
- public Optional getUSBPath() {
- return Arrays.stream(otherPaths).filter(path -> path.contains("/by-path/")).findFirst();
- }
-
- @Override
- public boolean equals(Object obj) {
- if (this == obj) return true;
- if (obj == null) return false;
- if (getClass() != obj.getClass()) return false;
- CameraInfo other = (CameraInfo) obj;
-
- // Windows device number is not significant. See
- // https://github.com/wpilibsuite/allwpilib/blob/4b94a64b06057c723d6fcafeb1a45f55a70d179a/cscore/src/main/native/windows/UsbCameraImpl.cpp#L1128
- if (!Platform.isWindows()) {
- if (dev != other.dev) return false;
- }
-
- if (!path.equals(other.path)) return false;
- if (!name.equals(other.name)) return false;
- if (!Arrays.asList(this.getUSBPath()).contains(other.getUSBPath())) return false;
- if (vendorId != other.vendorId) return false;
- if (productId != other.productId) return false;
-
- // Don't trust super.equals, as it compares references. Should PR this to allwpilib at some
- // point
- return true;
- }
-
- @Override
- public String toString() {
- return "CameraInfo [cameraType="
- + cameraType
- + ", baseName="
- + getBaseName()
- + ", vid="
- + vendorId
- + ", pid="
- + productId
- + ", path="
- + path
- + ", otherPaths="
- + Arrays.toString(otherPaths)
- + "]";
- }
-}
diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/CameraType.java b/photon-core/src/main/java/org/photonvision/vision/camera/CameraType.java
index 8ce16ca275..c080f366e5 100644
--- a/photon-core/src/main/java/org/photonvision/vision/camera/CameraType.java
+++ b/photon-core/src/main/java/org/photonvision/vision/camera/CameraType.java
@@ -19,6 +19,6 @@
public enum CameraType {
UsbCamera,
- HttpCamera,
- ZeroCopyPicam
+ ZeroCopyPicam,
+ FileCamera // special case for File-based vision sources
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java
index 8f27a4ca2a..76737fbf20 100644
--- a/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java
+++ b/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java
@@ -17,6 +17,7 @@
package org.photonvision.vision.camera;
+import edu.wpi.first.cscore.UsbCameraInfo;
import edu.wpi.first.cscore.VideoMode;
import edu.wpi.first.util.PixelFormat;
import java.nio.file.Path;
@@ -40,7 +41,8 @@ public FileVisionSource(CameraConfiguration cameraConfiguration) {
: null;
frameProvider =
new FileFrameProvider(
- Path.of(cameraConfiguration.path),
+ // TODO - create new File/replay camera info type
+ Path.of(cameraConfiguration.getDevicePath()),
cameraConfiguration.FOV,
FileFrameProvider.MAX_FPS,
calibration);
@@ -53,7 +55,12 @@ public FileVisionSource(CameraConfiguration cameraConfiguration) {
}
public FileVisionSource(String name, String imagePath, double fov) {
- super(new CameraConfiguration(name, imagePath));
+ // TODO - create new File/replay camera info type
+ super(
+ new CameraConfiguration(
+ PVCameraInfo.fromUsbCameraInfo(new UsbCameraInfo(0, imagePath, name, null, 0, 0)),
+ name,
+ name));
frameProvider = new FileFrameProvider(imagePath, fov);
settables =
new FileSourceSettables(cameraConfiguration, frameProvider.get().frameStaticProperties);
@@ -85,7 +92,12 @@ public boolean hasLEDs() {
return false; // Assume USB cameras do not have photonvision-controlled LEDs
}
- private static class FileSourceSettables extends VisionSourceSettables {
+ @Override
+ public void release() {
+ frameProvider.release();
+ }
+
+ public static class FileSourceSettables extends VisionSourceSettables {
private final VideoMode videoMode;
private final HashMap videoModes = new HashMap<>();
diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/PVCameraInfo.java b/photon-core/src/main/java/org/photonvision/vision/camera/PVCameraInfo.java
new file mode 100644
index 0000000000..c12d883ccb
--- /dev/null
+++ b/photon-core/src/main/java/org/photonvision/vision/camera/PVCameraInfo.java
@@ -0,0 +1,276 @@
+/*
+ * 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 .
+ */
+
+package org.photonvision.vision.camera;
+
+import com.fasterxml.jackson.annotation.JsonCreator;
+import com.fasterxml.jackson.annotation.JsonGetter;
+import com.fasterxml.jackson.annotation.JsonProperty;
+import com.fasterxml.jackson.annotation.JsonSubTypes;
+import com.fasterxml.jackson.annotation.JsonTypeInfo;
+import com.fasterxml.jackson.annotation.JsonTypeName;
+import edu.wpi.first.cscore.UsbCameraInfo;
+import java.util.Arrays;
+
+@JsonTypeInfo(use = JsonTypeInfo.Id.NAME, include = JsonTypeInfo.As.WRAPPER_OBJECT)
+@JsonSubTypes({
+ @JsonSubTypes.Type(value = PVCameraInfo.PVUsbCameraInfo.class),
+ @JsonSubTypes.Type(value = PVCameraInfo.PVCSICameraInfo.class),
+ @JsonSubTypes.Type(value = PVCameraInfo.PVFileCameraInfo.class)
+})
+public sealed interface PVCameraInfo {
+ /**
+ * @return The path of the camera.
+ */
+ String path();
+
+ /**
+ * @return The base name of the camera aka the name as just ascii.
+ */
+ String name();
+
+ /**
+ * @return Returns a human readable name
+ */
+ default String humanReadableName() {
+ return name().replaceAll(" ", "_");
+ }
+
+ /**
+ * If the camera is a USB camera this method returns a unique descriptor of the USB port this
+ * camera is attached to. EG "/dev/v4l/by-path/platform-fc800000.usb-usb-0:1.3:1.0-video-index0".
+ * If the camera is a CSI camera this method returns the path of the camera.
+ *
+ * If we are on Windows, this will return the opaque path as described by
+ * MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_SYMBOLIC_LINK (see
+ * https://learn.microsoft.com/en-us/windows/win32/medfound/mf-devsource-attribute-source-type-vidcap-symbolic-link)
+ *
+ * @return The unique path of the camera
+ */
+ @JsonGetter(value = "uniquePath")
+ String uniquePath();
+
+ String[] otherPaths();
+
+ CameraType type();
+
+ default boolean equals(PVCameraInfo other) {
+ return uniquePath().equals(other.uniquePath());
+ }
+
+ @JsonTypeName("PVUsbCameraInfo")
+ public static final class PVUsbCameraInfo extends UsbCameraInfo implements PVCameraInfo {
+ @JsonCreator
+ public PVUsbCameraInfo(
+ @JsonProperty("dev") int dev,
+ @JsonProperty("path") String path,
+ @JsonProperty("name") String name,
+ @JsonProperty("otherPaths") String[] otherPaths,
+ @JsonProperty("vendorId") int vendorId,
+ @JsonProperty("productId") int productId) {
+ super(dev, path, name, otherPaths, vendorId, productId);
+ }
+
+ private PVUsbCameraInfo(UsbCameraInfo info) {
+ super(info.dev, info.path, info.name, info.otherPaths, info.vendorId, info.productId);
+ }
+
+ @Override
+ public String path() {
+ return super.path;
+ }
+
+ @Override
+ public String name() {
+ return super.name.replaceAll("[^\\x00-\\x7F]", "");
+ }
+
+ @Override
+ public String uniquePath() {
+ return Arrays.stream(super.otherPaths)
+ .filter(path -> path.contains("/by-path/"))
+ .findFirst()
+ .orElse(path());
+ }
+
+ @Override
+ public String[] otherPaths() {
+ return super.otherPaths;
+ }
+
+ @Override
+ public CameraType type() {
+ return CameraType.UsbCamera;
+ }
+
+ @Override
+ public boolean equals(Object obj) {
+ if (this == obj) return true;
+ if (obj == null) return false;
+ if (obj instanceof PVCameraInfo info) {
+ return equals(info);
+ }
+ return false;
+ }
+
+ @Override
+ public String toString() {
+ return "PVUsbCameraInfo[type="
+ + type()
+ + ", dev="
+ + super.dev
+ + ", path='"
+ + super.path
+ + "', name='"
+ + super.name
+ + "', otherPaths="
+ + Arrays.toString(super.otherPaths)
+ + ", vid="
+ + super.vendorId
+ + ", pid="
+ + super.productId
+ + ", uniquePath='"
+ + uniquePath()
+ + "']";
+ }
+ }
+
+ @JsonTypeName("PVCSICameraInfo")
+ public static final class PVCSICameraInfo implements PVCameraInfo {
+ public final String path;
+ public final String baseName;
+
+ @JsonCreator
+ public PVCSICameraInfo(
+ @JsonProperty("path") String path, @JsonProperty("baseName") String baseName) {
+ this.path = path;
+ this.baseName = baseName;
+ }
+
+ @Override
+ public String path() {
+ return path;
+ }
+
+ @Override
+ public String name() {
+ return baseName.replaceAll("[^\\x00-\\x7F]", "");
+ }
+
+ @Override
+ public String uniquePath() {
+ return path();
+ }
+
+ @Override
+ public String[] otherPaths() {
+ return new String[0];
+ }
+
+ @Override
+ public CameraType type() {
+ return CameraType.ZeroCopyPicam;
+ }
+
+ @Override
+ public boolean equals(Object obj) {
+ if (this == obj) return true;
+ if (obj == null) return false;
+ if (obj instanceof PVCameraInfo info) {
+ return equals(info);
+ }
+ return false;
+ }
+
+ @Override
+ public String toString() {
+ return "PVCsiCameraInfo[type="
+ + type()
+ + ", basename="
+ + baseName
+ + ", path='"
+ + path
+ + "', uniquePath='"
+ + uniquePath()
+ + "']";
+ }
+ }
+
+ @JsonTypeName("PVFileCameraInfo")
+ public static final class PVFileCameraInfo implements PVCameraInfo {
+ public final String path;
+ public final String name;
+
+ @JsonCreator
+ public PVFileCameraInfo(@JsonProperty("path") String path, @JsonProperty("name") String name) {
+ this.path = path;
+ this.name = name;
+ }
+
+ @Override
+ public String path() {
+ return path;
+ }
+
+ @Override
+ public String name() {
+ return name;
+ }
+
+ @Override
+ public String uniquePath() {
+ return path();
+ }
+
+ @Override
+ public String[] otherPaths() {
+ return new String[0];
+ }
+
+ @Override
+ public CameraType type() {
+ return CameraType.FileCamera;
+ }
+
+ @Override
+ public boolean equals(Object obj) {
+ if (this == obj) return true;
+ if (obj == null) return false;
+ if (obj instanceof PVFileCameraInfo info) {
+ return equals(info);
+ }
+ return false;
+ }
+
+ @Override
+ public String toString() {
+ return "PVFileCameraInfo[type=" + type() + ", filename=" + name + ", path='" + path + "']";
+ }
+ }
+
+ public static PVCameraInfo fromUsbCameraInfo(UsbCameraInfo info) {
+ return new PVUsbCameraInfo(info);
+ }
+
+ public static PVCameraInfo fromCSICameraInfo(String path, String baseName) {
+ return new PVCSICameraInfo(path, baseName);
+ }
+
+ public static PVCameraInfo fromFileInfo(String path, String baseName) {
+ return new PVFileCameraInfo(path, baseName);
+ }
+}
diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/TestSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/TestSource.java
index 38b8b56afc..d4a5517d58 100644
--- a/photon-core/src/main/java/org/photonvision/vision/camera/TestSource.java
+++ b/photon-core/src/main/java/org/photonvision/vision/camera/TestSource.java
@@ -29,18 +29,17 @@
/** Dummy class for unit testing the vision source manager */
public class TestSource extends VisionSource {
- private FrameProvider usbFrameProvider;
-
public TestSource(CameraConfiguration config) {
super(config);
- getCameraConfiguration().cameraQuirks =
- QuirkyCamera.getQuirkyCamera(config.usbVID, config.usbVID, config.baseName);
+ // Disable camera quirk detection using this fun hack
+ getCameraConfiguration().cameraQuirks = QuirkyCamera.getQuirkyCamera(-1, -1, "");
}
@Override
public void remakeSettables() {
- // Nothing to do, settables for this type of VisionSource should never be remade.
+ // Nothing to do, settables for this type of VisionSource should never be
+ // remade.
return;
}
@@ -81,6 +80,22 @@ public void requestHsvSettings(HSVParams params) {
// TODO Auto-generated method stub
throw new UnsupportedOperationException("Unimplemented method 'requestHsvSettings'");
}
+
+ @Override
+ public void release() {
+ // TODO Auto-generated method stub
+ throw new UnsupportedOperationException("Unimplemented method 'release'");
+ }
+
+ @Override
+ public boolean checkCameraConnected() {
+ return true;
+ }
+
+ @Override
+ public boolean isConnected() {
+ return true;
+ }
};
}
@@ -100,4 +115,10 @@ public boolean isVendorCamera() {
public boolean hasLEDs() {
return false; // Assume USB cameras do not have photonvision-controlled LEDs
}
+
+ @Override
+ public void release() {
+ // TODO Auto-generated method stub
+ throw new UnsupportedOperationException("Unimplemented method 'close'");
+ }
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java
index 5fa7eaa971..dcfea72c5f 100644
--- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java
+++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java
@@ -67,8 +67,7 @@ public GenericUSBCameraSettables(CameraConfiguration configuration, UsbCamera ca
this.configuration = configuration;
this.camera = camera;
- getAllVideoModes();
-
+ // TODO - how should this work post-refactor???
if (!configuration.cameraQuirks.hasQuirk(CameraQuirk.StickyFPS)) {
if (!videoModes.isEmpty()) {
setVideoMode(videoModes.get(0)); // fixes double FPS set
@@ -91,6 +90,15 @@ protected void setUpExposureProperties() {
findProperty(
"raw_exposure_absolute", "raw_exposure_time_absolute", "exposure", "raw_Exposure");
+ if (expProp.isEmpty()) {
+ logger.warn("Could not find exposure property");
+ return;
+ } else {
+ exposureAbsProp = expProp.get();
+ this.minExposure = exposureAbsProp.getMin();
+ this.maxExposure = exposureAbsProp.getMax();
+ }
+
// Photonvision needs to be able to control auto exposure. Make sure we can
// first.
var autoExpProp = findProperty("exposure_auto", "auto_exposure");
@@ -262,55 +270,68 @@ public void setVideoModeInternal(VideoMode videoMode) {
}
}
- @Override
- public HashMap getAllVideoModes() {
- if (videoModes == null) {
- videoModes = new HashMap<>();
- List videoModesList = new ArrayList<>();
- try {
- VideoMode[] modes;
+ private void cacheVideoModes() {
+ videoModes = new HashMap<>();
+ List videoModesList = new ArrayList<>();
+ try {
+ VideoMode[] modes;
- modes = camera.enumerateVideoModes();
+ modes = camera.enumerateVideoModes();
- for (VideoMode videoMode : modes) {
- // Filter grey modes
- if (videoMode.pixelFormat == PixelFormat.kGray
- || videoMode.pixelFormat == PixelFormat.kUnknown) {
- continue;
- }
+ for (VideoMode videoMode : modes) {
+ // Filter grey modes
+ if (videoMode.pixelFormat == PixelFormat.kGray
+ || videoMode.pixelFormat == PixelFormat.kUnknown) {
+ continue;
+ }
- if (configuration.cameraQuirks.hasQuirk(CameraQuirk.FPSCap100)) {
- if (videoMode.fps > 100) {
- continue;
- }
+ if (configuration.cameraQuirks.hasQuirk(CameraQuirk.FPSCap100)) {
+ if (videoMode.fps > 100) {
+ continue;
}
-
- videoModesList.add(videoMode);
}
- } catch (Exception e) {
- logger.error("Exception while enumerating video modes!", e);
- videoModesList = List.of();
- }
- // Sort by resolution
- var sortedList =
- videoModesList.stream()
- .distinct() // remove redundant video mode entries
- .sorted(((a, b) -> (b.width + b.height) - (a.width + a.height)))
- .collect(Collectors.toList());
- Collections.reverse(sortedList);
-
- // On vendor cameras, respect blacklisted indices
- var indexBlacklist =
- ConfigManager.getInstance().getConfig().getHardwareConfig().blacklistedResIndices;
- for (int badIdx : indexBlacklist) {
- sortedList.remove(badIdx);
+ videoModesList.add(videoMode);
}
+ } catch (Exception e) {
+ logger.error("Exception while enumerating video modes!", e);
+ videoModesList = List.of();
+ }
- for (VideoMode videoMode : sortedList) {
- videoModes.put(sortedList.indexOf(videoMode), videoMode);
- }
+ // Sort by resolution
+ var sortedList =
+ videoModesList.stream()
+ .distinct() // remove redundant video mode entries
+ .sorted(((a, b) -> (b.width + b.height) - (a.width + a.height)))
+ .collect(Collectors.toList());
+ Collections.reverse(sortedList);
+
+ // On vendor cameras, respect blacklisted indices
+ var indexBlacklist =
+ ConfigManager.getInstance().getConfig().getHardwareConfig().blacklistedResIndices;
+ for (int badIdx : indexBlacklist) {
+ sortedList.remove(badIdx);
+ }
+
+ for (VideoMode videoMode : sortedList) {
+ videoModes.put(sortedList.indexOf(videoMode), videoMode);
+ }
+
+ // If after all that we still have no video modes, not much we can do besides
+ // throw up our hands
+ if (videoModes.isEmpty()) {
+ logger.info("Camera " + camera.getPath() + " has no video modes supported by PhotonVision");
}
+ }
+
+ @Override
+ public HashMap getAllVideoModes() {
+ if (!cameraPropertiesCached) {
+ // Device hasn't connected at least once, best I can do is given up
+ logger.warn("Device hasn't connected, cannot enumerate video modes");
+ return new HashMap<>();
+ }
+
return videoModes;
}
@@ -372,4 +393,21 @@ public double getMaxWhiteBalanceTemp() {
public double getMinWhiteBalanceTemp() {
return minWhiteBalanceTemp;
}
+
+ @Override
+ public void onCameraConnected() {
+ super.onCameraConnected();
+
+ logger.info("Caching cscore properties");
+
+ // Now that our device is actually connected, we can enumerate properties/video
+ // modes
+ setUpExposureProperties();
+ setUpWhiteBalanceProperties();
+ cacheVideoModes();
+
+ setAllCamDefaults();
+
+ calculateFrameStaticProps();
+ }
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/USBCameraSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/USBCameraSource.java
index 8bcd1e144b..13e5f538e2 100644
--- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/USBCameraSource.java
+++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/USBCameraSource.java
@@ -18,7 +18,6 @@
package org.photonvision.vision.camera.USBCameras;
import edu.wpi.first.cameraserver.CameraServer;
-import edu.wpi.first.cscore.CvSink;
import edu.wpi.first.cscore.UsbCamera;
import edu.wpi.first.cscore.VideoException;
import edu.wpi.first.cscore.VideoProperty;
@@ -28,6 +27,7 @@
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.vision.camera.CameraQuirk;
+import org.photonvision.vision.camera.PVCameraInfo.PVUsbCameraInfo;
import org.photonvision.vision.camera.QuirkyCamera;
import org.photonvision.vision.frame.FrameProvider;
import org.photonvision.vision.frame.provider.USBFrameProvider;
@@ -39,37 +39,54 @@ public class USBCameraSource extends VisionSource {
private final UsbCamera camera;
protected GenericUSBCameraSettables settables;
protected FrameProvider usbFrameProvider;
- private final CvSink cvSink;
+
+ private void onCameraConnected() {
+ // Aid to the development team - record the properties available for whatever the user plugged
+ // in
+ printCameraProperaties();
+
+ settables.onCameraConnected();
+ }
public USBCameraSource(CameraConfiguration config) {
super(config);
logger = new Logger(USBCameraSource.class, config.nickname, LogGroup.Camera);
- // cscore will auto-reconnect to the camera path we give it. v4l does not guarantee that if i
- // swap cameras around, the same /dev/videoN ID will be assigned to that camera. So instead
- // default to pinning to a particular USB port, or by "path" (appears to be a global identifier)
- // on Windows.
- camera = new UsbCamera(config.nickname, config.getUSBPath().orElse(config.path));
- cvSink = CameraServer.getVideo(this.camera);
- // set vid/pid if not done already for future matching
- if (config.usbVID <= 0) config.usbVID = this.camera.getInfo().vendorId;
- if (config.usbPID <= 0) config.usbPID = this.camera.getInfo().productId;
+ if (!(config.matchedCameraInfo instanceof PVUsbCameraInfo)) {
+ logger.error(
+ "USBCameraSource matched to a non-USB camera info?? "
+ + config.matchedCameraInfo.toString());
+ }
+
+ camera = new UsbCamera(config.nickname, config.getDevicePath());
+
+ // TODO - I don't need this, do I?
+ // // set vid/pid if not done already for future matching
+ // if (config.usbVID <= 0) config.usbVID = this.camera.getInfo().vendorId;
+ // if (config.usbPID <= 0) config.usbPID = this.camera.getInfo().productId;
+ // TODO - why do we delegate this to USBCameraSource? Quirks are part of the CameraConfig??
+ // also TODO - is the config's saved usb info a reasonable guess for quirk detection? seems like
+ // yes to me...
if (getCameraConfiguration().cameraQuirks == null) {
+ int vid =
+ (config.matchedCameraInfo instanceof PVUsbCameraInfo)
+ ? ((PVUsbCameraInfo) config.matchedCameraInfo).vendorId
+ : -1;
+ int pid =
+ (config.matchedCameraInfo instanceof PVUsbCameraInfo)
+ ? ((PVUsbCameraInfo) config.matchedCameraInfo).productId
+ : -1;
+
getCameraConfiguration().cameraQuirks =
- QuirkyCamera.getQuirkyCamera(
- camera.getInfo().vendorId, camera.getInfo().productId, config.baseName);
+ QuirkyCamera.getQuirkyCamera(vid, pid, config.matchedCameraInfo.name());
}
if (getCameraConfiguration().cameraQuirks.hasQuirks()) {
- logger.info("Quirky camera detected: " + getCameraConfiguration().cameraQuirks.baseName);
+ logger.info("Quirky camera detected: " + getCameraConfiguration().cameraQuirks);
}
- // Aid to the development team - record the properties available for whatever the user plugged
- // in
- printCameraProperaties();
-
var cameraBroken = getCameraConfiguration().cameraQuirks.hasQuirk(CameraQuirk.CompletelyBroken);
if (cameraBroken) {
@@ -87,16 +104,7 @@ public USBCameraSource(CameraConfiguration config) {
settables = createSettables(config, camera);
logger.info("Created settables " + settables);
- if (settables.getAllVideoModes().isEmpty()) {
- // No video modes produced from settables, disable the camera
- logger.info("Camera " + camera.getPath() + " has no video modes supported by PhotonVision");
- usbFrameProvider = null;
-
- } else {
- // Functional camera, set up the frame provider and configure defaults
- usbFrameProvider = new USBFrameProvider(cvSink, settables);
- settables.setAllCamDefaults();
- }
+ usbFrameProvider = new USBFrameProvider(camera, settables, this::onCameraConnected);
}
}
@@ -147,9 +155,6 @@ protected GenericUSBCameraSettables createSettables(
settables = new GenericUSBCameraSettables(config, camera);
}
- settables.setUpExposureProperties();
- settables.setUpWhiteBalanceProperties();
-
return settables;
}
@@ -165,7 +170,14 @@ public void remakeSettables() {
var oldVideoMode = this.settables.getCurrentVideoMode();
this.settables = createSettables(oldConfig, oldCamera);
- // And update FrameStaticProps
+ // Settables only cache videomodes on connect - force this to happen next tick
+ if (settables.camera.isConnected()) {
+ this.settables.onCameraConnected();
+ } else {
+ this.usbFrameProvider.cameraPropertiesCached = false;
+ }
+
+ // And update the settables' FrameStaticProps
settables.setVideoMode(oldVideoMode);
// Propogate our updated settables over to the frame provider
@@ -228,6 +240,14 @@ public boolean hasLEDs() {
return false; // Assume USB cameras do not have photonvision-controlled LEDs
}
+ @Override
+ public void release() {
+ CameraServer.removeCamera(camera.getName());
+ camera.close();
+ usbFrameProvider.release();
+ usbFrameProvider = null;
+ }
+
@Override
public boolean equals(Object obj) {
if (this == obj) return true;
@@ -243,9 +263,6 @@ public boolean equals(Object obj) {
if (usbFrameProvider == null) {
if (other.usbFrameProvider != null) return false;
} else if (!usbFrameProvider.equals(other.usbFrameProvider)) return false;
- if (cvSink == null) {
- if (other.cvSink != null) return false;
- } else if (!cvSink.equals(other.cvSink)) return false;
if (getCameraConfiguration().cameraQuirks == null) {
if (other.getCameraConfiguration().cameraQuirks != null) return false;
} else if (!getCameraConfiguration()
@@ -261,7 +278,6 @@ public int hashCode() {
settables,
usbFrameProvider,
cameraConfiguration,
- cvSink,
getCameraConfiguration().cameraQuirks);
}
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/csi/LibcameraGpuSettables.java
similarity index 97%
rename from photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java
rename to photon-core/src/main/java/org/photonvision/vision/camera/csi/LibcameraGpuSettables.java
index 2d4f045ae5..4b7c30698a 100644
--- a/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java
+++ b/photon-core/src/main/java/org/photonvision/vision/camera/csi/LibcameraGpuSettables.java
@@ -15,7 +15,7 @@
* along with this program. If not, see .
*/
-package org.photonvision.vision.camera;
+package org.photonvision.vision.camera.csi;
import edu.wpi.first.cscore.VideoMode;
import edu.wpi.first.math.MathUtil;
@@ -25,7 +25,7 @@
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.util.math.MathUtils;
import org.photonvision.raspi.LibCameraJNI;
-import org.photonvision.vision.camera.LibcameraGpuSource.FPSRatedVideoMode;
+import org.photonvision.vision.camera.csi.LibcameraGpuSource.FPSRatedVideoMode;
import org.photonvision.vision.opencv.ImageRotationMode;
import org.photonvision.vision.processes.VisionSourceSettables;
@@ -64,7 +64,7 @@ public LibcameraGpuSettables(CameraConfiguration configuration) {
videoModes = new HashMap<>();
- sensorModel = LibCameraJNI.getSensorModel(configuration.path);
+ sensorModel = LibCameraJNI.getSensorModel(configuration.matchedCameraInfo.path());
if (sensorModel == LibCameraJNI.SensorModel.IMX219) {
// Settings for the IMX219 sensor, which is used on the Pi Camera Module v2
@@ -113,6 +113,8 @@ public LibcameraGpuSettables(CameraConfiguration configuration) {
} else if (sensorModel == LibCameraJNI.SensorModel.OV5647) {
minExposure = 560;
}
+ this.cameraPropertiesCached =
+ true; // Camera properties are not able to be changed so they are always cached
}
@Override
@@ -213,7 +215,7 @@ protected void setVideoModeInternal(VideoMode videoMode) {
logger.debug("Creating libcamera");
r_ptr =
LibCameraJNI.createCamera(
- getConfiguration().path,
+ getConfiguration().matchedCameraInfo.path(),
mode.width,
mode.height,
(m_rotationMode == ImageRotationMode.DEG_180_CCW ? 180 : 0));
diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/csi/LibcameraGpuSource.java
similarity index 89%
rename from photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSource.java
rename to photon-core/src/main/java/org/photonvision/vision/camera/csi/LibcameraGpuSource.java
index 8db27a5d73..28449e9ac2 100644
--- a/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSource.java
+++ b/photon-core/src/main/java/org/photonvision/vision/camera/csi/LibcameraGpuSource.java
@@ -15,7 +15,7 @@
* along with this program. If not, see .
*/
-package org.photonvision.vision.camera;
+package org.photonvision.vision.camera.csi;
import edu.wpi.first.cscore.VideoMode;
import edu.wpi.first.util.PixelFormat;
@@ -23,6 +23,8 @@
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
+import org.photonvision.vision.camera.CameraType;
+import org.photonvision.vision.camera.QuirkyCamera;
import org.photonvision.vision.frame.FrameProvider;
import org.photonvision.vision.frame.provider.LibcameraGpuFrameProvider;
import org.photonvision.vision.processes.VisionSource;
@@ -32,11 +34,11 @@ public class LibcameraGpuSource extends VisionSource {
static final Logger logger = new Logger(LibcameraGpuSource.class, LogGroup.Camera);
private final LibcameraGpuSettables settables;
- private final LibcameraGpuFrameProvider frameProvider;
+ private LibcameraGpuFrameProvider frameProvider;
public LibcameraGpuSource(CameraConfiguration configuration) {
super(configuration);
- if (configuration.cameraType != CameraType.ZeroCopyPicam) {
+ if (configuration.matchedCameraInfo.type() != CameraType.ZeroCopyPicam) {
throw new IllegalArgumentException(
"GPUAcceleratedPicamSource only accepts CameraConfigurations with type Picam");
}
@@ -60,7 +62,8 @@ public VisionSourceSettables getSettables() {
@Override
public void remakeSettables() {
- // Nothing to do, settables for this type of VisionSource should never be remade.
+ // Nothing to do, settables for this type of VisionSource should never be
+ // remade.
return;
}
@@ -99,4 +102,10 @@ public boolean isVendorCamera() {
public boolean hasLEDs() {
return (ConfigManager.getInstance().getConfig().getHardwareConfig().ledPins.size() > 0);
}
+
+ @Override
+ public void release() {
+ frameProvider.release();
+ frameProvider = null;
+ }
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java
index a60f636921..806a624830 100644
--- a/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java
+++ b/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java
@@ -19,11 +19,33 @@
import java.util.function.Supplier;
import org.photonvision.vision.opencv.ImageRotationMode;
+import org.photonvision.vision.opencv.Releasable;
import org.photonvision.vision.pipe.impl.HSVPipe;
-public abstract class FrameProvider implements Supplier {
+public abstract class FrameProvider implements Supplier, Releasable {
protected int sequenceID = 0;
+ // Escape hatch to allow us to synchronously (from the main vision thread) run
+ // extra
+ // setup/callbacks once cscore connects to our underlying device for the first
+ // time
+ public boolean cameraPropertiesCached = false;
+
+ protected void onCameraConnected() {
+ cameraPropertiesCached = true;
+ }
+
+ public abstract boolean isConnected();
+
+ public abstract boolean checkCameraConnected();
+
+ /**
+ * Returns if the camera has connected at some point. This is not if it is currently connected.
+ */
+ public boolean hasConnected() {
+ return cameraPropertiesCached;
+ }
+
public abstract String getName();
/** Ask the camera to produce a certain kind of processed image (e.g. HSV or greyscale) */
diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java
index d6c1250e5c..6549e9c203 100644
--- a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java
+++ b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java
@@ -169,4 +169,8 @@ private String getMatchData() {
matchTypes[MathUtil.clamp((int) matchType.value, 0, matchTypes.length - 1)];
return matchTypeStr + "-" + matchNum.value + "-" + eventName.value;
}
+
+ public void close() {
+ // troododfa;lkjadsf;lkfdsaj otgooadflsk;j
+ }
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java
index 2238db496f..0ceb96c19a 100644
--- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java
+++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java
@@ -99,7 +99,9 @@ public final Frame get() {
outputMat,
m_processType,
input.captureTimestamp,
- input.staticProps.rotate(m_rImagePipe.getParams().rotation));
+ input.staticProps != null
+ ? input.staticProps.rotate(m_rImagePipe.getParams().rotation)
+ : input.staticProps);
}
@Override
diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java
index 7cc0846188..2b281b517f 100644
--- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java
+++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java
@@ -27,12 +27,13 @@
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 {
+public class FileFrameProvider extends CpuImageProcessor implements Releasable {
public static final int MAX_FPS = 10;
private static int count = 0;
@@ -106,7 +107,9 @@ public CapturedFrame getInputMat() {
try {
Thread.sleep(millisDelay);
} catch (InterruptedException e) {
- e.printStackTrace();
+ System.err.println("FileFrameProvider interrupted - not busywaiting");
+ // throw back up the stack
+ throw new RuntimeException(e);
}
}
@@ -118,4 +121,24 @@ public CapturedFrame getInputMat() {
public String getName() {
return "FileFrameProvider" + thisIndex + " - " + path.getFileName();
}
+
+ @Override
+ public void release() {
+ originalFrame.release();
+ }
+
+ @Override
+ public boolean checkCameraConnected() {
+ return true;
+ }
+
+ @Override
+ public boolean isConnected() {
+ return true;
+ }
+
+ @Override
+ public boolean hasConnected() {
+ return true;
+ }
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java
index 513deaadaf..6a354257b0 100644
--- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java
+++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java
@@ -22,7 +22,7 @@
import org.photonvision.common.logging.Logger;
import org.photonvision.common.util.math.MathUtils;
import org.photonvision.raspi.LibCameraJNI;
-import org.photonvision.vision.camera.LibcameraGpuSettables;
+import org.photonvision.vision.camera.csi.LibcameraGpuSettables;
import org.photonvision.vision.frame.Frame;
import org.photonvision.vision.frame.FrameProvider;
import org.photonvision.vision.frame.FrameThresholdType;
@@ -40,6 +40,8 @@ public LibcameraGpuFrameProvider(LibcameraGpuSettables visionSettables) {
var vidMode = settables.getCurrentVideoMode();
settables.setVideoMode(vidMode);
+ this.cameraPropertiesCached =
+ true; // Camera properties are not able to be changed so they are always cached
}
@Override
@@ -132,4 +134,30 @@ public void requestHsvSettings(HSVParams params) {
public void requestFrameCopies(boolean copyInput, boolean copyOutput) {
LibCameraJNI.setFramesToCopy(settables.r_ptr, copyInput, copyOutput);
}
+
+ @Override
+ public void release() {
+ synchronized (settables.CAMERA_LOCK) {
+ LibCameraJNI.stopCamera(settables.r_ptr);
+ LibCameraJNI.destroyCamera(settables.r_ptr);
+ settables.r_ptr = 0;
+ }
+ }
+
+ @Override
+ public boolean checkCameraConnected() {
+ String[] cameraNames = LibCameraJNI.getCameraNames();
+ for (String name : cameraNames) {
+ if (name.equals(settables.getConfiguration().getDevicePath())) {
+ return true;
+ }
+ }
+ return false;
+ }
+
+ // To our knowledge the camera is always connected (after boot) with csi cameras
+ @Override
+ public boolean isConnected() {
+ return checkCameraConnected();
+ }
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java
index 0cca9c9843..bae31562e0 100644
--- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java
+++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java
@@ -17,7 +17,9 @@
package org.photonvision.vision.frame.provider;
+import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.cscore.CvSink;
+import edu.wpi.first.cscore.UsbCamera;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.vision.opencv.CVMat;
@@ -26,27 +28,55 @@
public class USBFrameProvider extends CpuImageProcessor {
private final Logger logger;
- private final CvSink cvSink;
+ private UsbCamera camera = null;
+ private CvSink cvSink = null;
@SuppressWarnings("SpellCheckingInspection")
private VisionSourceSettables settables;
+ private Runnable connectedCallback;
+
@SuppressWarnings("SpellCheckingInspection")
- public USBFrameProvider(CvSink sink, VisionSourceSettables visionSettables) {
- logger = new Logger(USBFrameProvider.class, sink.getName(), LogGroup.Camera);
+ public USBFrameProvider(
+ UsbCamera camera, VisionSourceSettables visionSettables, Runnable connectedCallback) {
+ this.camera = camera;
+ this.cvSink = CameraServer.getVideo(this.camera);
+ this.logger =
+ new Logger(
+ USBFrameProvider.class, visionSettables.getConfiguration().nickname, LogGroup.Camera);
+ this.cvSink.setEnabled(true);
- cvSink = sink;
- cvSink.setEnabled(true);
this.settables = visionSettables;
+ this.connectedCallback = connectedCallback;
+ }
+
+ @Override
+ public boolean checkCameraConnected() {
+ boolean connected = camera.isConnected();
+
+ if (!cameraPropertiesCached && connected) {
+ logger.info("Camera connected! running callback");
+ onCameraConnected();
+ }
+
+ return connected;
}
@Override
public CapturedFrame getInputMat() {
- // We allocate memory so we don't fill a Mat in use by another thread (memory model is easier)
+ if (!cameraPropertiesCached && camera.isConnected()) {
+ onCameraConnected();
+ }
+
+ // We allocate memory so we don't fill a Mat in use by another thread (memory
+ // model is easier)
var mat = new CVMat();
- // This is from wpi::Now, or WPIUtilJNI.now(). The epoch from grabFrame is uS since
- // Hal::initialize was called
- long captureTimeNs = cvSink.grabFrame(mat.getMat()) * 1000;
+ // This is from wpi::Now, or WPIUtilJNI.now(). The epoch from grabFrame is uS
+ // since
+ // Hal::initialize was called. Timeout is in seconds
+ // TODO - under the hood, this incurs an extra copy. We should avoid this, if we
+ // can.
+ long captureTimeNs = cvSink.grabFrame(mat.getMat(), 1.0) * 1000;
if (captureTimeNs == 0) {
var error = cvSink.getError();
@@ -61,6 +91,25 @@ public String getName() {
return "USBFrameProvider - " + cvSink.getName();
}
+ @Override
+ public void release() {
+ CameraServer.removeServer(cvSink.getName());
+ cvSink.close();
+ cvSink = null;
+ }
+
+ @Override
+ public void onCameraConnected() {
+ super.onCameraConnected();
+
+ this.connectedCallback.run();
+ }
+
+ @Override
+ public boolean isConnected() {
+ return camera.isConnected();
+ }
+
public void updateSettables(VisionSourceSettables settables) {
this.settables = settables;
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/CameraMatchingOptions.java b/photon-core/src/main/java/org/photonvision/vision/processes/CameraMatchingOptions.java
deleted file mode 100644
index 87ad571abe..0000000000
--- a/photon-core/src/main/java/org/photonvision/vision/processes/CameraMatchingOptions.java
+++ /dev/null
@@ -1,57 +0,0 @@
-/*
- * 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 .
- */
-
-package org.photonvision.vision.processes;
-
-import java.util.List;
-import org.photonvision.vision.camera.CameraType;
-
-public class CameraMatchingOptions {
- public CameraMatchingOptions(
- boolean checkUSBPath,
- boolean checkVidPid,
- boolean checkBaseName,
- boolean checkPath,
- CameraType... allowedTypes) {
- this.checkUSBPath = checkUSBPath;
- this.checkVidPid = checkVidPid;
- this.checkBaseName = checkBaseName;
- this.checkPath = checkPath;
- this.allowedTypes = List.of(allowedTypes);
- }
-
- public final boolean checkUSBPath;
- public final boolean checkVidPid;
- public final boolean checkBaseName;
- public final boolean checkPath;
- public final List allowedTypes;
-
- @Override
- public String toString() {
- return "CameraMatchingOptions [checkUSBPath="
- + checkUSBPath
- + ", checkVidPid="
- + checkVidPid
- + ", checkBaseName="
- + checkBaseName
- + ", checkPath="
- + checkPath
- + ", allowedTypes="
- + allowedTypes
- + "]";
- }
-}
diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/Data.java b/photon-core/src/main/java/org/photonvision/vision/processes/Data.java
deleted file mode 100644
index c146a0e275..0000000000
--- a/photon-core/src/main/java/org/photonvision/vision/processes/Data.java
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * 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 .
- */
-
-package org.photonvision.vision.processes;
-
-import org.photonvision.vision.opencv.Releasable;
-import org.photonvision.vision.pipeline.result.CVPipelineResult;
-
-// TODO replace with CTT's data class
-public class Data implements Releasable {
- public CVPipelineResult result;
-
- @Override
- public void release() {
- result.release();
- }
-}
diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java
index 36b2e0eea8..03d00e7883 100644
--- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java
+++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java
@@ -26,12 +26,12 @@
import java.util.LinkedList;
import java.util.List;
import java.util.function.BiConsumer;
-import java.util.stream.Collectors;
import org.opencv.core.Size;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.dataflow.CVPipelineResultConsumer;
import org.photonvision.common.dataflow.DataChangeService;
+import org.photonvision.common.dataflow.DataChangeService.SubscriberHandle;
import org.photonvision.common.dataflow.events.OutgoingUIEvent;
import org.photonvision.common.dataflow.networktables.NTDataPublisher;
import org.photonvision.common.dataflow.statusLEDs.StatusLEDConsumer;
@@ -45,8 +45,8 @@
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
import org.photonvision.vision.camera.CameraQuirk;
import org.photonvision.vision.camera.CameraType;
-import org.photonvision.vision.camera.LibcameraGpuSource;
import org.photonvision.vision.camera.QuirkyCamera;
+import org.photonvision.vision.camera.csi.LibcameraGpuSource;
import org.photonvision.vision.frame.Frame;
import org.photonvision.vision.frame.consumer.FileSaveFrameConsumer;
import org.photonvision.vision.frame.consumer.MJPGFrameConsumer;
@@ -71,6 +71,7 @@ public class VisionModule {
private final VisionRunner visionRunner;
private final StreamRunnable streamRunnable;
private final VisionModuleChangeSubscriber changeSubscriber;
+ private final SubscriberHandle changeSubscriberHandle;
private final LinkedList resultConsumers = new LinkedList<>();
// Raw result consumers run before any drawing has been done by the
// OutputStreamPipeline
@@ -134,7 +135,7 @@ public VisionModule(PipelineManager pipelineManager, VisionSource visionSource,
this.streamRunnable = new StreamRunnable(new OutputStreamPipeline());
this.moduleIndex = index;
- DataChangeService.getInstance().addSubscriber(changeSubscriber);
+ changeSubscriberHandle = DataChangeService.getInstance().addSubscriber(changeSubscriber);
createStreams();
@@ -258,7 +259,7 @@ public void updateData(
@Override
public void run() {
- while (true) {
+ while (!Thread.interrupted()) {
final Frame m_frame;
final AdvancedPipelineSettings settings;
final List targets;
@@ -292,7 +293,8 @@ public void run() {
try {
Thread.sleep(1);
} catch (InterruptedException e) {
- e.printStackTrace();
+ logger.warn("StreamRunnable was interrupted - exiting");
+ return;
}
}
}
@@ -300,10 +302,33 @@ public void run() {
}
public void start() {
+ visionSource.cameraConfiguration.deactivated = false;
visionRunner.startProcess();
streamRunnable.start();
}
+ public void stop() {
+ visionSource.cameraConfiguration.deactivated = true;
+ visionRunner.stopProcess();
+
+ try {
+ streamRunnable.interrupt();
+ streamRunnable.join();
+ } catch (InterruptedException e) {
+ logger.error("Exception killing process thread", e);
+ }
+
+ visionSource.release();
+
+ inputVideoStreamer.close();
+ outputVideoStreamer.close();
+ inputFrameSaver.close();
+ outputFrameSaver.close();
+
+ changeSubscriberHandle.stop();
+ setVisionLEDs(false);
+ }
+
public void setFov(double fov) {
var settables = visionSource.getSettables();
logger.trace(() -> "Setting " + settables.getConfiguration().nickname + ") FOV (" + fov + ")");
@@ -411,6 +436,9 @@ boolean setPipeline(int index) {
logger.info("Setting pipeline to " + index);
logger.info("Pipeline name: " + pipelineManager.getPipelineNickname(index));
pipelineManager.setIndex(index);
+
+ VisionSourceSettables settables = visionSource.getSettables();
+
var pipelineSettings = pipelineManager.getPipelineSettings(index);
if (pipelineSettings == null) {
@@ -418,49 +446,51 @@ boolean setPipeline(int index) {
return false;
}
- visionSource.getSettables().setVideoModeInternal(pipelineSettings.cameraVideoModeIndex);
- visionSource.getSettables().setBrightness(pipelineSettings.cameraBrightness);
-
- // If manual exposure, force exposure slider to be valid
- if (!pipelineSettings.cameraAutoExposure) {
- if (pipelineSettings.cameraExposureRaw < 0)
- pipelineSettings.cameraExposureRaw = 10; // reasonable default
- }
+ visionRunner.runSyncronously(
+ () -> {
+ settables.setVideoModeInternal(pipelineSettings.cameraVideoModeIndex);
+ settables.setBrightness(pipelineSettings.cameraBrightness);
- visionSource.getSettables().setExposureRaw(pipelineSettings.cameraExposureRaw);
- try {
- visionSource.getSettables().setAutoExposure(pipelineSettings.cameraAutoExposure);
- } catch (VideoException e) {
- logger.error("Unable to set camera auto exposure!");
- logger.error(e.toString());
- }
- if (cameraQuirks.hasQuirk(CameraQuirk.Gain)) {
- // If the gain is disabled for some reason, re-enable it
- if (pipelineSettings.cameraGain == -1) pipelineSettings.cameraGain = 75;
- visionSource.getSettables().setGain(Math.max(0, pipelineSettings.cameraGain));
- } else {
- pipelineSettings.cameraGain = -1;
- }
+ // If manual exposure, force exposure slider to be valid
+ if (!pipelineSettings.cameraAutoExposure) {
+ if (pipelineSettings.cameraExposureRaw < 0)
+ pipelineSettings.cameraExposureRaw = 10; // reasonable default
+ }
- if (cameraQuirks.hasQuirk(CameraQuirk.AwbRedBlueGain)) {
- // If the AWB gains are disabled for some reason, re-enable it
- if (pipelineSettings.cameraRedGain == -1) pipelineSettings.cameraRedGain = 11;
- if (pipelineSettings.cameraBlueGain == -1) pipelineSettings.cameraBlueGain = 20;
- visionSource.getSettables().setRedGain(Math.max(0, pipelineSettings.cameraRedGain));
- visionSource.getSettables().setBlueGain(Math.max(0, pipelineSettings.cameraBlueGain));
- } else {
- pipelineSettings.cameraRedGain = -1;
- pipelineSettings.cameraBlueGain = -1;
+ settables.setExposureRaw(pipelineSettings.cameraExposureRaw);
+ try {
+ settables.setAutoExposure(pipelineSettings.cameraAutoExposure);
+ } catch (VideoException e) {
+ logger.error("Unable to set camera auto exposure!");
+ logger.error(e.toString());
+ }
+ if (cameraQuirks.hasQuirk(CameraQuirk.Gain)) {
+ // If the gain is disabled for some reason, re-enable it
+ if (pipelineSettings.cameraGain == -1) pipelineSettings.cameraGain = 75;
+ settables.setGain(Math.max(0, pipelineSettings.cameraGain));
+ } else {
+ pipelineSettings.cameraGain = -1;
+ }
- // All other cameras (than picams) should support AWB temp
- visionSource.getSettables().setWhiteBalanceTemp(pipelineSettings.cameraWhiteBalanceTemp);
- visionSource.getSettables().setAutoWhiteBalance(pipelineSettings.cameraAutoWhiteBalance);
- }
+ if (cameraQuirks.hasQuirk(CameraQuirk.AwbRedBlueGain)) {
+ // If the AWB gains are disabled for some reason, re-enable it
+ if (pipelineSettings.cameraRedGain == -1) pipelineSettings.cameraRedGain = 11;
+ if (pipelineSettings.cameraBlueGain == -1) pipelineSettings.cameraBlueGain = 20;
+ settables.setRedGain(Math.max(0, pipelineSettings.cameraRedGain));
+ settables.setBlueGain(Math.max(0, pipelineSettings.cameraBlueGain));
+ } else {
+ pipelineSettings.cameraRedGain = -1;
+ pipelineSettings.cameraBlueGain = -1;
+
+ // All other cameras (than picams) should support AWB temp
+ settables.setWhiteBalanceTemp(pipelineSettings.cameraWhiteBalanceTemp);
+ settables.setAutoWhiteBalance(pipelineSettings.cameraAutoWhiteBalance);
+ }
- setVisionLEDs(pipelineSettings.ledMode);
+ setVisionLEDs(pipelineSettings.ledMode);
- visionSource.getSettables().getConfiguration().currentPipelineIndex =
- pipelineManager.getRequestedIndex();
+ settables.getConfiguration().currentPipelineIndex = pipelineManager.getRequestedIndex();
+ });
return true;
}
@@ -485,7 +515,7 @@ public void saveModule() {
getStateAsCameraConfig(), visionSource.getSettables().getConfiguration().uniqueName);
}
- void saveAndBroadcastAll() {
+ public void saveAndBroadcastAll() {
saveModule();
DataChangeService.getInstance()
.publishEvent(
@@ -521,8 +551,11 @@ public void setCameraNickname(String newName) {
public UICameraConfiguration toUICameraConfig() {
var ret = new UICameraConfiguration();
+ var config = visionSource.getCameraConfiguration();
+ ret.matchedCameraInfo = config.matchedCameraInfo;
+ ret.cameraPath = config.getDevicePath();
ret.fov = visionSource.getSettables().getFOV();
- ret.isCSICamera = visionSource.getCameraConfiguration().cameraType == CameraType.ZeroCopyPicam;
+ ret.isCSICamera = config.matchedCameraInfo.type() == CameraType.ZeroCopyPicam;
ret.nickname = visionSource.getSettables().getConfiguration().nickname;
ret.uniqueName = visionSource.getSettables().getConfiguration().uniqueName;
ret.currentPipelineSettings =
@@ -535,6 +568,8 @@ public UICameraConfiguration toUICameraConfig() {
ret.minWhiteBalanceTemp = visionSource.getSettables().getMinWhiteBalanceTemp();
ret.maxWhiteBalanceTemp = visionSource.getSettables().getMaxWhiteBalanceTemp();
+ ret.deactivated = config.deactivated;
+
// TODO refactor into helper method
var temp = new HashMap>();
var videoModes = visionSource.getSettables().getAllVideoModes();
@@ -554,6 +589,11 @@ public UICameraConfiguration toUICameraConfig() {
temp.put(k, internalMap);
}
+
+ if (videoModes.size() == 0) {
+ logger.error("no video modes, guhhhhh");
+ }
+
ret.videoFormatList = temp;
ret.outputStreamPort = this.outputStreamPort;
ret.inputStreamPort = this.inputStreamPort;
@@ -561,11 +601,14 @@ public UICameraConfiguration toUICameraConfig() {
ret.calibrations =
visionSource.getSettables().getConfiguration().calibrations.stream()
.map(CameraCalibrationCoefficients::cloneWithoutObservations)
- .collect(Collectors.toList());
+ .toList();
ret.isFovConfigurable =
!(ConfigManager.getInstance().getConfig().getHardwareConfig().hasPresetFOV());
+ ret.isConnected = visionSource.getFrameProvider().isConnected();
+ ret.hasConnected = visionSource.getFrameProvider().hasConnected();
+
return ret;
}
@@ -643,4 +686,12 @@ public void changeCameraQuirks(HashMap quirksToChange) {
visionSource.remakeSettables();
saveAndBroadcastAll();
}
+
+ public String uniqueName() {
+ return this.visionSource.cameraConfiguration.uniqueName;
+ }
+
+ public CameraConfiguration getCameraConfiguration() {
+ return this.visionSource.cameraConfiguration;
+ }
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java
index d75e62cb7e..a11d0495d0 100644
--- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java
+++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java
@@ -19,6 +19,7 @@
import java.util.*;
import java.util.stream.Collectors;
+import org.photonvision.common.dataflow.websocket.UICameraConfiguration;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
@@ -26,15 +27,7 @@
public class VisionModuleManager {
private final Logger logger = new Logger(VisionModuleManager.class, LogGroup.VisionModule);
- private static class ThreadSafeSingleton {
- private static final VisionModuleManager INSTANCE = new VisionModuleManager();
- }
-
- public static VisionModuleManager getInstance() {
- return VisionModuleManager.ThreadSafeSingleton.INSTANCE;
- }
-
- protected final List visionModules = new ArrayList<>();
+ private final List visionModules = new ArrayList<>();
VisionModuleManager() {}
@@ -53,25 +46,25 @@ public VisionModule getModule(int i) {
return visionModules.get(i);
}
- public List addSources(List visionSources) {
- var addedModules = new HashMap();
+ public synchronized VisionModule addSource(VisionSource visionSource) {
+ visionSource.cameraConfiguration.streamIndex = newCameraIndex();
- assignCameraIndex(visionSources);
- for (var visionSource : visionSources) {
- var pipelineManager = new PipelineManager(visionSource.getCameraConfiguration());
+ var pipelineManager = new PipelineManager(visionSource.getCameraConfiguration());
+ var module =
+ new VisionModule(
+ pipelineManager, visionSource, visionSource.cameraConfiguration.streamIndex);
+ visionModules.add(module);
- var module = new VisionModule(pipelineManager, visionSource, visionModules.size());
- visionModules.add(module);
- addedModules.put(visionSource.getCameraConfiguration().streamIndex, module);
- }
+ return module;
+ }
- return addedModules.entrySet().stream()
- .sorted(Comparator.comparingInt(Map.Entry::getKey)) // sort by stream index
- .map(Map.Entry::getValue) // map to Stream of VisionModule
- .collect(Collectors.toList()); // collect in a List
+ public synchronized void removeModule(VisionModule module) {
+ visionModules.remove(module);
+ module.stop();
+ module.saveAndBroadcastAll();
}
- private void assignCameraIndex(List config) {
+ private synchronized int newCameraIndex() {
// We won't necessarily have already added all the cameras we need to at this point
// But by operating on the list, we have a fairly good idea of which we need to change,
// but it's not guaranteed that we change the correct one
@@ -80,29 +73,40 @@ private void assignCameraIndex(List config) {
// Big list, which should contain every vision source (currently loaded plus the new ones being
// added)
- var bigList = new ArrayList();
- bigList.addAll(
- this.getModules().stream().map(it -> it.visionSource).collect(Collectors.toList()));
- bigList.addAll(config);
-
- for (var v : config) {
- var listNoV = new ArrayList<>(bigList);
- listNoV.remove(v);
- if (listNoV.stream()
- .anyMatch(
- it ->
- it.getCameraConfiguration().streamIndex
- == v.getCameraConfiguration().streamIndex)) {
- int idx = 0;
- while (listNoV.stream()
+ List bigList =
+ this.getModules().stream()
.map(it -> it.getCameraConfiguration().streamIndex)
- .collect(Collectors.toList())
- .contains(idx)) {
- idx++;
- }
- logger.debug("Assigning idx " + idx);
- v.getCameraConfiguration().streamIndex = idx;
- }
+ .collect(Collectors.toList());
+
+ int idx = 0;
+ while (bigList.contains(idx)) {
+ idx++;
+ }
+
+ if (idx >= 5) {
+ logger.warn("VisionModuleManager has reached the maximum number of cameras (5).");
+ }
+
+ return idx;
+ }
+
+ public static class UiVmmState {
+ public final List visionModules;
+
+ UiVmmState(List _v) {
+ this.visionModules = _v;
}
}
+
+ public synchronized UiVmmState getState() {
+ return new UiVmmState(
+ this.visionModules.stream()
+ .map(VisionModule::toUICameraConfig)
+ .map(
+ it -> {
+ it.calibrations = null;
+ return it;
+ })
+ .collect(Collectors.toList()));
+ }
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java
index f7c7df7fed..4d6b6c28fc 100644
--- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java
+++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java
@@ -17,8 +17,17 @@
package org.photonvision.vision.processes;
+import java.util.ArrayList;
+import java.util.List;
+import java.util.concurrent.Callable;
+import java.util.concurrent.CompletableFuture;
+import java.util.concurrent.Future;
import java.util.function.Consumer;
import java.util.function.Supplier;
+import org.photonvision.common.configuration.ConfigManager;
+import org.photonvision.common.dataflow.DataChangeService;
+import org.photonvision.common.dataflow.events.OutgoingUIEvent;
+import org.photonvision.common.dataflow.websocket.UIPhotonConfiguration;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.vision.camera.QuirkyCamera;
@@ -38,6 +47,7 @@ public class VisionRunner {
private final Supplier pipelineSupplier;
private final Consumer pipelineResultConsumer;
private final VisionModuleChangeSubscriber changeSubscriber;
+ private final List runnableList = new ArrayList();
private final QuirkyCamera cameraQuirks;
private long loopCount;
@@ -72,12 +82,86 @@ public void startProcess() {
visionProcessThread.start();
}
+ public void stopProcess() {
+ try {
+ System.out.println("Interrupting vision process thread");
+ visionProcessThread.interrupt();
+ visionProcessThread.join();
+ } catch (InterruptedException e) {
+ logger.error("Exception killing process thread", e);
+ }
+ }
+
+ public Future runSyncronously(Runnable runnable) {
+ CompletableFuture future = new CompletableFuture<>();
+
+ synchronized (runnableList) {
+ runnableList.add(
+ () -> {
+ try {
+ runnable.run();
+ future.complete(null);
+ } catch (Exception ex) {
+ future.completeExceptionally(ex);
+ }
+ });
+ }
+ return future;
+ }
+
+ public Future runSyncronously(Callable callable) {
+ CompletableFuture future = new CompletableFuture<>();
+
+ synchronized (runnableList) {
+ runnableList.add(
+ () -> {
+ try {
+ T result = callable.call();
+ future.complete(result);
+ } catch (Exception ex) {
+ future.completeExceptionally(ex);
+ }
+ });
+ }
+
+ return future;
+ }
+
private void update() {
+ // wait for the camera to connect
+ while (!frameSupplier.checkCameraConnected() && !Thread.interrupted()) {
+ // yield
+ pipelineResultConsumer.accept(new CVPipelineResult(0l, 0, 0, null, new Frame()));
+ try {
+ Thread.sleep(100);
+ } catch (InterruptedException e) {
+ return;
+ }
+ }
+
+ DataChangeService.getInstance()
+ .publishEvent(
+ new OutgoingUIEvent<>(
+ "fullsettings",
+ UIPhotonConfiguration.programStateToUi(ConfigManager.getInstance().getConfig())));
+
while (!Thread.interrupted()) {
changeSubscriber.processSettingChanges();
+ synchronized (runnableList) {
+ for (var runnable : runnableList) {
+ try {
+ runnable.run();
+ } catch (Exception ex) {
+ logger.error("Exception running runnable", ex);
+ }
+ }
+ runnableList.clear();
+ }
+
var pipeline = pipelineSupplier.get();
- // Tell our camera implementation here what kind of pre-processing we need it to be doing
+ // Tell our camera implementation here what kind of pre-processing we need it to
+ // be doing
// (pipeline-dependent). I kinda hate how much leak this has...
// TODO would a callback object be a better fit?
var wantedProcessType = pipeline.getThresholdType();
@@ -101,14 +185,17 @@ private void update() {
if (frame.processedImage.getMat().empty() && frame.colorImage.getMat().empty()) {
// give up without increasing loop count
// Still feed with blank frames just dont run any pipelines
+
pipelineResultConsumer.accept(new CVPipelineResult(0l, 0, 0, null, new Frame()));
continue;
}
- // If the pipeline has changed while we are getting our frame we should scrap that frame it
+ // If the pipeline has changed while we are getting our frame we should scrap
+ // that frame it
// may result in incorrect frame settings like hsv values
if (pipeline == pipelineSupplier.get()) {
- // There's no guarantee the processing type change will occur this tick, so pipelines should
+ // There's no guarantee the processing type change will occur this tick, so
+ // pipelines should
// check themselves
try {
var pipelineResult = pipeline.run(frame, cameraQuirks);
diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSource.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSource.java
index 618d4fa144..034e3f5f0f 100644
--- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSource.java
+++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSource.java
@@ -19,8 +19,9 @@
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.vision.frame.FrameProvider;
+import org.photonvision.vision.opencv.Releasable;
-public abstract class VisionSource {
+public abstract class VisionSource implements Releasable {
protected final CameraConfiguration cameraConfiguration;
protected VisionSource(CameraConfiguration cameraConfiguration) {
diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java
index 1e40248a2e..fd0e0d7441 100644
--- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java
+++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java
@@ -21,14 +21,17 @@
import java.util.ArrayList;
import java.util.Arrays;
import java.util.Collection;
+import java.util.HashMap;
import java.util.List;
-import java.util.concurrent.CopyOnWriteArrayList;
+import java.util.Optional;
import java.util.function.Predicate;
-import java.util.stream.Collectors;
+import java.util.regex.Pattern;
+import java.util.stream.Stream;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.dataflow.DataChangeService;
import org.photonvision.common.dataflow.events.OutgoingUIEvent;
+import org.photonvision.common.dataflow.websocket.UICameraConfiguration;
import org.photonvision.common.dataflow.websocket.UIPhotonConfiguration;
import org.photonvision.common.hardware.Platform;
import org.photonvision.common.hardware.Platform.OSType;
@@ -37,23 +40,27 @@
import org.photonvision.common.util.TimedTaskManager;
import org.photonvision.raspi.LibCameraJNI;
import org.photonvision.raspi.LibCameraJNILoader;
-import org.photonvision.vision.camera.CameraInfo;
-import org.photonvision.vision.camera.CameraQuirk;
import org.photonvision.vision.camera.CameraType;
-import org.photonvision.vision.camera.LibcameraGpuSource;
-import org.photonvision.vision.camera.TestSource;
+import org.photonvision.vision.camera.FileVisionSource;
+import org.photonvision.vision.camera.PVCameraInfo;
import org.photonvision.vision.camera.USBCameras.USBCameraSource;
-
+import org.photonvision.vision.camera.csi.LibcameraGpuSource;
+
+/**
+ * This class manages starting up VisionModules for serialized devices ({@link
+ * VisionSourceManager#loadVisionSourceFromCamConfig}), as well as handling requests from users to
+ * disable (release the camera device, but keep the configuration around) ({@link
+ * VisionSourceManager#deactivateVisionSource}), reactivate (recreate a VisionModule from a saved
+ * and currently disabled configuration) ({@link
+ * VisionSourceManager#reactivateDisabledCameraConfig}), and create a new VisionModule from a {@link
+ * PVCameraInfo} ({@link VisionSourceManager#assignUnmatchedCamera}).
+ *
+ * We now require user interaction for pretty much every operation this undertakes.
+ */
public class VisionSourceManager {
private static final Logger logger = new Logger(VisionSourceManager.class, LogGroup.Camera);
- private static final List deviceBlacklist = List.of("bcm2835-isp");
- final List knownCameras = new CopyOnWriteArrayList<>();
-
- final List unmatchedLoadedConfigs = new CopyOnWriteArrayList<>();
- private boolean hasWarned;
- private boolean hasWarnedNoCameras = false;
- private String ignoredCamerasRegex = "";
+ private static final List deviceBlacklist = List.of("bcm2835-isp");
private static class SingletonHolder {
private static final VisionSourceManager INSTANCE = new VisionSourceManager();
@@ -63,547 +70,348 @@ public static VisionSourceManager getInstance() {
return SingletonHolder.INSTANCE;
}
- VisionSourceManager() {}
-
- public void registerTimedTask() {
- TimedTaskManager.getInstance().addTask("VisionSourceManager", this::tryMatchCams, 3000);
+ // Jackson does use these members even if your IDE claims otherwise
+ public static class VisionSourceManagerState {
+ public List disabledConfigs;
+ public List allConnectedCameras;
}
- public void registerLoadedConfigs(CameraConfiguration... configs) {
- registerLoadedConfigs(Arrays.asList(configs));
+ // Map of (unique name) -> (all CameraConfigurations) that have been registered
+ protected final HashMap disabledCameraConfigs = new HashMap<>();
+
+ // The subset of cameras that are "active", converted to VisionModules
+ public VisionModuleManager vmm = new VisionModuleManager();
+
+ public void registerTimedTasks() {
+ TimedTaskManager.getInstance().addTask("CameraDeviceExplorer", this::pushUiUpdate, 1000);
}
/**
- * Register new camera configs loaded from disk. This will add them to the list of configs to try
- * to match, and also automatically spawn new vision processes as necessary.
+ * Register new camera configs loaded from disk. This will create vision modules for each camera
+ * config and start them.
*
* @param configs The loaded camera configs.
*/
- public void registerLoadedConfigs(Collection configs) {
- unmatchedLoadedConfigs.addAll(configs);
- }
+ public synchronized void registerLoadedConfigs(Collection configs) {
+ logger.info("Registering loaded camera configs");
+
+ final HashMap deserializedConfigs = new HashMap<>();
+
+ // 1. Verify all camera unique names are unique and paths/types are unique for paranoia. This
+ // seems redundant, consider deleting
+ for (var config : configs) {
+ Predicate checkDuplicateCamera =
+ (other) ->
+ (other.type().equals(config.matchedCameraInfo.type())
+ && other.uniquePath().equals(config.matchedCameraInfo.uniquePath()));
+
+ if (deserializedConfigs.containsKey(config.uniqueName)) {
+ logger.error(
+ "Duplicate unique name for config " + config.uniqueName + " -- not overwriting");
+ } else if (deserializedConfigs.values().stream()
+ .map(it -> it.matchedCameraInfo)
+ .anyMatch(checkDuplicateCamera)) {
+ logger.error(
+ "Duplicate camera type & path for config " + config.uniqueName + " -- not overwriting");
+ } else {
+ deserializedConfigs.put(config.uniqueName, config);
+ }
+ }
- /**
- * Pre filter out any csi cameras to return just USB Cameras. Allow defining the camerainfo.
- *
- * @return a list containing usbcamerainfo.
- */
- protected List getConnectedUSBCameras() {
- List cameraInfos =
- List.of(UsbCamera.enumerateUsbCameras()).stream()
- .map(c -> new CameraInfo(c))
- .collect(Collectors.toList());
- return cameraInfos;
+ // 2. create sources -> VMMs for all active cameras and add to our VMM. We don't care about if
+ // the underlying device is currently connected or not.
+ deserializedConfigs.values().stream()
+ .filter(it -> !it.deactivated)
+ .map(this::loadVisionSourceFromCamConfig)
+ .map(vmm::addSource)
+ .forEach(VisionModule::start);
+
+ // 3. write down all disabled sources for later
+ deserializedConfigs.entrySet().stream()
+ .filter(it -> it.getValue().deactivated)
+ .forEach(it -> this.disabledCameraConfigs.put(it.getKey(), it.getValue()));
+
+ logger.info(
+ "Finished registering loaded camera configs! Started "
+ + vmm.getModules().size()
+ + " active VisionModules, with "
+ + deserializedConfigs.size()
+ + " disabled VisionModules");
}
/**
- * Retrieve the list of csi cameras from libcamera.
+ * Reactivate a previously created vision source
*
- * @return a list containing csicamerainfo.
+ * @param uniqueName
*/
- protected List getConnectedCSICameras() {
- List cameraInfos = new ArrayList();
- if (LibCameraJNILoader.isSupported())
- for (String path : LibCameraJNI.getCameraNames()) {
- String name = LibCameraJNI.getSensorModel(path).getFriendlyName();
- cameraInfos.add(
- new CameraInfo(-1, path, name, new String[] {}, -1, -1, CameraType.ZeroCopyPicam));
- }
- return cameraInfos;
- }
+ public synchronized boolean reactivateDisabledCameraConfig(String uniqueName) {
+ // Make sure we have an old, currently -inactive- camera around
+ var deactivatedConfig = Optional.ofNullable(this.disabledCameraConfigs.remove(uniqueName));
+ if (deactivatedConfig.isEmpty() || !deactivatedConfig.get().deactivated) {
+ // Not in map, give up
+ return false;
+ }
- protected void tryMatchCams() {
- var visionSourceList = tryMatchCamImpl();
- if (visionSourceList == null) return;
+ // Check if the camera is already in use by another module
+ if (vmm.getModules().stream()
+ .anyMatch(
+ module ->
+ module
+ .getCameraConfiguration()
+ .matchedCameraInfo
+ .uniquePath()
+ .equals(deactivatedConfig.get().matchedCameraInfo.uniquePath()))) {
+ logger.error(
+ "Camera unique-path already in use by active VisionModule! Cannot reactivate "
+ + deactivatedConfig.get().nickname);
+ }
+
+ // transform the camera info all the way to a VisionModule and then start it
+ var created =
+ deactivatedConfig
+ .map(this::loadVisionSourceFromCamConfig)
+ .map(vmm::addSource)
+ .map(
+ it -> {
+ it.start();
+ it.saveAndBroadcastAll();
+ return it;
+ })
+ .isPresent();
+
+ if (!created) {
+ // Couldn't create a VM for this config - restore state
+ this.disabledCameraConfigs.put(uniqueName, deactivatedConfig.get());
+ }
- logger.info("Adding " + visionSourceList.size() + " configs to VMM.");
- ConfigManager.getInstance().addCameraConfigurations(visionSourceList);
- var addedSources = VisionModuleManager.getInstance().addSources(visionSourceList);
- addedSources.forEach(VisionModule::start);
+ // We have a new camera! Tell the world about it
DataChangeService.getInstance()
.publishEvent(
new OutgoingUIEvent<>(
"fullsettings",
UIPhotonConfiguration.programStateToUi(ConfigManager.getInstance().getConfig())));
- }
- protected List tryMatchCamImpl() {
- return tryMatchCamImpl(null);
- }
+ pushUiUpdate();
- protected List tryMatchCamImpl(ArrayList cameraInfos) {
- return tryMatchCamImpl(cameraInfos, Platform.getCurrentPlatform());
+ return created;
}
/**
- * @param cameraInfos Used to feed camera info for unit tests.
- * @return New VisionSources.
+ * Assign a camera that currently has no associated CameraConfiguration loaded.
+ *
+ * @param cameraInfo
*/
- protected List tryMatchCamImpl(
- ArrayList cameraInfos, Platform platform) {
- boolean createSources = true;
- List connectedCameras;
- if (cameraInfos == null) {
- // Detect USB cameras using CSCore
- connectedCameras = new ArrayList<>(filterAllowedDevices(getConnectedUSBCameras(), platform));
- // Detect CSI cameras using libcamera
- connectedCameras.addAll(
- new ArrayList<>(filterAllowedDevices(getConnectedCSICameras(), platform)));
- } else {
- connectedCameras = new ArrayList<>(filterAllowedDevices(cameraInfos, platform));
- createSources =
- false; // Dont create sources if we are using supplied camerainfo for unit tests.
+ public synchronized boolean assignUnmatchedCamera(PVCameraInfo cameraInfo) {
+ // Check if the camera is already in use by another module
+ if (vmm.getModules().stream()
+ .anyMatch(
+ module ->
+ module
+ .getCameraConfiguration()
+ .matchedCameraInfo
+ .uniquePath()
+ .equals(cameraInfo.uniquePath()))) {
+ logger.error(
+ "Camera unique-path already in use by active VisionModule! Cannot add " + cameraInfo);
}
- // Return no new sources because there are no new sources
- if (connectedCameras.isEmpty()) {
- if (!hasWarnedNoCameras) {
- logger.warn(
- "No cameras were detected! Check that all cameras are connected, and that the path is correct.");
- hasWarnedNoCameras = true;
- }
- return null;
- } else hasWarnedNoCameras = false;
-
- // Remove any known cameras.
- connectedCameras.removeIf(c -> knownCameras.contains(c));
-
- // All cameras are already loaded return no new sources.
- if (connectedCameras.isEmpty()) return null;
+ var source = loadVisionSourceFromCamConfig(new CameraConfiguration(cameraInfo));
+ var module = vmm.addSource(source);
- logger.debug("Matching " + connectedCameras.size() + " new camera(s)!");
-
- // Debug prints
- for (var info : connectedCameras) {
- logger.info("Detected unmatched physical camera: " + info.toString());
- }
+ module.start();
- if (!unmatchedLoadedConfigs.isEmpty())
- logger.debug("Trying to match " + unmatchedLoadedConfigs.size() + " unmatched config(s)...");
-
- // Match camera configs to physical cameras
- List matchedCameras =
- matchCameras(connectedCameras, unmatchedLoadedConfigs);
-
- unmatchedLoadedConfigs.removeAll(matchedCameras);
- if (!unmatchedLoadedConfigs.isEmpty() && !hasWarned) {
- logger.warn(
- () ->
- "After matching, "
- + unmatchedLoadedConfigs.size()
- + " config(s) remained unmatched. Is your camera disconnected?");
- logger.warn(
- "Unloaded configs: "
- + unmatchedLoadedConfigs.stream()
- .map(it -> it.nickname)
- .collect(Collectors.joining(", ")));
- hasWarned = true;
- }
+ // We have a new camera! Tell the world about it
+ DataChangeService.getInstance()
+ .publishEvent(
+ new OutgoingUIEvent<>(
+ "fullsettings",
+ UIPhotonConfiguration.programStateToUi(ConfigManager.getInstance().getConfig())));
- // We add the matched cameras to the known camera list
- this.knownCameras.addAll(connectedCameras);
+ pushUiUpdate();
- if (matchedCameras.isEmpty()) return null;
+ return true;
+ }
- // Turn these camera configs into vision sources
- var sources = loadVisionSourcesFromCamConfigs(matchedCameras, createSources);
+ public synchronized boolean deleteVisionSource(String uniqueName) {
+ deactivateVisionSource(uniqueName);
+ var config = disabledCameraConfigs.remove(uniqueName);
+ ConfigManager.getInstance().getConfig().removeCameraConfig(uniqueName);
+ ConfigManager.getInstance().saveToDisk();
- // Print info about each vision source
- for (var src : sources) {
- logger.debug(
- () ->
- "Matched config for camera \""
- + src.getFrameProvider().getName()
- + "\" and loaded "
- + src.getCameraConfiguration().pipelineSettings.size()
- + " pipelines");
- }
+ DataChangeService.getInstance()
+ .publishEvent(
+ new OutgoingUIEvent<>(
+ "fullsettings",
+ UIPhotonConfiguration.programStateToUi(ConfigManager.getInstance().getConfig())));
+ pushUiUpdate();
- return sources;
+ return config != null;
}
- /**
- * Get a predicate for checking cameras against a saved config.
- *
- * @param savedConfig The saved camera configuration to match against
- * @param checkUSBPath If we should compare the USB port/bus IDs
- * @param checkVidPid If we should compare USB VID and PID
- * @param checkBaseName If we should compare {@link CameraInfo#getBaseName}
- * @param checkPath If we should check {@link CameraInfo::path} (eg /dev/videoN on Linux, or
- * ?/usb#vid_05c8&pid_03df&mi_00#7&fa76035&0&0000#{e5323777-f976-4f5b-9b55-b94699c46e44}\global
- * on Windows)
- */
- private final Predicate getCameraMatcher(
- final CameraConfiguration savedConfig,
- boolean checkUSBPath,
- boolean checkVidPid,
- boolean checkBaseName,
- boolean checkPath) {
- if (checkUSBPath && savedConfig.getUSBPath().isEmpty()) {
- logger.debug(
- "WARN: Camera has empty USB path, but asked to match by name: "
- + savedConfig.toShortString());
+ public synchronized boolean deactivateVisionSource(String uniqueName) {
+ // try to find the module. If we find it, remove it from the VMM
+ var removedConfig =
+ vmm.getModules().stream()
+ .filter(module -> module.uniqueName().equals(uniqueName))
+ .findFirst()
+ .map(
+ it -> {
+ vmm.removeModule(it);
+ return it.getCameraConfiguration();
+ });
+
+ if (removedConfig.isEmpty()) {
+ logger.error("Could not find module " + uniqueName);
+ return false;
}
- return (CameraInfo physicalCamera) -> {
- var matches = true;
-
- if (checkUSBPath) {
- var savedPath = savedConfig.getUSBPath();
- matches &= (savedPath.isPresent() && physicalCamera.getUSBPath().equals(savedPath));
- }
- if (checkBaseName) {
- matches &= physicalCamera.getBaseName().equals(savedConfig.baseName);
- }
- if (checkVidPid) {
- matches &=
- (physicalCamera.vendorId == savedConfig.usbVID
- && physicalCamera.productId == savedConfig.usbPID);
- }
- if (checkPath) {
- matches &= (physicalCamera.path.equals(savedConfig.path));
- }
+ // And stuff it into our list of disabled camera configs
+ disabledCameraConfigs.put(removedConfig.get().uniqueName, removedConfig.get());
- matches &= (physicalCamera.cameraType == savedConfig.cameraType);
+ logger.info("Disabled the VisionModule for " + removedConfig.get().nickname);
- return matches;
- };
- }
+ pushUiUpdate();
- /**
- * Create {@link CameraConfiguration}s based on a list of detected USB cameras and the configs on
- * disk.
- *
- * @param detectedCamInfos Information about currently connected USB cameras.
- * @param loadedCamConfigs The USB {@link CameraConfiguration}s loaded from disk.
- * @return the matched configurations.
- */
- public List matchCameras(
- List detectedCamInfos, List loadedCamConfigs) {
- return matchCameras(
- detectedCamInfos,
- loadedCamConfigs,
- ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath);
+ return true;
}
- /**
- * Create {@link CameraConfiguration}s based on a list of detected USB cameras and the configs on
- * disk.
- *
- * @param detectedCamInfos Information about currently connected USB cameras.
- * @param loadedCamConfigs The USB {@link CameraConfiguration}s loaded from disk.
- * @param matchCamerasOnlyByPath If we should never try to match only by (base name, vid, pid)
- * @return the matched configurations.
- */
- public List matchCameras(
- List detectedCamInfos,
- List loadedCamConfigs,
- boolean matchCamerasOnlyByPath) {
- var detectedCameraList = new ArrayList<>(detectedCamInfos);
- ArrayList cameraConfigurations = new ArrayList();
- ArrayList unloadedConfigs =
- new ArrayList(loadedCamConfigs);
-
- logger.info("Matching CSI cameras by port & base name...");
- cameraConfigurations.addAll(
- matchCamerasByStrategy(
- detectedCameraList,
- unloadedConfigs,
- new CameraMatchingOptions(false, false, true, true, CameraType.ZeroCopyPicam)));
-
- logger.info("Matching USB cameras by usb port & name & USB VID/PID...");
- cameraConfigurations.addAll(
- matchCamerasByStrategy(
- detectedCameraList,
- unloadedConfigs,
- new CameraMatchingOptions(true, true, true, false, CameraType.UsbCamera)));
-
- // On windows, the v4l path is actually useful and tells us the port the camera is physically
- // connected to which is neat
- if (Platform.isWindows() && !matchCamerasOnlyByPath) {
- logger.info("Matching USB cameras by windows-path & USB VID/PID only...");
- cameraConfigurations.addAll(
- matchCamerasByStrategy(
- detectedCameraList,
- unloadedConfigs,
- new CameraMatchingOptions(false, true, true, true, CameraType.UsbCamera)));
- }
-
- logger.info("Matching USB cameras by usb port & USB VID/PID...");
- cameraConfigurations.addAll(
- matchCamerasByStrategy(
- detectedCameraList,
- unloadedConfigs,
- new CameraMatchingOptions(true, true, false, false, CameraType.UsbCamera)));
-
- // Legacy migration -- VID/PID will be unset, so we have to try with our most relaxed strategy
- // at least once. We _should_ still have a valid USB path (assuming cameras have not moved), so
- // try that first, then fallback to base name only beloow
- logger.info("Matching USB cameras by base-name & usb port...");
- cameraConfigurations.addAll(
- matchCamerasByStrategy(
- detectedCameraList,
- unloadedConfigs,
- new CameraMatchingOptions(true, false, true, false, CameraType.UsbCamera)));
-
- // handle disabling only-by-base-name matching
- if (!matchCamerasOnlyByPath) {
- logger.info("Matching USB cameras by base-name & USB VID/PID only...");
- cameraConfigurations.addAll(
- matchCamerasByStrategy(
- detectedCameraList,
- unloadedConfigs,
- new CameraMatchingOptions(false, true, true, false, CameraType.UsbCamera)));
-
- // Legacy migration for if no USB VID/PID set
- logger.info("Matching USB cameras by base-name only...");
- cameraConfigurations.addAll(
- matchCamerasByStrategy(
- detectedCameraList,
- unloadedConfigs,
- new CameraMatchingOptions(false, false, true, false, CameraType.UsbCamera)));
- } else logger.info("Skipping match by filepath/vid/pid, disabled by user");
-
- if (detectedCameraList.size() > 0) {
- // handle disabling only-by-base-name matching
- if (!matchCamerasOnlyByPath) {
- cameraConfigurations.addAll(
- createConfigsForCameras(detectedCameraList, unloadedConfigs, cameraConfigurations));
- } else {
- logger.warn(
- "Not creating 'new' Photon CameraConfigurations for ["
- + detectedCamInfos.stream()
- .map(CameraInfo::toString)
- .collect(Collectors.joining(";"))
- + "], disabled by user");
- }
- }
+ protected synchronized VisionSourceManagerState getVsmState() {
+ var ret = new VisionSourceManagerState();
- logger.debug("Matched or created " + cameraConfigurations.size() + " camera configs!");
- return cameraConfigurations;
- }
+ ret.allConnectedCameras = filterAllowedDevices(getConnectedCameras());
+ ret.disabledConfigs =
+ disabledCameraConfigs.values().stream().map(it -> it.toUiConfig()).toList();
- /**
- * Abstractly match cameras
- *
- * @param detectedCamInfos Physical cameras unmatched and attached to the device
- * @param unloadedConfigs {@link CameraConfiguration}
- * @param checkUSBPath If we should compare the USB port/bus IDs
- * @param checkVidPid If we should compare USB VID and PID
- * @param checkBaseName If we should check {@link CameraInfo::getBaseName}
- * @param checkPath If we should check {@link CameraInfo::path} (eg /dev/videoN on Linux, or
- * usb#vid_05c8&pid_03df&mi_00#7&fa76035&0&0000#{e5323777-f976-4f5b-9b55-b94699c46e44}\global
- * on Windows). Note that path may change based on order cameras are plugged in/unplugged on
- * Linux, and should not be trusted to remain the same.
- * @return All matched or created new configs
- */
- private List matchCamerasByStrategy(
- List detectedCamInfos,
- List unloadedConfigs,
- CameraMatchingOptions matchingOptions) {
- List ret = new ArrayList();
- List unloadedConfigsCopy =
- new ArrayList(unloadedConfigs);
-
- if (unloadedConfigsCopy.isEmpty()) return List.of();
-
- logger.debug("Matching with options " + matchingOptions.toString());
-
- for (CameraConfiguration config : unloadedConfigsCopy) {
- // Only run match path by id if the camera type is allowed. This allows us to specify matching
- // behavior per-camera-type
- if (matchingOptions.allowedTypes.contains(config.cameraType)) {
- logger.debug(
- String.format(
- "Trying to find a match for loaded camera %s (%s) with camera config: %s",
- config.baseName, config.uniqueName, config.toShortString()));
-
- // Get matcher and filter against it, picking out the first match
- Predicate matches =
- getCameraMatcher(
- config,
- matchingOptions.checkUSBPath,
- matchingOptions.checkVidPid,
- matchingOptions.checkBaseName,
- matchingOptions.checkPath);
- var cameraInfo = detectedCamInfos.stream().filter(matches).findFirst().orElse(null);
-
- // If we actually matched a camera to a config, remove that camera from the list
- // and add it to the output
- if (cameraInfo != null) {
- logger.debug(
- "Matched the config for "
- + config.uniqueName
- + " to the physical camera config above!");
- ret.add(mergeInfoIntoConfig(config, cameraInfo));
- detectedCamInfos.remove(cameraInfo);
- unloadedConfigs.remove(config);
- } else {
- logger.debug("No camera found for the config " + config.uniqueName);
- }
- }
- }
return ret;
}
- /**
- * Create new {@link CameraConfiguration}s for unmatched cameras, and assign them a unique name
- * (unique in the set of (loaded configs, unloaded configs, loaded vision modules) at least)
- */
- private List createConfigsForCameras(
- List detectedCameraList,
- List unloadedCamConfigs,
- List loadedConfigs) {
- List ret = new ArrayList();
- logger.debug(
- "After matching loaded configs, these cameras remained unmatched: "
- + detectedCameraList.stream()
- .map(n -> String.valueOf(n))
- .collect(Collectors.joining("-", "{", "}")));
- for (CameraInfo info : detectedCameraList) {
- // create new camera config for all new cameras
- String baseName = info.getBaseName();
- String uniqueName = info.getHumanReadableName();
-
- int suffix = 0;
- while (containsName(loadedConfigs, uniqueName)
- || containsName(uniqueName)
- || containsName(unloadedCamConfigs, uniqueName)
- || containsName(ret, uniqueName)) {
- suffix++;
- uniqueName = String.format("%s (%d)", uniqueName, suffix);
- }
-
- logger.info("Creating a new camera config for camera " + uniqueName);
-
- String nickname = uniqueName;
-
- CameraConfiguration configuration =
- new CameraConfiguration(baseName, uniqueName, nickname, info.path, info.otherPaths);
-
- configuration.cameraType = info.cameraType;
-
- ret.add(configuration);
- }
- return ret;
+ protected void pushUiUpdate() {
+ DataChangeService.getInstance()
+ .publishEvent(OutgoingUIEvent.wrappedOf("visionSourceManager", getVsmState()));
}
- private CameraConfiguration mergeInfoIntoConfig(CameraConfiguration cfg, CameraInfo info) {
- if (!cfg.path.equals(info.path)) {
- logger.debug("Updating path config from " + cfg.path + " to " + info.path);
- cfg.path = info.path;
- }
- cfg.otherPaths = info.otherPaths;
- cfg.cameraType = info.cameraType;
-
- if (cfg.otherPaths.length != info.otherPaths.length) {
- logger.debug(
- "Updating otherPath config from "
- + Arrays.toString(cfg.otherPaths)
- + " to "
- + Arrays.toString(info.otherPaths));
- cfg.otherPaths = info.otherPaths.clone();
- } else {
- for (int i = 0; i < info.otherPaths.length; i++) {
- if (!cfg.otherPaths[i].equals(info.otherPaths[i])) {
- logger.debug(
- "Updating otherPath config from "
- + Arrays.toString(cfg.otherPaths)
- + " to "
- + Arrays.toString(info.otherPaths));
- cfg.otherPaths = info.otherPaths.clone();
- break;
- }
- }
+ protected List getConnectedCameras() {
+ List cameraInfos = new ArrayList<>();
+ // find all connected cameras
+ // cscore can return usb and csi cameras but csi are filtered out
+ Stream.of(UsbCamera.enumerateUsbCameras())
+ .map(c -> PVCameraInfo.fromUsbCameraInfo(c))
+ .filter(c -> !(String.join("", c.otherPaths()).contains("csi-video")))
+ .filter(c -> !c.name().equals("unicam"))
+ .forEach(cameraInfos::add);
+ if (LibCameraJNILoader.isSupported()) {
+ // find all CSI cameras (Raspberry Pi cameras)
+ Stream.of(LibCameraJNI.getCameraNames())
+ .map(
+ path -> {
+ String name = LibCameraJNI.getSensorModel(path).getFriendlyName();
+ return PVCameraInfo.fromCSICameraInfo(path, name);
+ })
+ .forEach(cameraInfos::add);
}
- return cfg;
- }
+ // FileVisionSources are a bit quirky. They aren't enumerated by the above, but i still want my
+ // UI to look like it ought to work
+ vmm.getModules().stream()
+ .map(it -> it.getCameraConfiguration().matchedCameraInfo)
+ .filter(info -> info instanceof PVCameraInfo.PVFileCameraInfo)
+ .forEach(cameraInfos::add);
- public void setIgnoredCamerasRegex(String ignoredCamerasRegex) {
- this.ignoredCamerasRegex = ignoredCamerasRegex;
+ return cameraInfos;
}
- /**
- * Filter out any blacklisted or ignored devices.
- *
- * @param allDevices
- * @return list of devices with blacklisted or ignore devices removed.
- */
- private List filterAllowedDevices(List allDevices, Platform platform) {
- List filteredDevices = new ArrayList<>();
+ private static List filterAllowedDevices(List allDevices) {
+ Platform platform = Platform.getCurrentPlatform();
+ ArrayList filteredDevices = new ArrayList<>();
for (var device : allDevices) {
- if (deviceBlacklist.contains(device.name)) {
- logger.trace(
- "Skipping blacklisted device: \"" + device.name + "\" at \"" + device.path + "\"");
- } else if (device.name.matches(ignoredCamerasRegex)) {
- logger.trace("Skipping ignored device: \"" + device.name + "\" at \"" + device.path);
- } else if (device.getIsV4lCsiCamera()) {
- } else if (device.otherPaths.length == 0
- && platform.osType == OSType.LINUX
- && device.cameraType == CameraType.UsbCamera) {
+ boolean valid = false;
+ if (deviceBlacklist.contains(device.name())) {
logger.trace(
- "Skipping device with no other paths: \"" + device.name + "\" at \"" + device.path);
- // If cscore hasnt passed this other paths aka a path by id or a path as in usb port then we
- // cant guarantee it is a valid camera.
+ "Skipping blacklisted device: \"" + device.name() + "\" at \"" + device.path() + "\"");
+ } else if (device instanceof PVCameraInfo.PVUsbCameraInfo usbDevice) {
+ if (usbDevice.otherPaths.length == 0
+ && platform.osType == OSType.LINUX
+ && device.type() == CameraType.UsbCamera) {
+ logger.trace(
+ "Skipping device with no other paths: \""
+ + device.name()
+ + "\" at \""
+ + device.path());
+ } else if (Arrays.stream(usbDevice.otherPaths).anyMatch(it -> it.contains("csi-video"))
+ || usbDevice.name().equals("unicam")) {
+ logger.trace(
+ "Skipping CSI device from CSCore: \""
+ + device.name()
+ + "\" at \""
+ + device.path()
+ + "\"");
+ } else {
+ valid = true;
+ }
} else {
+ valid = true;
+ }
+ if (valid) {
filteredDevices.add(device);
logger.trace(
- "Adding local video device - \"" + device.name + "\" at \"" + device.path + "\"");
+ "Adding local video device - \"" + device.name() + "\" at \"" + device.path() + "\"");
}
}
return filteredDevices;
}
- private static List loadVisionSourcesFromCamConfigs(
- List camConfigs, boolean createSources) {
- var cameraSources = new ArrayList();
- for (var configuration : camConfigs) {
- // In unit tests, create dummy
- if (!createSources) {
- cameraSources.add(new TestSource(configuration));
- continue;
+ /**
+ * Convert a configuration into a VisionSource. The VisionSource type is pulled from the {@link
+ * CameraConfiguration}'s matchedCameraInfo. We depend on the underlying {@link VisionSource} to
+ * be robust to disconnected sources at boot
+ *
+ * Verify that nickname is unique within the set of desesrialized camera configurations, adding
+ * random characters if this isn't the case
+ */
+ protected VisionSource loadVisionSourceFromCamConfig(CameraConfiguration configuration) {
+ logger.debug("Creating VisionSource for " + configuration.toShortString());
+
+ // First, make sure that nickname is globally unique since we use the nickname in NetworkTables.
+ // "Just one more source of truth bro it'll real this time I promise"
+ var currentNicknames = new ArrayList();
+ this.disabledCameraConfigs.values().stream()
+ .map(it -> it.nickname)
+ .forEach(currentNicknames::add);
+ this.vmm.getModules().stream()
+ .map(it -> it.getCameraConfiguration().nickname)
+ .forEach(currentNicknames::add);
+ // while it's a duplicate
+ while (currentNicknames.contains(configuration.nickname)) {
+ // if we already have a number, extract
+ var pattern = Pattern.compile("(^.*) \\(([0-9]+)\\)$");
+ var matcher = pattern.matcher(configuration.nickname);
+ if (matcher.find()) {
+ int oldNumber = Integer.parseInt(matcher.group(2));
+ int newNumber = oldNumber + 1;
+ configuration.nickname = matcher.group(1) + " (" + newNumber + ")";
+ } else {
+ configuration.nickname += " (1)";
}
+ }
- boolean is_pi = Platform.isRaspberryPi();
+ VisionSource source =
+ switch (configuration.matchedCameraInfo.type()) {
+ case UsbCamera -> new USBCameraSource(configuration);
+ case ZeroCopyPicam -> new LibcameraGpuSource(configuration);
+ case FileCamera -> new FileVisionSource(configuration);
+ };
- if (configuration.cameraType == CameraType.ZeroCopyPicam && is_pi) {
- // If the camera was loaded from libcamera then create its source using libcamera.
- var piCamSrc = new LibcameraGpuSource(configuration);
- cameraSources.add(piCamSrc);
- } else {
- var newCam = new USBCameraSource(configuration);
- if (!newCam.getCameraQuirks().hasQuirk(CameraQuirk.CompletelyBroken)
- && !newCam.getSettables().videoModes.isEmpty()) {
- cameraSources.add(newCam);
- }
- }
- logger.debug("Creating VisionSource for " + configuration.toShortString());
+ if (source.getFrameProvider() == null) {
+ logger.error("Frame provider is null?");
+ }
+ if (source.getSettables() == null) {
+ logger.error("Settables are null?");
}
- return cameraSources;
- }
- /**
- * Check if a given config list contains the given unique name.
- *
- * @param configList A list of camera configs.
- * @param uniqueName The unique name.
- * @return If the list of configs contains the unique name.
- */
- private boolean containsName(
- final List configList, final String uniqueName) {
- return configList.stream()
- .anyMatch(configuration -> configuration.uniqueName.equals(uniqueName));
+ return source;
}
- /**
- * Check if the current list of known cameras contains the given unique name.
- *
- * @param uniqueName The unique name.
- * @return If the list of cameras contains the unique name.
- */
- private boolean containsName(final String uniqueName) {
- return VisionModuleManager.getInstance().getModules().stream()
- .anyMatch(camera -> camera.visionSource.cameraConfiguration.uniqueName.equals(uniqueName));
+ public List getVisionModules() {
+ return vmm.getModules();
}
}
diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceSettables.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceSettables.java
index 4db1176b6d..2b299c14dc 100644
--- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceSettables.java
+++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceSettables.java
@@ -26,22 +26,33 @@
import org.photonvision.vision.frame.FrameStaticProperties;
public abstract class VisionSourceSettables {
- protected static final Logger logger =
- new Logger(VisionSourceSettables.class, LogGroup.VisionModule);
+ protected Logger logger;
private final CameraConfiguration configuration;
protected VisionSourceSettables(CameraConfiguration configuration) {
this.configuration = configuration;
+ this.logger =
+ new Logger(VisionSourceSettables.class, configuration.nickname, LogGroup.VisionModule);
}
- protected FrameStaticProperties frameStaticProperties;
- protected HashMap videoModes;
+ protected FrameStaticProperties frameStaticProperties = null;
+ protected HashMap videoModes = new HashMap<>();
public CameraConfiguration getConfiguration() {
return configuration;
}
+ // If the device has been connected at least once, and we cached properties
+ protected boolean cameraPropertiesCached = false;
+
+ /**
+ * Runs exactly once the first time that the underlying device goes from disconnected to connected
+ */
+ public void onCameraConnected() {
+ cameraPropertiesCached = true;
+ }
+
public abstract void setExposureRaw(double exposureRaw);
public abstract double getMinExposureRaw();
@@ -109,7 +120,7 @@ public void addCalibration(CameraCalibrationCoefficients calibrationCoefficients
calculateFrameStaticProps();
}
- private void calculateFrameStaticProps() {
+ protected void calculateFrameStaticProps() {
var videoMode = getCurrentVideoMode();
this.frameStaticProperties =
new FrameStaticProperties(
diff --git a/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java b/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java
index d564e8319e..8f5c333a86 100644
--- a/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java
+++ b/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java
@@ -30,6 +30,7 @@
import org.photonvision.common.logging.Logger;
import org.photonvision.common.util.TestUtils;
import org.photonvision.common.util.file.JacksonUtils;
+import org.photonvision.vision.camera.PVCameraInfo;
import org.photonvision.vision.pipeline.AprilTagPipelineSettings;
import org.photonvision.vision.pipeline.CVPipelineSettings;
import org.photonvision.vision.pipeline.ColoredShapePipelineSettings;
@@ -39,7 +40,8 @@
public class ConfigTest {
private static ConfigManager configMgr;
private static final CameraConfiguration cameraConfig =
- new CameraConfiguration("TestCamera", "/dev/video420");
+ new CameraConfiguration(
+ "TestCamera", PVCameraInfo.fromFileInfo("TestCamera", "/dev/video420"));
private static ReflectivePipelineSettings REFLECTIVE_PIPELINE_SETTINGS;
private static ColoredShapePipelineSettings COLORED_SHAPE_PIPELINE_SETTINGS;
private static AprilTagPipelineSettings APRIL_TAG_PIPELINE_SETTINGS;
diff --git a/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java b/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java
index e991c9ad39..dec8d7e9be 100644
--- a/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java
+++ b/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java
@@ -20,6 +20,7 @@
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
import static org.junit.jupiter.api.Assertions.assertEquals;
+import edu.wpi.first.cscore.UsbCameraInfo;
import java.io.File;
import java.io.IOException;
import java.nio.file.Files;
@@ -32,8 +33,7 @@
import org.junit.jupiter.api.Test;
import org.photonvision.common.util.TestUtils;
import org.photonvision.vision.camera.CameraQuirk;
-import org.photonvision.vision.camera.CameraType;
-import org.photonvision.vision.camera.QuirkyCamera;
+import org.photonvision.vision.camera.PVCameraInfo;
import org.photonvision.vision.pipeline.AprilTagPipelineSettings;
import org.photonvision.vision.pipeline.ColoredShapePipelineSettings;
import org.photonvision.vision.pipeline.ReflectivePipelineSettings;
@@ -76,26 +76,18 @@ public void testLoad() {
cfgLoader.load();
- var testcamcfg =
+ var testCamCfg =
new CameraConfiguration(
- "basename",
- "a_unique_name",
- "a_nick_name",
- 69,
- "a/path/idk",
- CameraType.UsbCamera,
- QuirkyCamera.getQuirkyCamera(-1, -1),
- List.of(),
- 0,
- -1,
- -1);
- testcamcfg.pipelineSettings =
+ PVCameraInfo.fromUsbCameraInfo(
+ new UsbCameraInfo(0, "/dev/videoN", "some_name", new String[0], -1, 01)));
+
+ testCamCfg.pipelineSettings =
List.of(
new ReflectivePipelineSettings(),
new AprilTagPipelineSettings(),
new ColoredShapePipelineSettings());
- cfgLoader.getConfig().addCameraConfig(testcamcfg);
+ cfgLoader.getConfig().addCameraConfig(testCamCfg);
cfgLoader.getConfig().getNetworkConfig().ntServerAddress = "5940";
cfgLoader.saveToDisk();
diff --git a/photon-core/src/test/java/org/photonvision/vision/processes/MockUsbCameraSource.java b/photon-core/src/test/java/org/photonvision/vision/processes/MockUsbCameraSource.java
index f1fdc36a1d..e17367adc2 100644
--- a/photon-core/src/test/java/org/photonvision/vision/processes/MockUsbCameraSource.java
+++ b/photon-core/src/test/java/org/photonvision/vision/processes/MockUsbCameraSource.java
@@ -31,7 +31,8 @@ public class MockUsbCameraSource extends USBCameraSource {
public MockUsbCameraSource(CameraConfiguration config, int pid, int vid) {
super(config);
- getCameraConfiguration().cameraQuirks = QuirkyCamera.getQuirkyCamera(pid, vid, config.baseName);
+ getCameraConfiguration().cameraQuirks =
+ QuirkyCamera.getQuirkyCamera(pid, vid, config.matchedCameraInfo.name());
/** File used as frame provider */
usbFrameProvider =
diff --git a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java
index 4eb4adf6fa..465cc9bc69 100644
--- a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java
+++ b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java
@@ -34,6 +34,7 @@
import org.photonvision.common.dataflow.CVPipelineResultConsumer;
import org.photonvision.common.util.TestUtils;
import org.photonvision.jni.PhotonTargetingJniLoader;
+import org.photonvision.vision.camera.PVCameraInfo;
import org.photonvision.vision.camera.QuirkyCamera;
import org.photonvision.vision.camera.USBCameras.USBCameraSource;
import org.photonvision.vision.frame.FrameProvider;
@@ -90,6 +91,9 @@ public boolean hasLEDs() {
public void remakeSettables() {
return;
}
+
+ @Override
+ public void release() {}
}
private static class TestSettables extends VisionSourceSettables {
@@ -166,7 +170,9 @@ public void accept(CVPipelineResult result) {
public void setupManager() {
ConfigManager.getInstance().load();
- var conf = new CameraConfiguration("Foo", "Bar");
+ var vmm = new VisionModuleManager();
+
+ var conf = new CameraConfiguration(PVCameraInfo.fromFileInfo("Foo", "Bar"));
var ffp =
new FileFrameProvider(
TestUtils.getWPIImagePath(TestUtils.WPI2019Image.kCargoStraightDark72in_HighRes, false),
@@ -174,12 +180,12 @@ public void setupManager() {
var testSource = new TestSource(ffp, conf);
- var modules = VisionModuleManager.getInstance().addSources(List.of(testSource));
+ var module = vmm.addSource(testSource);
var module0DataConsumer = new TestDataConsumer();
- VisionModuleManager.getInstance().visionModules.get(0).addResultConsumer(module0DataConsumer);
+ module.addResultConsumer(module0DataConsumer);
- modules.forEach(VisionModule::start);
+ module.start();
sleep(1500);
@@ -193,7 +199,7 @@ public void testMultipleStreamIndex() {
var vmm = new VisionModuleManager();
- var conf = new CameraConfiguration("Foo", "Bar");
+ var conf = new CameraConfiguration(PVCameraInfo.fromFileInfo("Foo", "Bar"));
conf.streamIndex = 1;
var ffp =
new FileFrameProvider(
@@ -201,7 +207,7 @@ public void testMultipleStreamIndex() {
TestUtils.WPI2019Image.FOV);
var testSource = new TestSource(ffp, conf);
- var conf2 = new CameraConfiguration("Foo2", "Bar");
+ var conf2 = new CameraConfiguration(PVCameraInfo.fromFileInfo("Foo2", "Bar2"));
conf2.streamIndex = 0;
var ffp2 =
new FileFrameProvider(
@@ -209,7 +215,7 @@ public void testMultipleStreamIndex() {
TestUtils.WPI2019Image.FOV);
var testSource2 = new TestSource(ffp2, conf2);
- var conf3 = new CameraConfiguration("Foo3", "Bar");
+ var conf3 = new CameraConfiguration(PVCameraInfo.fromFileInfo("Foo3", "Bar3"));
conf3.streamIndex = 0;
var ffp3 =
new FileFrameProvider(
@@ -218,24 +224,23 @@ public void testMultipleStreamIndex() {
var testSource3 = new TestSource(ffp3, conf3);
// Arducam OV9281 UC844 raspberry pi test.
- var conf4 = new CameraConfiguration("Left", "dev/video1");
+ var conf4 = new CameraConfiguration(PVCameraInfo.fromFileInfo("Left", "/dev/video1"));
USBCameraSource usbSimulation = new MockUsbCameraSource(conf4, 0x6366, 0x0c45);
- var conf5 = new CameraConfiguration("Right", "dev/video2");
+ var conf5 = new CameraConfiguration(PVCameraInfo.fromFileInfo("Right", "/dev/video2"));
USBCameraSource usbSimulation2 = new MockUsbCameraSource(conf5, 0x6366, 0x0c45);
var modules =
- vmm.addSources(
- List.of(testSource, testSource2, testSource3, usbSimulation, usbSimulation2));
+ List.of(testSource, testSource2, testSource3, usbSimulation, usbSimulation2).stream()
+ .map(vmm::addSource)
+ .collect(Collectors.toList());
System.out.println(
Arrays.toString(
- modules.stream()
- .map(it -> it.visionSource.getCameraConfiguration().streamIndex)
- .toArray()));
+ modules.stream().map(it -> it.getCameraConfiguration().streamIndex).toArray()));
var idxs =
modules.stream()
- .map(it -> it.visionSource.getCameraConfiguration().streamIndex)
+ .map(it -> it.getCameraConfiguration().streamIndex)
.collect(Collectors.toList());
assertTrue(usbSimulation.equals(usbSimulation));
diff --git a/photon-core/src/test/java/org/photonvision/vision/processes/VisionSourceManagerTest.java b/photon-core/src/test/java/org/photonvision/vision/processes/VisionSourceManagerTest.java
index 17cd2ed068..fddeb8e3fb 100644
--- a/photon-core/src/test/java/org/photonvision/vision/processes/VisionSourceManagerTest.java
+++ b/photon-core/src/test/java/org/photonvision/vision/processes/VisionSourceManagerTest.java
@@ -17,674 +17,223 @@
package org.photonvision.vision.processes;
-import static org.junit.jupiter.api.Assertions.*;
+import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+import edu.wpi.first.cscore.UsbCameraInfo;
+import java.io.IOException;
import java.util.ArrayList;
import java.util.List;
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeAll;
+import org.junit.jupiter.api.BeforeEach;
import org.junit.jupiter.api.Test;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.configuration.ConfigManager;
-import org.photonvision.common.hardware.Platform;
-import org.photonvision.common.logging.LogGroup;
-import org.photonvision.common.logging.LogLevel;
-import org.photonvision.common.logging.Logger;
-import org.photonvision.vision.camera.CameraInfo;
-import org.photonvision.vision.camera.CameraType;
+import org.photonvision.common.util.TestUtils;
+import org.photonvision.common.util.file.JacksonUtils;
+import org.photonvision.jni.PhotonTargetingJniLoader;
+import org.photonvision.vision.camera.PVCameraInfo;
public class VisionSourceManagerTest {
- @Test
- public void visionSourceTest() {
- Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
-
- var inst = new VisionSourceManager();
- var cameraInfos = new ArrayList();
- ConfigManager.getInstance().clearConfig();
- ConfigManager.getInstance().load();
-
- inst.tryMatchCamImpl(cameraInfos);
-
- var config3 =
- new CameraConfiguration(
- "thirdTestVideo",
- "thirdTestVideo",
- "thirdTestVideo",
- "dev/video1",
- new String[] {"by-id/123"});
- config3.usbVID = 3;
- config3.usbPID = 4;
- var config4 =
- new CameraConfiguration(
- "fourthTestVideo",
- "fourthTestVideo",
- "fourthTestVideo",
- "dev/video2",
- new String[] {"by-id/321"});
- config4.usbVID = 5;
- config4.usbPID = 6;
-
- CameraInfo info1 =
- new CameraInfo(0, "dev/video0", "testVideo", new String[] {"/usb/path/0"}, 1, 2);
-
- cameraInfos.add(info1);
-
- inst.registerLoadedConfigs(config3, config4);
-
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(inst.knownCameras.contains(info1));
- assertEquals(2, inst.unmatchedLoadedConfigs.size());
-
- CameraInfo info2 =
- new CameraInfo(0, "dev/video1", "secondTestVideo", new String[] {"/usb/path/1"}, 2, 3);
-
- cameraInfos.add(info2);
-
- var cams = inst.matchCameras(cameraInfos, inst.unmatchedLoadedConfigs);
+ // Test harness that overrides getConnectedCameras, but uses USB cameras for
+ // everything else
+ // when we start testing libcamera stuff we'll need to mock more stuff out
+ private static class TestVsm extends VisionSourceManager {
+ public List testCameras = new ArrayList<>();
+
+ @Override
+ protected List getConnectedCameras() {
+ return testCameras;
+ }
- // assertEquals("testVideo (1)", cams.get(0).uniqueName); // Proper suffixing
-
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(inst.knownCameras.contains(info2));
- assertEquals(2, inst.unmatchedLoadedConfigs.size());
-
- CameraInfo info3 =
- new CameraInfo(0, "dev/video2", "thirdTestVideo", new String[] {"by-id/123"}, 3, 4);
-
- CameraInfo info4 =
- new CameraInfo(0, "dev/video3", "fourthTestVideo", new String[] {"by-id/321"}, 5, 6);
-
- cameraInfos.add(info4);
-
- cams = inst.matchCameras(cameraInfos, inst.unmatchedLoadedConfigs);
-
- var cam4 =
- cams.stream()
- .filter(
- cam -> cam.otherPaths.length > 0 && cam.otherPaths[0].equals(config4.otherPaths[0]))
- .findFirst()
- .orElse(null);
- // If this is null, cam4 got matched to config3 instead of config4
-
- assertEquals(cam4.nickname, config4.nickname);
-
- cameraInfos.add(info3);
-
- cams = inst.matchCameras(cameraInfos, inst.unmatchedLoadedConfigs);
-
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(inst.knownCameras.contains(info2));
- assertTrue(inst.knownCameras.contains(info3));
-
- var cam3 =
- cams.stream()
- .filter(
- cam -> cam.otherPaths.length > 0 && cam.otherPaths[0].equals(config3.otherPaths[0]))
- .findFirst()
- .orElse(null);
- cam4 =
- cams.stream()
- .filter(
- cam -> cam.otherPaths.length > 0 && cam.otherPaths[0].equals(config4.otherPaths[0]))
- .findFirst()
- .orElse(null);
-
- assertEquals(cam3.nickname, config3.nickname);
- assertEquals(cam4.nickname, config4.nickname);
-
- CameraInfo info5 =
- new CameraInfo(
- 2,
- "/dev/video2",
- "Left Camera",
- new String[] {
- "/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Left_Camera_12345-video-index0",
- "/dev/v4l/by-path/platform-xhci-hcd.0-usb-0:2:1.0-video-index0"
- },
- 7,
- 8);
- cameraInfos.add(info5);
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(inst.knownCameras.contains(info5));
-
- CameraInfo info6 =
- new CameraInfo(
- 3,
- "dev/video3",
- "Right Camera",
- new String[] {
- "/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Right_Camera_123456-video-index0",
- "/dev/v4l/by-path/platform-xhci-hcd.1-usb-0:1:1.0-video-index0"
- },
- 9,
- 10);
- cameraInfos.add(info6);
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(inst.knownCameras.contains(info6));
-
- // RPI 5 CSI Tests
-
- // CSI CAMERAS SHOULD NOT BE LOADED LIKE THIS THEY SHOULD GO THROUGH LIBCAM.
- CameraInfo info7 =
- new CameraInfo(
- 4,
- "dev/video4",
- "CSICAM-DEV", // Typically rp1-cfe for unit test changed to CSICAM-DEV
- new String[] {"/dev/v4l/by-path/platform-1f00110000.csi-video-index0"},
- 11,
- 12);
- cameraInfos.add(info7);
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(!inst.knownCameras.contains(info7)); // This camera should not be recognized/used.
-
- CameraInfo info8 =
- new CameraInfo(
- 5,
- "dev/video8",
- "CSICAM-DEV", // Typically rp1-cfe for unit test changed to CSICAM-DEV
- new String[] {"/dev/v4l/by-path/platform-1f00110000.csi-video-index4"},
- 13,
- 14);
- cameraInfos.add(info8);
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(!inst.knownCameras.contains(info8)); // This camera should not be recognized/used.
-
- CameraInfo info9 =
- new CameraInfo(
- 6,
- "dev/video9",
- "CSICAM-DEV", // Typically rp1-cfe for unit test changed to CSICAM-DEV
- new String[] {"/dev/v4l/by-path/platform-1f00110000.csi-video-index5"},
- 15,
- 16);
- cameraInfos.add(info9);
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(!inst.knownCameras.contains(info9)); // This camera should not be recognized/used.
- assertEquals(6, inst.knownCameras.size());
- assertEquals(0, inst.unmatchedLoadedConfigs.size());
-
- // RPI LIBCAMERA CSI CAMERA TESTS
- CameraInfo info10 =
- new CameraInfo(
- -1,
- "/base/soc/i2c0mux/i2c@0/ov9281@60",
- "OV9281", // Typically rp1-cfe for unit test changed to CSICAM-DEV
- new String[] {},
- -1,
- -1,
- CameraType.ZeroCopyPicam);
- cameraInfos.add(info10);
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(inst.knownCameras.contains(info10));
- assertEquals(7, inst.knownCameras.size());
- assertEquals(0, inst.unmatchedLoadedConfigs.size());
-
- CameraInfo info11 =
- new CameraInfo(
- -1,
- "/base/soc/i2c0mux/i2c@1/ov9281@60",
- "OV9281", // Typically rp1-cfe for unit test changed to CSICAM-DEV
- new String[] {},
- -1,
- -1,
- CameraType.ZeroCopyPicam);
- cameraInfos.add(info11);
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(inst.knownCameras.contains(info11));
- assertEquals(8, inst.knownCameras.size());
- assertEquals(0, inst.unmatchedLoadedConfigs.size());
-
- CameraInfo info12 =
- new CameraInfo(
- -1,
- " /base/axi/pcie@120000/rp1/i2c@80000/ov5647@36",
- "Camera Module v1",
- new String[] {},
- -1,
- -1,
- CameraType.ZeroCopyPicam);
- cameraInfos.add(info12);
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(inst.knownCameras.contains(info12));
- assertEquals(9, inst.knownCameras.size());
- assertEquals(0, inst.unmatchedLoadedConfigs.size());
-
- CameraInfo info13 =
- new CameraInfo(
- -1,
- "/base/axi/pcie@120000/rp1/i2c@88000/imx708@1a",
- "Camera Module v3",
- new String[] {},
- -1,
- -1,
- CameraType.ZeroCopyPicam);
- cameraInfos.add(info13);
- inst.tryMatchCamImpl(cameraInfos);
-
- assertTrue(inst.knownCameras.contains(info13));
- assertEquals(10, inst.knownCameras.size());
- assertEquals(0, inst.unmatchedLoadedConfigs.size());
+ public void teardown() {
+ // release native resources
+ var uniqueNames = getVisionModules().stream().map(VisionModule::uniqueName).toList();
+ for (var name : uniqueNames) {
+ deactivateVisionSource(name);
+ }
+ }
}
- @Test
- public void testDisableInhibitPathChangeIdenticalCams() {
- Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
+ @BeforeAll
+ public static void loadLibraries() {
+ TestUtils.loadLibraries();
+ assertDoesNotThrow(PhotonTargetingJniLoader::load);
+ assertTrue(PhotonTargetingJniLoader.isWorking);
- var inst = new VisionSourceManager();
- ConfigManager.getInstance().clearConfig();
+ // Broadcast all still calls into configmanager (ew) so set that up here
ConfigManager.getInstance().load();
- ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath = false;
-
- var CAM2_OLD_PATH =
- new String[] {"/dev/v4l/by-path/platform-fc880000.usb-usb-0:1:1.0-video-index0"};
- var CAM2_NEW_PATH =
- new String[] {"/dev/v4l/by-path/platform-fc880080.usb-usb-0:1:1.3-video-index0"};
-
- var CAM1_OLD_PATHS =
- new String[] {
- "/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Arducam_OV2311_USB_Camera_UC621-video-index0",
- "/dev/v4l/by-path/platform-fc800000.usb-usb-0:1:1.0-video-index0"
- };
-
- var camera1_saved_config =
- new CameraConfiguration(
- "Arducam OV2311 USB Camera",
- "Arducam OV2311 USB Camera",
- "front-left",
- "/dev/video0",
- CAM1_OLD_PATHS);
- camera1_saved_config.usbVID = 3141;
- camera1_saved_config.usbPID = 25446;
- var camera2_saved_config =
- new CameraConfiguration(
- "Arducam OV2311 USB Camera",
- "Arducam OV2311 USB Camera (1)",
- "front-left",
- "/dev/video2",
- CAM2_OLD_PATH);
- camera2_saved_config.usbVID = 3141;
- camera2_saved_config.usbPID = 25446;
-
- // And load our "old" configs
- inst.registerLoadedConfigs(camera1_saved_config, camera2_saved_config);
-
- // Camera attached to new port, but strict matching disabled
- {
- CameraInfo info1 =
- new CameraInfo(
- 0, "/dev/video11", "Arducam OV2311 USB Camera", CAM1_OLD_PATHS, 3141, 25446);
- CameraInfo info2 =
- new CameraInfo(
- 0, "/dev/video12", "Arducam OV2311 USB Camera", CAM2_NEW_PATH, 3141, 25446);
-
- var cameraInfos = new ArrayList();
- cameraInfos.add(info1);
- cameraInfos.add(info2);
- List ret1 = inst.tryMatchCamImpl(cameraInfos);
-
- // and check the new one got matched got matched
- assertEquals(2, ret1.size());
- assertEquals(
- 1, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info1.path)).count());
- assertEquals(
- 1, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info2.path)).count());
- }
}
- @Test
- public void testInhibitPathChangeIdenticalCams() {
- Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
+ private TestVsm vsm = null;
- var inst = new VisionSourceManager();
+ @BeforeEach
+ public void createVsm() {
ConfigManager.getInstance().clearConfig();
- ConfigManager.getInstance().load();
- ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath = true;
-
- var CAM2_OLD_PATH =
- new String[] {"/dev/v4l/by-path/platform-fc880000.usb-usb-0:1:1.0-video-index0"};
- var CAM2_NEW_PATH =
- new String[] {"/dev/v4l/by-path/platform-fc880080.usb-usb-0:1:1.3-video-index0"};
+ vsm = new TestVsm();
+ }
- var CAM1_OLD_PATHS =
- new String[] {
- "/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Arducam_OV2311_USB_Camera_UC621-video-index0",
- "/dev/v4l/by-path/platform-fc800000.usb-usb-0:1:1.0-video-index0"
- };
+ @AfterEach
+ public void teardownVsm() {
+ vsm.teardown();
+ }
- var camera1_saved_config =
- new CameraConfiguration(
- "Arducam OV2311 USB Camera",
- "Arducam OV2311 USB Camera (1)",
- "front-left",
- "/dev/video0",
- CAM1_OLD_PATHS);
- camera1_saved_config.usbVID = 3141;
- camera1_saved_config.usbPID = 25446;
- var camera2_saved_config =
- new CameraConfiguration(
- "Arducam OV2311 USB Camera",
- "Arducam OV2311 USB Camera (1)",
- "front-left",
- "/dev/video2",
- CAM2_OLD_PATH);
- camera2_saved_config.usbVID = 3141;
- camera2_saved_config.usbPID = 25446;
-
- // And load our "old" configs
- inst.registerLoadedConfigs(camera1_saved_config, camera2_saved_config);
-
- // initial pass with camera in the wrong spot
+ @Test
+ public void testCameraInfoSerde() throws InterruptedException, IOException {
{
- // Give our cameras new "paths" to fake the windows logic out. this should not
- // affect strict matching
- CameraInfo info1 =
- new CameraInfo(
- 0, "/dev/video11", "Arducam OV2311 USB Camera", CAM1_OLD_PATHS, 3141, 25446);
- CameraInfo info2 =
- new CameraInfo(
- 0, "/dev/video12", "Arducam OV2311 USB Camera", CAM2_NEW_PATH, 3141, 25446);
-
- var cameraInfos = new ArrayList();
- cameraInfos.add(info1);
- cameraInfos.add(info2);
- List ret1 = inst.tryMatchCamImpl(cameraInfos);
-
- // Our cameras should be "known"
- assertTrue(inst.knownCameras.contains(info1));
- assertTrue(inst.knownCameras.contains(info2));
- assertEquals(2, inst.knownCameras.size());
-
- // And we should have matched one camera
- assertEquals(1, ret1.size());
- // and only matched camera1, not 2
- assertEquals(
- 1, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info1.path)).count());
- assertEquals(
- 0, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info2.path)).count());
+ var usb =
+ PVCameraInfo.fromUsbCameraInfo(
+ new UsbCameraInfo(
+ 2,
+ "/dev/video2",
+ "Left Camera", // renamed arducam
+ new String[] {
+ "/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Left_Camera_12345-video-index0",
+ "/dev/v4l/by-path/platform-xhci-hcd.0-usb-0:2:1.0-video-index0"
+ },
+ 7,
+ 8));
+
+ var str = JacksonUtils.serializeToString(usb);
+ System.out.println(str);
+ System.out.println(JacksonUtils.deserialize(str, PVCameraInfo.class));
}
-
- // Now move our camera back
{
- CameraInfo info1 =
- new CameraInfo(
- 0, "/dev/video11", "Arducam OV2311 USB Camera", CAM1_OLD_PATHS, 3141, 25446);
- CameraInfo info2 =
- new CameraInfo(
- 0, "/dev/video12", "Arducam OV2311 USB Camera", CAM2_OLD_PATH, 3141, 25446);
-
- var cameraInfos = new ArrayList();
- cameraInfos.add(info1);
- cameraInfos.add(info2);
- List ret1 = inst.tryMatchCamImpl(cameraInfos);
-
- // and check the new one got matched got matched
- assertEquals(1, ret1.size());
- assertEquals(
- 0, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info1.path)).count());
- assertEquals(
- 1, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info2.path)).count());
+ var csi =
+ PVCameraInfo.fromCSICameraInfo(
+ "/dev/v4l/by-path/platform-1f00110000.csi-video-index0", "rp1-cfe");
+ var str = JacksonUtils.serializeToString(csi);
+ System.out.println(str);
+ System.out.println(JacksonUtils.deserialize(str, PVCameraInfo.class));
}
}
@Test
- public void testCSICameraMatching() {
- Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
+ public void testEmpty() {
+ var vsm = new TestVsm();
- // List of known cameras
- var cameraInfos = new ArrayList();
-
- var inst = new VisionSourceManager();
- ConfigManager.getInstance().clearConfig();
- ConfigManager.getInstance().load();
- ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath = false;
-
- CameraInfo info1 =
- new CameraInfo(
- -1,
- "/base/soc/i2c0mux/i2c@0/ov9281@60",
- "OV9281", // Typically rp1-cfe for unit test changed to CSICAM-DEV
- new String[] {},
- -1,
- -1,
- CameraType.ZeroCopyPicam);
-
- CameraInfo info2 =
- new CameraInfo(
- -1,
- "/base/soc/i2c0mux/i2c@1/ov9281@60",
- "OV9281", // Typically rp1-cfe for unit test changed to CSICAM-DEV
- new String[] {},
- -1,
- -1,
- CameraType.ZeroCopyPicam);
-
- var camera1_saved_config =
- new CameraConfiguration(
- "OV9281", "OV9281", "test-1", "/base/soc/i2c0mux/i2c@0/ov9281@60", new String[0]);
- camera1_saved_config.cameraType = CameraType.ZeroCopyPicam;
- camera1_saved_config.usbVID = -1;
- camera1_saved_config.usbPID = -1;
+ List configs = List.of();
+ vsm.registerLoadedConfigs(configs);
- var camera2_saved_config =
- new CameraConfiguration(
- "OV9281", "OV9281 (1)", "test-2", "/base/soc/i2c0mux/i2c@1/ov9281@60", new String[0]);
- camera2_saved_config.usbVID = -1;
- camera2_saved_config.usbPID = -1;
- camera2_saved_config.cameraType = CameraType.ZeroCopyPicam;
-
- cameraInfos.add(info1);
- cameraInfos.add(info2);
-
- // Try matching with both cameras being "known"
- inst.registerLoadedConfigs(camera1_saved_config, camera2_saved_config);
- var ret1 = inst.tryMatchCamImpl(cameraInfos);
-
- // Our cameras should be "known"
- assertTrue(inst.knownCameras.contains(info1));
- assertTrue(inst.knownCameras.contains(info2));
- assertEquals(2, inst.knownCameras.size());
- assertEquals(2, ret1.size());
-
- // Exactly one camera should have the path we put in
- for (int i = 0; i < cameraInfos.size(); i++) {
- var testPath = cameraInfos.get(i).path;
- assertEquals(
- 1, ret1.stream().filter(it -> testPath.equals(it.cameraConfiguration.path)).count());
- }
+ // And make assertions about the current matching state
+ assertEquals(0, vsm.getVsmState().allConnectedCameras.size());
+ assertEquals(0, vsm.getVsmState().disabledConfigs.size());
+ assertEquals(0, vsm.vmm.getModules().size());
}
@Test
- public void testNoOtherPaths() {
- Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
-
- // List of known cameras
- var cameraInfos = new ArrayList();
-
- var inst = new VisionSourceManager();
- ConfigManager.getInstance().clearConfig();
- ConfigManager.getInstance().load();
- ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath = false;
+ public void testFileVisionSource() throws InterruptedException, IOException {
+ var fileCamera1 =
+ PVCameraInfo.fromFileInfo(
+ TestUtils.getApriltagImagePath(TestUtils.ApriltagTestImages.kTag1_640_480, false)
+ .toAbsolutePath()
+ .toString(),
+ "kTag1_640_480");
- // Match empty camera infos
- inst.tryMatchCamImpl(cameraInfos);
+ vsm.testCameras = List.of(fileCamera1);
- CameraInfo info1 =
- new CameraInfo(0, "/dev/video0", "Arducam OV2311 USB Camera", new String[] {}, 3141, 25446);
+ List configs = List.of();
+ vsm.registerLoadedConfigs(configs);
- cameraInfos.add(info1);
+ vsm.assignUnmatchedCamera(fileCamera1);
- // Match two "new" cameras
- var ret1 = inst.tryMatchCamImpl(cameraInfos, Platform.LINUX_64);
+ System.out.println(JacksonUtils.serializeToString(ConfigManager.getInstance().getConfig()));
- // Our cameras should be "known"
- assertFalse(inst.knownCameras.contains(info1));
- assertEquals(0, inst.knownCameras.size());
- assertEquals(null, ret1);
-
- // Match two "new" cameras
- var ret2 = inst.tryMatchCamImpl(cameraInfos, Platform.WINDOWS_64);
-
- // Our cameras should be "known"
- assertTrue(inst.knownCameras.contains(info1));
- assertEquals(1, inst.knownCameras.size());
- assertEquals(1, ret2.size());
+ // And make assertions about the current matching state
+ assertEquals(1, vsm.getVsmState().allConnectedCameras.size());
+ assertEquals(0, vsm.getVsmState().disabledConfigs.size());
+ assertEquals(1, vsm.vmm.getModules().size());
}
@Test
- public void testIdenticalCameras() {
- Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
-
- // List of known cameras
- var cameraInfos = new ArrayList();
-
- var inst = new VisionSourceManager();
- ConfigManager.getInstance().clearConfig();
- ConfigManager.getInstance().load();
- ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath = false;
-
- // Match empty camera infos
- inst.tryMatchCamImpl(cameraInfos);
-
- CameraInfo info1 =
- new CameraInfo(
- 0,
- "/dev/video0",
- "Arducam OV2311 USB Camera",
- new String[] {
- "/dev/v4l/by-path/platform-fc800000.usb-usb-0:1:1.0-video-index0" // V4l doesnt assign
- // by-id paths that
- // are identical to
- // two different
- // cameras
- },
- 3141,
- 25446);
- CameraInfo info2 =
- new CameraInfo(
- 0,
- "/dev/video2",
- "Arducam OV2311 USB Camera",
- new String[] {
- "/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Arducam_OV2311_USB_Camera_UC621-video-index0",
- "/dev/v4l/by-path/platform-fc880000.usb-usb-0:1:1.0-video-index0"
- },
- 3141,
- 25446);
-
- cameraInfos.add(info1);
- cameraInfos.add(info2);
-
- // Match two "new" cameras
- var ret1 = inst.tryMatchCamImpl(cameraInfos);
-
- // Our cameras should be "known"
- assertTrue(inst.knownCameras.contains(info1));
- assertTrue(inst.knownCameras.contains(info2));
- assertEquals(2, inst.knownCameras.size());
- assertEquals(2, ret1.size());
-
- // Exactly one camera should have the path we put in
- for (int i = 0; i < cameraInfos.size(); i++) {
- var testPath = cameraInfos.get(i).getUSBPath().get();
- assertEquals(
- 1,
- ret1.stream()
- .filter(it -> testPath.equals(it.cameraConfiguration.getUSBPath().get()))
- .count());
- }
-
- // and the names should be unique
- for (int i = 0; i < ret1.size(); i++) {
- var thisName = ret1.get(i).cameraConfiguration.uniqueName;
- assertEquals(
- 1,
- ret1.stream().filter(it -> thisName.equals(it.cameraConfiguration.uniqueName)).count());
- }
+ public void testEnabledDisabled() throws InterruptedException {
+ // GIVEN a VSM
+ var vsm = new TestVsm();
+ // AND one enabled camera, and one disabled camera
+ var enabledCam =
+ new CameraConfiguration(
+ PVCameraInfo.fromUsbCameraInfo(
+ new UsbCameraInfo(
+ 0,
+ "/dev/video0",
+ "Lifecam HD-3000",
+ new String[] {"/dev/v4l/by-path/foobar1"},
+ 5940,
+ 5940)));
+ enabledCam.deactivated = false;
+ enabledCam.nickname = "Matt's awesome camera 1";
+
+ var disabledCam =
+ new CameraConfiguration(
+ PVCameraInfo.fromUsbCameraInfo(
+ new UsbCameraInfo(
+ 1,
+ "/dev/video1",
+ "Lifecam HD-3000",
+ new String[] {"/dev/v4l/by-path/foobar2"},
+ 5940,
+ 5940)));
+ enabledCam.deactivated = true;
+ enabledCam.nickname = "Matt's awesome camera 2";
+
+ vsm.testCameras = List.of(enabledCam.matchedCameraInfo, disabledCam.matchedCameraInfo);
+
+ // WHEN cameras are loaded from disk
+ vsm.registerLoadedConfigs(List.of(enabledCam, disabledCam));
+
+ // the enabled and disabled cameras will be matched
+ assertEquals(2, vsm.getVsmState().allConnectedCameras.size());
+ assertEquals(1, vsm.getVsmState().disabledConfigs.size());
+ assertEquals(1, vsm.vmm.getModules().size());
+
+ Thread.sleep(2000);
+
+ vsm.teardown();
+ }
- // duplicate cameras, same info, new ref
- var duplicateCameraInfos = new ArrayList();
- CameraInfo info1_dup =
- new CameraInfo(
- 0,
- "/dev/video0",
- "Arducam OV2311 USB Camera",
- new String[] {
- "/dev/v4l/by-path/platform-fc800000.usb-usb-0:1:1.0-video-index0" // V4l doesnt assign
- // by-id paths that
- // are identical to
- // two different
- // cameras
- },
- 3141,
- 25446);
- CameraInfo info2_dup =
- new CameraInfo(
- 0,
- "/dev/video2",
- "Arducam OV2311 USB Camera",
- new String[] {
- "/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Arducam_OV2311_USB_Camera_UC621-video-index0",
- "/dev/v4l/by-path/platform-fc880000.usb-usb-0:1:1.0-video-index0"
- },
- 3141,
- 25446);
-
- duplicateCameraInfos.add(info1_dup);
- duplicateCameraInfos.add(info2_dup);
-
- inst.tryMatchCamImpl(duplicateCameraInfos);
-
- // Our cameras should be "known", and we should only "know" two cameras still
- assertTrue(inst.knownCameras.contains(info1_dup));
- assertTrue(inst.knownCameras.contains(info2_dup));
- assertEquals(2, inst.knownCameras.size());
-
- // duplicate cameras this simulates unplugging one and plugging the other in where v4l assigns
- // the same by-id path to the other camera
- var duplicateCameraInfos1 = new ArrayList();
- CameraInfo info3_dup =
- new CameraInfo(
- 0,
- "/dev/video0",
- "Arducam OV2311 USB Camera",
- new String[] {
- "/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Arducam_OV2311_USB_Camera_UC621-video-index0",
- "/dev/v4l/by-path/platform-fc800000.usb-usb-0:1:1.0-video-index0"
- },
- 3141,
- 25446);
- CameraInfo info4_dup =
- new CameraInfo(
- 0,
- "/dev/video2",
- "Arducam OV2311 USB Camera",
- new String[] {
- "/dev/v4l/by-path/platform-fc880000.usb-usb-0:1:1.0-video-index0" // V4l doesnt assign
- // by-id paths that
- // are identical to
- // two different
- // cameras
- },
- 3141,
- 25446);
-
- duplicateCameraInfos1.add(info3_dup);
- duplicateCameraInfos1.add(info4_dup);
-
- inst.tryMatchCamImpl(duplicateCameraInfos1);
-
- // Our cameras should be "known", and we should only "know" two cameras still
- assertTrue(inst.knownCameras.contains(info3_dup));
- assertTrue(inst.knownCameras.contains(info4_dup));
- assertEquals(2, inst.knownCameras.size());
+ @Test
+ public void testDuplicate() throws InterruptedException, IOException {
+ var fileCamera1 =
+ PVCameraInfo.fromFileInfo(
+ TestUtils.getApriltagImagePath(TestUtils.ApriltagTestImages.kTag1_640_480, false)
+ .toAbsolutePath()
+ .toString(),
+ "kTag1_640_480");
+ CameraConfiguration camConf1 = new CameraConfiguration(fileCamera1);
+ camConf1.deactivated = true;
+
+ var fileCamera2 =
+ PVCameraInfo.fromFileInfo(
+ TestUtils.getApriltagImagePath(TestUtils.ApriltagTestImages.kRobots, false)
+ .toAbsolutePath()
+ .toString(),
+ "kTag1_640_480");
+ CameraConfiguration camConf2 = new CameraConfiguration(fileCamera2);
+ camConf2.nickname = camConf1.nickname + " (1)";
+ camConf2.uniqueName += "owo";
+ camConf2.deactivated = true;
+
+ var fileCamera3 =
+ PVCameraInfo.fromFileInfo(
+ TestUtils.getApriltagImagePath(TestUtils.ApriltagTestImages.kTag1_640_480, false)
+ .toAbsolutePath()
+ .toString(),
+ "kTag1_640_480");
+
+ vsm.testCameras = List.of(fileCamera1, fileCamera2, fileCamera3);
+
+ List configs = List.of(camConf1, camConf2);
+ vsm.registerLoadedConfigs(configs);
+
+ vsm.assignUnmatchedCamera(fileCamera3);
+
+ System.out.println(JacksonUtils.serializeToString(ConfigManager.getInstance().getConfig()));
+
+ // And make assertions about the current matching state
+ assertEquals(3, vsm.getVsmState().allConnectedCameras.size());
+ assertEquals(2, vsm.getVsmState().disabledConfigs.size());
+ assertEquals(1, vsm.vmm.getModules().size());
}
}
diff --git a/photon-server/src/main/java/org/photonvision/Main.java b/photon-server/src/main/java/org/photonvision/Main.java
index 5ac8d31560..ee79616814 100644
--- a/photon-server/src/main/java/org/photonvision/Main.java
+++ b/photon-server/src/main/java/org/photonvision/Main.java
@@ -19,12 +19,9 @@
import edu.wpi.first.hal.HAL;
import java.io.IOException;
-import java.nio.file.Files;
import java.nio.file.Path;
import java.util.ArrayList;
import java.util.List;
-import java.util.Objects;
-import java.util.stream.Collectors;
import org.apache.commons.cli.*;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.configuration.ConfigManager;
@@ -41,25 +38,17 @@
import org.photonvision.common.logging.PvCSCoreLogger;
import org.photonvision.common.networking.NetworkManager;
import org.photonvision.common.util.TestUtils;
-import org.photonvision.common.util.numbers.IntegerCouple;
import org.photonvision.jni.PhotonTargetingJniLoader;
import org.photonvision.jni.RknnDetectorJNI;
import org.photonvision.mrcal.MrCalJNILoader;
import org.photonvision.raspi.LibCameraJNILoader;
import org.photonvision.server.Server;
import org.photonvision.vision.apriltag.AprilTagFamily;
-import org.photonvision.vision.camera.FileVisionSource;
+import org.photonvision.vision.camera.PVCameraInfo;
import org.photonvision.vision.opencv.CVMat;
-import org.photonvision.vision.opencv.ContourGroupingMode;
-import org.photonvision.vision.opencv.ContourShape;
import org.photonvision.vision.pipeline.AprilTagPipelineSettings;
import org.photonvision.vision.pipeline.CVPipelineSettings;
-import org.photonvision.vision.pipeline.ColoredShapePipelineSettings;
import org.photonvision.vision.pipeline.PipelineProfiler;
-import org.photonvision.vision.pipeline.ReflectivePipelineSettings;
-import org.photonvision.vision.processes.VisionModule;
-import org.photonvision.vision.processes.VisionModuleManager;
-import org.photonvision.vision.processes.VisionSource;
import org.photonvision.vision.processes.VisionSourceManager;
import org.photonvision.vision.target.TargetModel;
@@ -126,11 +115,6 @@ private static boolean handleArgs(String[] args) throws ParseException {
}
}
- if (cmd.hasOption("ignore-cameras")) {
- VisionSourceManager.getInstance()
- .setIgnoredCamerasRegex(cmd.getOptionValue("ignore-cameras"));
- }
-
if (cmd.hasOption("disable-networking")) {
NetworkManager.getInstance().networkingIsDisabled = true;
}
@@ -146,156 +130,27 @@ private static boolean handleArgs(String[] args) throws ParseException {
return true;
}
- private static void addTestModeFromFolder() {
- ConfigManager.getInstance().load();
-
- try {
- List collectedSources =
- Files.list(testModeFolder)
- .filter(p -> p.toFile().isFile())
- .map(
- p -> {
- try {
- CameraConfiguration camConf =
- new CameraConfiguration(
- p.getFileName().toString(), p.toAbsolutePath().toString());
- camConf.FOV = TestUtils.WPI2019Image.FOV; // Good guess?
- camConf.addCalibration(TestUtils.get2020LifeCamCoeffs(false));
-
- var pipeSettings = new AprilTagPipelineSettings();
- pipeSettings.pipelineNickname = p.getFileName().toString();
- pipeSettings.outputShowMultipleTargets = true;
- pipeSettings.inputShouldShow = true;
- pipeSettings.outputShouldShow = false;
- pipeSettings.solvePNPEnabled = true;
-
- var aprilTag = new AprilTagPipelineSettings();
- var psList = new ArrayList();
- psList.add(aprilTag);
- camConf.pipelineSettings = psList;
-
- return new FileVisionSource(camConf);
- } catch (Exception e) {
- logger.error("Couldn't load image " + p.getFileName().toString(), e);
- return null;
- }
- })
- .filter(Objects::nonNull)
- .collect(Collectors.toList());
-
- ConfigManager.getInstance().unloadCameraConfigs();
- VisionModuleManager.getInstance().addSources(collectedSources).forEach(VisionModule::start);
- ConfigManager.getInstance().addCameraConfigurations(collectedSources);
- } catch (IOException e) {
- logger.error("Path does not exist!");
- System.exit(1);
- }
- }
-
private static void addTestModeSources() {
ConfigManager.getInstance().load();
- var camConf2019 =
- ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2019");
- if (camConf2019 == null) {
- camConf2019 =
- new CameraConfiguration("WPI2019", TestUtils.getTestMode2019ImagePath().toString());
- camConf2019.FOV = TestUtils.WPI2019Image.FOV;
- camConf2019.calibrations.add(TestUtils.get2019LifeCamCoeffs(true));
-
- var pipeline2019 = new ReflectivePipelineSettings();
- pipeline2019.pipelineNickname = "CargoShip";
- pipeline2019.targetModel = TargetModel.k2019DualTarget;
- pipeline2019.outputShowMultipleTargets = true;
- pipeline2019.contourGroupingMode = ContourGroupingMode.Dual;
- pipeline2019.inputShouldShow = true;
-
- var psList2019 = new ArrayList();
- psList2019.add(pipeline2019);
- camConf2019.pipelineSettings = psList2019;
- }
-
- var camConf2020 =
- ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2020");
- if (camConf2020 == null) {
- camConf2020 =
- new CameraConfiguration("WPI2020", TestUtils.getTestMode2020ImagePath().toString());
- camConf2020.FOV = TestUtils.WPI2020Image.FOV;
- camConf2020.calibrations.add(TestUtils.get2019LifeCamCoeffs(true));
-
- var pipeline2020 = new ReflectivePipelineSettings();
- pipeline2020.pipelineNickname = "OuterPort";
- pipeline2020.targetModel = TargetModel.k2020HighGoalOuter;
- camConf2020.calibrations.add(TestUtils.get2020LifeCamCoeffs(true));
- pipeline2020.inputShouldShow = true;
-
- var psList2020 = new ArrayList();
- psList2020.add(pipeline2020);
- camConf2020.pipelineSettings = psList2020;
- }
-
- var camConf2022 =
- ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2022");
- if (camConf2022 == null) {
- camConf2022 =
- new CameraConfiguration("WPI2022", TestUtils.getTestMode2022ImagePath().toString());
- camConf2022.FOV = TestUtils.WPI2022Image.FOV;
- camConf2022.calibrations.add(TestUtils.get2019LifeCamCoeffs(true));
-
- var pipeline2022 = new ReflectivePipelineSettings();
- pipeline2022.pipelineNickname = "OuterPort";
- pipeline2022.targetModel = TargetModel.k2020HighGoalOuter;
- pipeline2022.inputShouldShow = true;
- // camConf2020.calibrations.add(TestUtils.get2020LifeCamCoeffs(true));
-
- var psList2022 = new ArrayList();
- psList2022.add(pipeline2022);
- camConf2022.pipelineSettings = psList2022;
- }
-
- CameraConfiguration camConf2023 =
- ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2023");
- if (camConf2023 == null) {
- camConf2023 =
- new CameraConfiguration(
- "WPI2023",
- TestUtils.getResourcesFolderPath(true)
- .resolve("testimages")
- .resolve(TestUtils.WPI2023Apriltags.k383_60_Angle2.path)
- .toString());
-
- camConf2023.FOV = TestUtils.WPI2023Apriltags.FOV;
- camConf2023.calibrations.add(TestUtils.get2023LifeCamCoeffs(true));
-
- var pipeline2023 = new AprilTagPipelineSettings();
- var path_split = Path.of(camConf2023.path).getFileName().toString();
- pipeline2023.pipelineNickname = path_split.replace(".png", "");
- pipeline2023.targetModel = TargetModel.kAprilTag6in_16h5;
- pipeline2023.inputShouldShow = true;
- pipeline2023.solvePNPEnabled = true;
-
- var psList2023 = new ArrayList();
- psList2023.add(pipeline2023);
- camConf2023.pipelineSettings = psList2023;
- }
-
CameraConfiguration camConf2024 =
ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2024");
- if (camConf2024 == null) {
+ if (camConf2024 == null || true) {
camConf2024 =
new CameraConfiguration(
- "WPI2024",
- TestUtils.getResourcesFolderPath(true)
- .resolve("testimages")
- .resolve(TestUtils.WPI2024Images.kSpeakerCenter_143in.path)
- .toString());
+ 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.path).getFileName().toString();
+ 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;
@@ -307,47 +162,11 @@ private static void addTestModeSources() {
camConf2024.pipelineSettings = psList2024;
}
- // Colored shape testing
- var camConfShape =
- ConfigManager.getInstance().getConfig().getCameraConfigurations().get("Shape");
-
- // If we haven't saved shape settings, create a new one
- if (camConfShape == null) {
- camConfShape =
- new CameraConfiguration(
- "Shape",
- TestUtils.getPowercellImagePath(TestUtils.PowercellTestImages.kPowercell_test_1, true)
- .toString());
- var settings = new ColoredShapePipelineSettings();
- settings.hsvHue = new IntegerCouple(0, 35);
- settings.hsvSaturation = new IntegerCouple(82, 255);
- settings.hsvValue = new IntegerCouple(62, 255);
- settings.contourShape = ContourShape.Triangle;
- settings.outputShowMultipleTargets = true;
- settings.circleAccuracy = 15;
- settings.inputShouldShow = true;
- camConfShape.addPipelineSetting(settings);
- }
-
- var collectedSources = new ArrayList();
-
- var fvsShape = new FileVisionSource(camConfShape);
- var fvs2019 = new FileVisionSource(camConf2019);
- var fvs2020 = new FileVisionSource(camConf2020);
- var fvs2022 = new FileVisionSource(camConf2022);
- var fvs2023 = new FileVisionSource(camConf2023);
- var fvs2024 = new FileVisionSource(camConf2024);
-
- collectedSources.add(fvs2024);
- // collectedSources.add(fvs2023);
- // collectedSources.add(fvs2022);
- // collectedSources.add(fvsShape);
- // collectedSources.add(fvs2020);
- // collectedSources.add(fvs2019);
+ var cameraConfigs = List.of(camConf2024);
ConfigManager.getInstance().unloadCameraConfigs();
- VisionModuleManager.getInstance().addSources(collectedSources).forEach(VisionModule::start);
- ConfigManager.getInstance().addCameraConfigurations(collectedSources);
+ cameraConfigs.stream().forEach(ConfigManager.getInstance()::addCameraConfiguration);
+ VisionSourceManager.getInstance().registerLoadedConfigs(cameraConfigs);
}
public static void main(String[] args) {
@@ -475,21 +294,21 @@ public static void main(String[] args) {
System.exit(0);
}
+ // todo - should test mode just add test mode sources, but still allow local usb cameras to be
+ // added?
if (!isTestMode) {
logger.debug("Loading VisionSourceManager...");
VisionSourceManager.getInstance()
.registerLoadedConfigs(
ConfigManager.getInstance().getConfig().getCameraConfigurations().values());
-
- VisionSourceManager.getInstance().registerTimedTask();
} else {
if (testModeFolder == null) {
addTestModeSources();
- } else {
- addTestModeFromFolder();
}
}
+ VisionSourceManager.getInstance().registerTimedTasks();
+
logger.info("Starting server...");
HardwareManager.getInstance().setRunning(true);
Server.initialize(DEFAULT_WEBPORT);
diff --git a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java
index 713d22435e..16a5a06892 100644
--- a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java
+++ b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java
@@ -52,7 +52,8 @@
import org.photonvision.common.util.file.ProgramDirectoryUtilities;
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
import org.photonvision.vision.camera.CameraQuirk;
-import org.photonvision.vision.processes.VisionModuleManager;
+import org.photonvision.vision.camera.PVCameraInfo;
+import org.photonvision.vision.processes.VisionSourceManager;
import org.zeroturnaround.zip.ZipUtil;
public class RequestHandler {
@@ -395,7 +396,7 @@ public static void onCameraSettingsRequest(Context ctx) {
logger.info("Changing camera FOV to: " + fov);
logger.info("Changing quirks to: " + settings.quirksToChange.toString());
- var module = VisionModuleManager.getInstance().getModule(index);
+ var module = VisionSourceManager.getInstance().vmm.getModule(index);
module.setFov(fov);
module.changeCameraQuirks(settings.quirksToChange);
@@ -474,7 +475,7 @@ public static void onCalibrationEndRequest(Context ctx) {
try {
index = kObjectMapper.readTree(ctx.bodyInputStream()).get("index").asInt();
- var calData = VisionModuleManager.getInstance().getModule(index).endCalibration();
+ var calData = VisionSourceManager.getInstance().vmm.getModule(index).endCalibration();
if (calData == null) {
ctx.result("The calibration process failed");
ctx.status(500);
@@ -551,7 +552,7 @@ public static void onCameraNicknameChangeRequest(Context ctx) {
String name = data.get("name").asText();
int idx = data.get("cameraIndex").asInt();
- VisionModuleManager.getInstance().getModule(idx).setCameraNickname(name);
+ VisionSourceManager.getInstance().vmm.getModule(idx).setCameraNickname(name);
ctx.status(200);
ctx.result("Successfully changed the camera name to: " + name);
logger.info("Successfully changed the camera name to: " + name);
@@ -581,7 +582,8 @@ public static void onCalibrationSnapshotRequest(Context ctx) {
var observationIdx = Integer.parseInt(ctx.queryParam("snapshotIdx"));
CameraCalibrationCoefficients calList =
- VisionModuleManager.getInstance()
+ VisionSourceManager.getInstance()
+ .vmm
.getModule(idx)
.getStateAsCameraConfig()
.calibrations
@@ -631,7 +633,7 @@ public static void onCalibrationExportRequest(Context ctx) {
var width = Integer.parseInt(ctx.queryParam("width"));
var height = Integer.parseInt(ctx.queryParam("height"));
- var cc = VisionModuleManager.getInstance().getModule(idx).getStateAsCameraConfig();
+ var cc = VisionSourceManager.getInstance().vmm.getModule(idx).getStateAsCameraConfig();
CameraCalibrationCoefficients calList =
cc.calibrations.stream()
@@ -818,19 +820,63 @@ public static void onNukeOneCamera(Context ctx) {
FileUtils.deleteDirectory(cameraDir);
}
- // prevent -anyone- else from writing camera configs -- but flush first
- ConfigManager.getInstance().saveToDisk();
- ConfigManager.getInstance().setWriteTaskEnabled(false);
- ConfigManager.getInstance().disableFlushOnShutdown();
- // remove the config from the global config and force-flush
- ConfigManager.getInstance().getConfig().removeCameraConfig(name);
- ConfigManager.getInstance().saveToDisk();
+ VisionSourceManager.getInstance().deleteVisionSource(name);
+
ctx.status(200);
- restartProgram();
} catch (IOException e) {
// todo
logger.error("asdf", e);
ctx.status(500);
}
}
+
+ public static void onActivateMatchedCameraRequest(Context ctx) {
+ logger.info(ctx.queryString().toString());
+
+ String uniqueName = ctx.queryParam("uniqueName");
+
+ if (VisionSourceManager.getInstance().reactivateDisabledCameraConfig(uniqueName)) {
+ ctx.status(200);
+ } else {
+ ctx.status(403);
+ }
+
+ ctx.result("Successfully assigned camera with unique name: " + uniqueName);
+ }
+
+ public static void onAssignUnmatchedCameraRequest(Context ctx) {
+ logger.info(ctx.queryString().toString());
+
+ PVCameraInfo camera;
+ try {
+ camera = JacksonUtils.deserialize(ctx.queryParam("cameraInfo"), PVCameraInfo.class);
+ } catch (IOException e) {
+ ctx.status(401);
+ return;
+ }
+
+ if (VisionSourceManager.getInstance().assignUnmatchedCamera(camera)) {
+ ctx.status(200);
+ } else {
+ ctx.status(403);
+ }
+
+ ctx.result("Successfully assigned camera: " + camera);
+ }
+
+ public static void onUnassignCameraRequest(Context ctx) {
+ logger.info(ctx.queryString().toString());
+
+ String uniqueName = ctx.queryParam("uniqueName");
+
+ if (VisionSourceManager.getInstance().deactivateVisionSource(uniqueName)) {
+ ctx.status(200);
+ } else {
+ ctx.status(403);
+ }
+
+ ctx.status(200);
+
+ ctx.result("Successfully assigned camera with unique name: " + uniqueName);
+ }
}
diff --git a/photon-server/src/main/java/org/photonvision/server/Server.java b/photon-server/src/main/java/org/photonvision/server/Server.java
index 701794d0c6..67ccd2d756 100644
--- a/photon-server/src/main/java/org/photonvision/server/Server.java
+++ b/photon-server/src/main/java/org/photonvision/server/Server.java
@@ -136,6 +136,9 @@ private static void start(int port) {
app.get("/api/utils/getCalibrationJSON", RequestHandler::onCalibrationExportRequest);
app.post("/api/utils/nukeConfigDirectory", RequestHandler::onNukeConfigDirectory);
app.post("/api/utils/nukeOneCamera", RequestHandler::onNukeOneCamera);
+ app.post("/api/utils/activateMatchedCamera", RequestHandler::onActivateMatchedCameraRequest);
+ app.post("/api/utils/assignUnmatchedCamera", RequestHandler::onAssignUnmatchedCameraRequest);
+ app.post("/api/utils/unassignCamera", RequestHandler::onUnassignCameraRequest);
// Calibration
app.post("/api/calibration/end", RequestHandler::onCalibrationEndRequest);