Compare commits

...

2 Commits

Author SHA1 Message Date
Matt
428f926ac2 Actually properly match cameras by name fr this time (#1237)
Our current code matches cameras in this order (which I think is objectively wrong and stupid)

- by-id (/dev/v4l/by-id/product-string)
- by path (/dev/videoN)
- product string/name, but ascii only
- asks cscore to reconnect to cameras using `path`, which on linux is actually /dev/videoN. This isn't guaranteed to stick to a camera if you replug them weirdly at runtime.

This is silly and does not consider the actual physical usb port. I propose instead, in this order:

- By physical usb port path and base name
- by physical usb port path and USB VID/PID
- By base name only (with a toggle switch to disable this, and create a new VisionModule instead)
- Give cscore /dev/video/by-path on Linux systems, pinning Photon USBCameras to a particular usb port once created.

This changes lots of things so stay paranoid!
2024-02-16 16:05:47 -05:00
Matt
4efeb3d412 Load libwinpthread-1.dll before libgcc_s_seh-1 (#1228) 2024-02-16 16:05:16 -05:00
13 changed files with 314 additions and 121 deletions

View File

@@ -59,7 +59,8 @@ const settingsHaveChanged = (): boolean => {
a.shouldPublishProto !== b.shouldPublishProto ||
a.networkManagerIface !== b.networkManagerIface ||
a.setStaticCommand !== b.setStaticCommand ||
a.setDHCPcommand !== b.setDHCPcommand
a.setDHCPcommand !== b.setDHCPcommand ||
a.matchCamerasOnlyByPath !== b.matchCamerasOnlyByPath
);
};
@@ -77,6 +78,7 @@ const saveGeneralSettings = () => {
setStaticCommand: tempSettingsStruct.value.setStaticCommand || "",
shouldManage: tempSettingsStruct.value.shouldManage,
shouldPublishProto: tempSettingsStruct.value.shouldPublishProto,
matchCamerasOnlyByPath: tempSettingsStruct.value.matchCamerasOnlyByPath,
staticIp: tempSettingsStruct.value.staticIp
};
@@ -137,6 +139,8 @@ watchEffect(() => {
<template>
<v-card dark class="mb-3 pr-6 pb-3" style="background-color: #006492">
<v-card-title>Global Settings</v-card-title>
<v-divider />
<v-card-title>Networking</v-card-title>
<div class="ml-5">
<v-form ref="form" v-model="settingsValid">
@@ -254,6 +258,9 @@ watchEffect(() => {
>
This mode is intended for debugging; it should be off for proper usage. PhotonLib will NOT work!
</v-banner>
<v-divider />
<v-card-title>Miscellaneous</v-card-title>
<pv-switch
v-model="tempSettingsStruct.shouldPublishProto"
label="Also Publish Protobuf"
@@ -272,6 +279,14 @@ watchEffect(() => {
This mode is intended for debugging; it should be off for field use. You may notice a performance hit by using
this mode.
</v-banner>
<pv-switch
v-model="tempSettingsStruct.matchCamerasOnlyByPath"
label="Match cameras by-path ONLY"
tooltip="ONLY match cameras by the USB port they're plugged into + (basename or USB VID/PID), and never only by the device product string"
class="mt-3 mb-2"
:label-cols="4"
/>
<v-divider class="mb-3" />
</v-form>
<v-btn
color="accent"

View File

@@ -44,7 +44,9 @@ export const useSettingsStore = defineStore("settings", {
connName: "Example Wired Connection",
devName: "eth0"
}
]
],
networkingDisabled: false,
matchCamerasOnlyByPath: false
},
lighting: {
supported: true,

View File

@@ -47,6 +47,7 @@ export interface NetworkSettings {
setDHCPcommand?: string;
networkInterfaceNames: NetworkInterfaceType[];
networkingDisabled: boolean;
matchCamerasOnlyByPath: boolean;
}
export type ConfigurableNetworkSettings = Omit<

View File

@@ -23,6 +23,7 @@ import com.fasterxml.jackson.annotation.JsonProperty;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.List;
import java.util.Optional;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
@@ -51,6 +52,12 @@ public class CameraConfiguration {
@JsonIgnore public String[] otherPaths = {};
@JsonProperty("usbVID")
public int usbVID = -1;
@JsonProperty("usbPID")
public int usbPID = -1;
public CameraType cameraType = CameraType.UsbCamera;
public double FOV = 70;
public final List<CameraCalibrationCoefficients> calibrations;
@@ -98,7 +105,9 @@ public class CameraConfiguration {
@JsonProperty("cameraType") CameraType cameraType,
@JsonProperty("cameraQuirks") QuirkyCamera cameraQuirks,
@JsonProperty("calibration") List<CameraCalibrationCoefficients> calibrations,
@JsonProperty("currentPipelineIndex") int currentPipelineIndex) {
@JsonProperty("currentPipelineIndex") int currentPipelineIndex,
@JsonProperty("usbVID") int usbVID,
@JsonProperty("usbPID") int usbPID) {
this.baseName = baseName;
this.uniqueName = uniqueName;
this.nickname = nickname;
@@ -108,6 +117,8 @@ public class CameraConfiguration {
this.cameraQuirks = cameraQuirks;
this.calibrations = calibrations != null ? calibrations : new ArrayList<>();
this.currentPipelineIndex = currentPipelineIndex;
this.usbPID = usbPID;
this.usbVID = usbVID;
logger.debug(
"Creating camera configuration for "
@@ -156,6 +167,17 @@ public class CameraConfiguration {
calibrations.add(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"
*
* @return
*/
@JsonIgnore
public Optional<String> getUSBPath() {
return Arrays.stream(otherPaths).filter(path -> path.contains("/by-path/")).findFirst();
}
@Override
public String toString() {
return "CameraConfiguration [baseName="

View File

@@ -20,6 +20,24 @@ package org.photonvision.common.configuration;
public class HardwareSettings {
public int ledBrightnessPercentage = 100;
@Override
public int hashCode() {
final int prime = 31;
int result = 1;
result = prime * result + ledBrightnessPercentage;
return result;
}
@Override
public boolean equals(Object obj) {
if (this == obj) return true;
if (obj == null) return false;
if (getClass() != obj.getClass()) return false;
HardwareSettings other = (HardwareSettings) obj;
if (ledBrightnessPercentage != other.ledBrightnessPercentage) return false;
return true;
}
@Override
public String toString() {
return "HardwareSettings [ledBrightnessPercentage=" + ledBrightnessPercentage + "]";

View File

@@ -39,6 +39,12 @@ 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
*/
public boolean matchCamerasOnlyByPath = false;
@JsonIgnore public static final String NM_IFACE_STRING = "${interface}";
@JsonIgnore public static final String NM_IP_STRING = "${ipaddr}";
@@ -76,7 +82,8 @@ public class NetworkConfig {
@JsonProperty("shouldPublishProto") boolean shouldPublishProto,
@JsonProperty("networkManagerIface") String networkManagerIface,
@JsonProperty("setStaticCommand") String setStaticCommand,
@JsonProperty("setDHCPcommand") String setDHCPcommand) {
@JsonProperty("setDHCPcommand") String setDHCPcommand,
@JsonProperty("matchCamerasOnlyByPath") boolean matchCamerasOnlyByPath) {
this.ntServerAddress = ntServerAddress;
this.connectionType = connectionType;
this.staticIp = staticIp;
@@ -86,6 +93,7 @@ public class NetworkConfig {
this.networkManagerIface = networkManagerIface;
this.setStaticCommand = setStaticCommand;
this.setDHCPcommand = setDHCPcommand;
this.matchCamerasOnlyByPath = matchCamerasOnlyByPath;
setShouldManage(shouldManage);
}

View File

@@ -53,6 +53,7 @@ public class MrCalJNILoader extends PhotonJNICommon {
"libcolamd",
"libccolamd",
"openblas",
"libwinpthread-1",
"libgcc_s_seh-1",
"libquadmath-0",
"libgfortran-5",

View File

@@ -19,6 +19,7 @@ package org.photonvision.vision.camera;
import edu.wpi.first.cscore.UsbCameraInfo;
import java.util.Arrays;
import java.util.Optional;
public class CameraInfo extends UsbCameraInfo {
public final CameraType cameraType;
@@ -68,6 +69,16 @@ public class CameraInfo extends UsbCameraInfo {
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<String> getUSBPath() {
return Arrays.stream(otherPaths).filter(path -> path.contains("/by-path/")).findFirst();
}
@Override
public boolean equals(Object o) {
if (o == this) return true;
@@ -79,4 +90,19 @@ public class CameraInfo extends UsbCameraInfo {
&& productId == other.productId
&& vendorId == other.vendorId;
}
@Override
public String toString() {
return "CameraInfo [cameraType="
+ cameraType
+ "baseName="
+ getBaseName()
+ ", vid="
+ vendorId
+ ", pid="
+ productId
+ ", otherPaths="
+ Arrays.toString(otherPaths)
+ "]";
}
}

View File

@@ -49,9 +49,17 @@ public class USBCameraSource extends VisionSource {
super(config);
logger = new Logger(USBCameraSource.class, config.nickname, LogGroup.Camera);
camera = new UsbCamera(config.nickname, config.path);
// 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 (getCameraConfiguration().cameraQuirks == null)
getCameraConfiguration().cameraQuirks =
QuirkyCamera.getQuirkyCamera(

View File

@@ -23,6 +23,7 @@ import java.util.Arrays;
import java.util.Collection;
import java.util.List;
import java.util.concurrent.CopyOnWriteArrayList;
import java.util.function.Predicate;
import java.util.stream.Collectors;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.configuration.ConfigManager;
@@ -164,7 +165,7 @@ public class VisionSourceManager {
// Debug prints
for (var info : connectedCameras) {
logger.info("Adding local video device - \"" + info.name + "\" at \"" + info.path + "\"");
logger.info("Detected unmatched physical camera: " + info.toString());
}
if (!unmatchedLoadedConfigs.isEmpty())
@@ -216,6 +217,52 @@ public class VisionSourceManager {
return sources;
}
/**
* 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<CameraInfo> 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: "
+ camCfgToString(savedConfig));
}
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));
}
return matches;
};
}
/**
* Create {@link CameraConfiguration}s based on a list of detected USB cameras and the configs on
* disk.
@@ -226,35 +273,111 @@ public class VisionSourceManager {
*/
public List<CameraConfiguration> matchCameras(
List<CameraInfo> detectedCamInfos, List<CameraConfiguration> loadedCamConfigs) {
return matchCameras(
detectedCamInfos,
loadedCamConfigs,
ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath);
}
private static final String camCfgToString(CameraConfiguration c) {
return new StringBuilder()
.append("[baseName=")
.append(c.baseName)
.append(", uniqueName=")
.append(c.uniqueName)
.append(", otherPaths=")
.append(Arrays.toString(c.otherPaths))
.append(", vid=")
.append(c.usbVID)
.append(", pid=")
.append(c.usbPID)
.append("]")
.toString();
}
/**
* 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<CameraConfiguration> matchCameras(
List<CameraInfo> detectedCamInfos,
List<CameraConfiguration> loadedCamConfigs,
boolean matchCamerasOnlyByPath) {
var detectedCameraList = new ArrayList<>(detectedCamInfos);
ArrayList<CameraConfiguration> cameraConfigurations = new ArrayList<CameraConfiguration>();
ArrayList<CameraConfiguration> unloadedConfigs =
new ArrayList<CameraConfiguration>(loadedCamConfigs);
if (detectedCameraList.size() > 0 || unloadedConfigs.size() > 0)
cameraConfigurations.addAll(matchByPathByID(detectedCameraList, unloadedConfigs));
else logger.debug("Skipping matchByPath no configs or cameras left to match");
if (detectedCameraList.size() > 0 || unloadedConfigs.size() > 0) {
logger.info("Matching by usb port & name & USB VID/PID...");
cameraConfigurations.addAll(
matchCamerasByStrategy(detectedCameraList, unloadedConfigs, true, true, true, false));
} else
logger.debug("Skipping match by usb port/name/vid/pid, no configs or cameras left to match");
if (detectedCameraList.size() > 0 || unloadedConfigs.size() > 0)
cameraConfigurations.addAll(matchByPath(detectedCameraList, unloadedConfigs));
else logger.debug("Skipping matchByPath no configs or cameras left to match");
// 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()) {
if (detectedCameraList.size() > 0 || unloadedConfigs.size() > 0) {
logger.info("Matching by windows-path & USB VID/PID only...");
cameraConfigurations.addAll(
matchCamerasByStrategy(detectedCameraList, unloadedConfigs, false, true, true, true));
} else
logger.debug(
"Skipping matching by windiws-path/name/vid/pid, no configs or cameras left to match");
}
if (detectedCameraList.size() > 0 || unloadedConfigs.size() > 0)
cameraConfigurations.addAll(matchByName(detectedCameraList, unloadedConfigs));
else logger.debug("Skipping matchByName no configs or cameras left to match");
if (detectedCameraList.size() > 0 || unloadedConfigs.size() > 0) {
logger.info("Matching by usb port & USB VID/PID...");
cameraConfigurations.addAll(
matchCamerasByStrategy(detectedCameraList, unloadedConfigs, true, true, false, false));
} else logger.debug("Skipping match by port/vid/pid, no configs or cameras left to match");
if (detectedCameraList.size() > 0)
// handle disabling only-by-base-name matching
if (!matchCamerasOnlyByPath) {
if (detectedCameraList.size() > 0 || unloadedConfigs.size() > 0) {
logger.info("Matching by base-name & USB VID/PID only...");
cameraConfigurations.addAll(
matchCamerasByStrategy(detectedCameraList, unloadedConfigs, false, true, true, false));
} else
logger.debug("Skipping match by base-name/viid/pid, no configs or cameras left to match");
} else logger.info("Skipping match by filepath/vid/pid, disabled by user");
if (detectedCameraList.size() > 0) {
cameraConfigurations.addAll(
createConfigsForCameras(detectedCameraList, unloadedConfigs, cameraConfigurations));
}
logger.debug("Matched or created " + cameraConfigurations.size() + " camera configs!");
return cameraConfigurations;
}
// loop over all the configs loaded from disk, attempting to match each camera
// to a config by path-by-id on linux
private List<CameraConfiguration> matchByPathByID(
List<CameraInfo> detectedCamInfos, List<CameraConfiguration> unloadedConfigs) {
/**
* 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<CameraConfiguration> matchCamerasByStrategy(
List<CameraInfo> detectedCamInfos,
List<CameraConfiguration> unloadedConfigs,
boolean checkUSBPath,
boolean checkVidPid,
boolean checkBaseName,
boolean checkPath) {
List<CameraConfiguration> ret = new ArrayList<CameraConfiguration>();
List<CameraConfiguration> unloadedConfigsCopy =
new ArrayList<CameraConfiguration>(unloadedConfigs);
@@ -262,111 +385,43 @@ public class VisionSourceManager {
for (CameraConfiguration config : unloadedConfigsCopy) {
// Only run match path by id if the camera is not a CSI camera.
if (config.cameraType != CameraType.ZeroCopyPicam) {
CameraInfo cameraInfo;
if (config.otherPaths.length == 0) {
logger.debug("No valid path-by-id found for config with name " + config.baseName);
} else {
// attempt matching by path and basename
logger.debug(
"Trying to find a match for loaded camera "
+ config.baseName
+ " with path-by-id "
+ config.otherPaths[0]);
cameraInfo =
detectedCamInfos.stream()
.filter(
usbCameraInfo ->
usbCameraInfo.otherPaths.length != 0
&& usbCameraInfo.otherPaths[0].equals(config.otherPaths[0])
&& usbCameraInfo.getBaseName().equals(config.baseName))
.findFirst()
.orElse(null);
logger.debug(
String.format(
"Trying to find a match for loaded camera %s by strategy (path %s vid/pid %s basename %s path %s) with camera config: %s",
config.baseName,
checkUSBPath,
checkVidPid,
checkBaseName,
checkPath,
camCfgToString(config)));
// 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.baseName + " to a physical camera!");
ret.add(mergeInfoIntoConfig(config, cameraInfo));
detectedCamInfos.remove(cameraInfo);
unloadedConfigs.remove(config);
}
// Get matcher and filter against it, picking out the first match
Predicate<CameraInfo> matches =
getCameraMatcher(config, checkUSBPath, checkVidPid, checkBaseName, 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.baseName + " to a physical camera!");
ret.add(mergeInfoIntoConfig(config, cameraInfo));
detectedCamInfos.remove(cameraInfo);
unloadedConfigs.remove(config);
} else {
logger.debug("No camera found for the config " + config.baseName);
}
}
}
return ret;
}
private List<CameraConfiguration> matchByPath(
List<CameraInfo> detectedCamInfos, List<CameraConfiguration> unloadedConfigs) {
List<CameraConfiguration> ret = new ArrayList<CameraConfiguration>();
List<CameraConfiguration> unloadedConfigsCopy =
new ArrayList<CameraConfiguration>(unloadedConfigs);
// now attempt to match the cameras and configs remaining by normal path
for (CameraConfiguration config : unloadedConfigsCopy) {
CameraInfo cameraInfo;
// attempt matching by path and basename
logger.debug(
"Trying to find a match for loaded camera "
+ config.baseName
+ " with path "
+ config.path);
cameraInfo =
detectedCamInfos.stream()
.filter(
usbCameraInfo ->
usbCameraInfo.path.equals(config.path)
&& usbCameraInfo.getBaseName().equals(config.baseName))
.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.baseName + " to a physical camera!");
ret.add(mergeInfoIntoConfig(config, cameraInfo));
detectedCamInfos.remove(cameraInfo);
unloadedConfigs.remove(config);
}
}
return ret;
}
// Try matching cameras to configs by name.
private List<CameraConfiguration> matchByName(
List<CameraInfo> detectedCamInfos, List<CameraConfiguration> unloadedConfigs) {
List<CameraConfiguration> ret = new ArrayList<CameraConfiguration>();
List<CameraConfiguration> unloadedConfigsCopy =
new ArrayList<CameraConfiguration>(unloadedConfigs);
// if both path and ID based matching fails, attempt basename only match
for (CameraConfiguration config : unloadedConfigsCopy) {
CameraInfo cameraInfo;
logger.debug("Trying to find a match for loaded camera with name " + config.baseName);
cameraInfo =
detectedCamInfos.stream()
.filter(CameraInfo -> CameraInfo.getBaseName().equals(config.baseName))
.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.baseName + " to a physical camera!");
ret.add(mergeInfoIntoConfig(config, cameraInfo));
detectedCamInfos.remove(cameraInfo);
unloadedConfigs.remove(config);
}
}
return ret;
}
// If we have any unmatched cameras left, create a new CameraConfiguration for
// them here.
/**
* 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<CameraConfiguration> createConfigsForCameras(
List<CameraInfo> detectedCameraList,
List<CameraConfiguration> loadedCamConfigs,
List<CameraConfiguration> unloadedCamConfigs,
List<CameraConfiguration> loadedConfigs) {
List<CameraConfiguration> ret = new ArrayList<CameraConfiguration>();
logger.debug(
@@ -377,7 +432,9 @@ public class VisionSourceManager {
String uniqueName = info.getHumanReadableName();
int suffix = 0;
while (containsName(loadedConfigs, uniqueName) || containsName(uniqueName)) {
while (containsName(loadedConfigs, uniqueName)
|| containsName(uniqueName)
|| containsName(unloadedCamConfigs, uniqueName)) {
suffix++;
uniqueName = String.format("%s (%d)", uniqueName, suffix);
}
@@ -460,7 +517,7 @@ public class VisionSourceManager {
List<CameraConfiguration> camConfigs) {
var cameraSources = new ArrayList<VisionSource>();
for (var configuration : camConfigs) {
logger.debug("Creating VisionSource for " + configuration);
logger.debug("Creating VisionSource for " + camCfgToString(configuration));
boolean is_pi = Platform.isRaspberryPi();

View File

@@ -139,8 +139,31 @@ public class ConfigTest {
writer.write(str);
writer.flush();
writer.close();
Assertions.assertDoesNotThrow(
() -> JacksonUtils.deserialize(tempFile.toPath(), CameraConfiguration.class));
CameraConfiguration result =
JacksonUtils.deserialize(tempFile.toPath(), CameraConfiguration.class);
tempFile.delete();
}
@Test
public void testJacksonAddUSBVIDPID() throws IOException {
var str =
"{\"baseName\":\"aaaaaa\",\"uniqueName\":\"aaaaaa\",\"nickname\":\"aaaaaa\",\"FOV\":70.0,\"path\":\"dev/vid\",\"cameraType\":\"UsbCamera\",\"currentPipelineIndex\":0,\"camPitch\":{\"radians\":0.0},\"calibrations\":[], \"usbVID\":3, \"usbPID\":4, \"cameraLEDs\":[]}";
File tempFile = File.createTempFile("test", ".json");
tempFile.deleteOnExit();
var writer = new FileWriter(tempFile);
writer.write(str);
writer.flush();
writer.close();
try {
CameraConfiguration result =
JacksonUtils.deserialize(tempFile.toPath(), CameraConfiguration.class);
String ser = JacksonUtils.serializeToString(result);
System.out.println(ser);
} catch (Exception e) {
e.printStackTrace();
}
tempFile.delete();
}

View File

@@ -84,7 +84,9 @@ public class SQLConfigTest {
CameraType.UsbCamera,
QuirkyCamera.getQuirkyCamera(-1, -1),
List.of(),
0);
0,
-1,
-1);
testcamcfg.pipelineSettings =
List.of(
new ReflectivePipelineSettings(),

View File

@@ -24,14 +24,20 @@ import java.util.ArrayList;
import org.junit.jupiter.api.Test;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.configuration.ConfigManager;
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;
public class VisionSourceManagerTest {
@Test
public void visionSourceTest() {
Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
var inst = new VisionSourceManager();
var cameraInfos = new ArrayList<CameraInfo>();
ConfigManager.getInstance().clearConfig();
ConfigManager.getInstance().load();
inst.tryMatchCamImpl(cameraInfos);
@@ -43,6 +49,8 @@ public class VisionSourceManagerTest {
"thirdTestVideo",
"dev/video1",
new String[] {"by-id/123"});
config3.usbVID = 3;
config3.usbPID = 4;
var config4 =
new CameraConfiguration(
"fourthTestVideo",
@@ -50,6 +58,8 @@ public class VisionSourceManagerTest {
"fourthTestVideo",
"dev/video2",
new String[] {"by-id/321"});
config4.usbVID = 5;
config4.usbPID = 6;
CameraInfo info1 = new CameraInfo(0, "dev/video0", "testVideo", new String[0], 1, 2);