Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Another config matching bug #1518

Merged
merged 4 commits into from
Nov 5, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -84,15 +84,7 @@ public CameraConfiguration(
this.calibrations = new ArrayList<>();
this.otherPaths = alternates;

logger.debug(
"Creating USB camera configuration for "
+ cameraType
+ " "
+ baseName
+ " (AKA "
+ nickname
+ ") at "
+ path);
logger.debug("Creating USB camera configuration for " + this.toShortString());
}

@JsonCreator
Expand Down Expand Up @@ -120,15 +112,7 @@ public CameraConfiguration(
this.usbPID = usbPID;
this.usbVID = usbVID;

logger.debug(
"Creating camera configuration for "
+ cameraType
+ " "
+ baseName
+ " (AKA "
+ nickname
+ ") at "
+ path);
logger.debug("Loaded camera configuration for " + toShortString());
}

public void addPipelineSettings(List<CVPipelineSettings> settings) {
Expand Down Expand Up @@ -189,6 +173,30 @@ public Optional<String> getUSBPath() {
return Arrays.stream(otherPaths).filter(path -> path.contains("/by-path/")).findFirst();
}

public String toShortString() {
return "CameraConfiguration [baseName="
+ baseName
+ ", uniqueName="
+ uniqueName
+ ", nickname="
+ nickname
+ ", path="
+ path
+ ", otherPaths="
+ Arrays.toString(otherPaths)
+ ", cameraType="
+ cameraType
+ ", cameraQuirks="
+ cameraQuirks
+ ", FOV="
+ FOV
+ "]"
+ ", PID="
+ usbPID
+ ", VID="
+ usbVID;
}

@Override
public String toString() {
return "CameraConfiguration [baseName="
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
import org.photonvision.common.dataflow.DataChangeService;
import org.photonvision.common.dataflow.events.OutgoingUIEvent;
import org.photonvision.common.hardware.Platform;
import org.photonvision.common.hardware.Platform.OSType;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.common.util.TimedTaskManager;
Expand Down Expand Up @@ -128,20 +129,26 @@ protected List<VisionSource> tryMatchCamImpl() {
return tryMatchCamImpl(null);
}

protected List<VisionSource> tryMatchCamImpl(ArrayList<CameraInfo> cameraInfos) {
return tryMatchCamImpl(cameraInfos, Platform.getCurrentPlatform());
}

/**
* @param cameraInfos Used to feed camera info for unit tests.
* @return New VisionSources.
*/
protected List<VisionSource> tryMatchCamImpl(ArrayList<CameraInfo> cameraInfos) {
protected List<VisionSource> tryMatchCamImpl(
ArrayList<CameraInfo> cameraInfos, Platform platform) {
boolean createSources = true;
List<CameraInfo> connectedCameras;
if (cameraInfos == null) {
// Detect USB cameras using CSCore
connectedCameras = new ArrayList<>(filterAllowedDevices(getConnectedUSBCameras()));
connectedCameras = new ArrayList<>(filterAllowedDevices(getConnectedUSBCameras(), platform));
// Detect CSI cameras using libcamera
connectedCameras.addAll(new ArrayList<>(filterAllowedDevices(getConnectedCSICameras())));
connectedCameras.addAll(
new ArrayList<>(filterAllowedDevices(getConnectedCSICameras(), platform)));
} else {
connectedCameras = new ArrayList<>(filterAllowedDevices(cameraInfos));
connectedCameras = new ArrayList<>(filterAllowedDevices(cameraInfos, platform));
createSources =
false; // Dont create sources if we are using supplied camerainfo for unit tests.
}
Expand All @@ -162,15 +169,15 @@ protected List<VisionSource> tryMatchCamImpl(ArrayList<CameraInfo> cameraInfos)
// All cameras are already loaded return no new sources.
if (connectedCameras.isEmpty()) return null;

logger.debug("Matching " + connectedCameras.size() + " new cameras!");
logger.debug("Matching " + connectedCameras.size() + " new camera(s)!");

// Debug prints
for (var info : connectedCameras) {
logger.info("Detected unmatched physical camera: " + info.toString());
}

if (!unmatchedLoadedConfigs.isEmpty())
logger.debug("Trying to match " + unmatchedLoadedConfigs.size() + " unmatched configs...");
logger.debug("Trying to match " + unmatchedLoadedConfigs.size() + " unmatched config(s)...");

// Match camera configs to physical cameras
List<CameraConfiguration> matchedCameras =
Expand All @@ -182,7 +189,7 @@ protected List<VisionSource> tryMatchCamImpl(ArrayList<CameraInfo> cameraInfos)
() ->
"After matching, "
+ unmatchedLoadedConfigs.size()
+ " configs remained unmatched. Is your camera disconnected?");
+ " config(s) remained unmatched. Is your camera disconnected?");
logger.warn(
"Unloaded configs: "
+ unmatchedLoadedConfigs.stream()
Expand Down Expand Up @@ -233,7 +240,7 @@ private final Predicate<CameraInfo> getCameraMatcher(
if (checkUSBPath && savedConfig.getUSBPath().isEmpty()) {
logger.debug(
"WARN: Camera has empty USB path, but asked to match by name: "
+ camCfgToString(savedConfig));
+ savedConfig.toShortString());
}

return (CameraInfo physicalCamera) -> {
Expand Down Expand Up @@ -277,22 +284,6 @@ public List<CameraConfiguration> matchCameras(
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.
Expand Down Expand Up @@ -423,7 +414,7 @@ private List<CameraConfiguration> matchCamerasByStrategy(
logger.debug(
String.format(
"Trying to find a match for loaded camera %s (%s) with camera config: %s",
config.baseName, config.uniqueName, camCfgToString(config)));
config.baseName, config.uniqueName, config.toShortString()));

// Get matcher and filter against it, picking out the first match
Predicate<CameraInfo> matches =
Expand Down Expand Up @@ -463,7 +454,7 @@ private List<CameraConfiguration> createConfigsForCameras(
List<CameraConfiguration> loadedConfigs) {
List<CameraConfiguration> ret = new ArrayList<CameraConfiguration>();
logger.debug(
"After matching loaded configs, these configs remained unmatched: "
"After matching loaded configs, these cameras remained unmatched: "
+ detectedCameraList.stream()
.map(n -> String.valueOf(n))
.collect(Collectors.joining("-", "{", "}")));
Expand Down Expand Up @@ -537,7 +528,7 @@ public void setIgnoredCamerasRegex(String ignoredCamerasRegex) {
* @param allDevices
* @return list of devices with blacklisted or ignore devices removed.
*/
private List<CameraInfo> filterAllowedDevices(List<CameraInfo> allDevices) {
private List<CameraInfo> filterAllowedDevices(List<CameraInfo> allDevices, Platform platform) {
List<CameraInfo> filteredDevices = new ArrayList<>();
for (var device : allDevices) {
if (deviceBlacklist.contains(device.name)) {
Expand All @@ -546,6 +537,13 @@ private List<CameraInfo> filterAllowedDevices(List<CameraInfo> allDevices) {
} 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
Comment on lines 539 to +540
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

double else-if - syntax error?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

skill issue, this is a complete statement, just a confusing one with an empty body. add a comment

&& platform.osType == OSType.LINUX
&& device.cameraType == CameraType.UsbCamera) {
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.
Comment on lines +545 to +546
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

do we need to make any assertions to check that otherPaths does not contain "by-id" or "by-path", or will the otherPaths length always be empty?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good question. This specific problem is hard to recreate. I believe if we get either a by-id or by-path we should be good to assume we can read from the camera.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do we want to merge this as-is, or explicitly check only that there are no by-ids or by-paths?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

im fine doing it as is

} else {
filteredDevices.add(device);
logger.trace(
Expand All @@ -559,8 +557,6 @@ private static List<VisionSource> loadVisionSourcesFromCamConfigs(
List<CameraConfiguration> camConfigs, boolean createSources) {
var cameraSources = new ArrayList<VisionSource>();
for (var configuration : camConfigs) {
logger.debug("Creating VisionSource for " + camCfgToString(configuration));

// In unit tests, create dummy
if (!createSources) {
cameraSources.add(new TestSource(configuration));
Expand All @@ -580,6 +576,7 @@ private static List<VisionSource> loadVisionSourcesFromCamConfigs(
cameraSources.add(newCam);
}
}
logger.debug("Creating VisionSource for " + configuration.toShortString());
}
return cameraSources;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,14 @@

package org.photonvision.vision.processes;

import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertTrue;
import static org.junit.jupiter.api.Assertions.*;

import java.util.ArrayList;
import java.util.List;
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;
Expand Down Expand Up @@ -62,7 +62,8 @@ public void visionSourceTest() {
config4.usbVID = 5;
config4.usbPID = 6;

CameraInfo info1 = new CameraInfo(0, "dev/video0", "testVideo", new String[0], 1, 2);
CameraInfo info1 =
new CameraInfo(0, "dev/video0", "testVideo", new String[] {"/usb/path/0"}, 1, 2);

cameraInfos.add(info1);

Expand All @@ -73,7 +74,8 @@ public void visionSourceTest() {
assertTrue(inst.knownCameras.contains(info1));
assertEquals(2, inst.unmatchedLoadedConfigs.size());

CameraInfo info2 = new CameraInfo(0, "dev/video1", "secondTestVideo", new String[0], 2, 3);
CameraInfo info2 =
new CameraInfo(0, "dev/video1", "secondTestVideo", new String[] {"/usb/path/1"}, 2, 3);

cameraInfos.add(info2);

Expand Down Expand Up @@ -500,6 +502,43 @@ public void testCSICameraMatching() {
}
}

@Test
public void testNoOtherPaths() {
Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);

// List of known cameras
var cameraInfos = new ArrayList<CameraInfo>();

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[] {}, 3141, 25446);

cameraInfos.add(info1);

// Match two "new" cameras
var ret1 = inst.tryMatchCamImpl(cameraInfos, Platform.LINUX_64);

// 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());
}

@Test
public void testIdenticalCameras() {
Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ public enum Platform {
LINUX_ARM32("Linux ARM32", "linuxarm32", false, OSType.LINUX, false), // ODROID XU4, C1+
UNKNOWN("Unsupported Platform", "", false, OSType.UNKNOWN, false);

private enum OSType {
public enum OSType {
mcm001 marked this conversation as resolved.
Show resolved Hide resolved
WINDOWS,
LINUX,
MACOS,
Expand Down Expand Up @@ -123,7 +123,7 @@ public static boolean isSupported() {
private static final String UnknownPlatformString =
String.format("Unknown Platform. OS: %s, Architecture: %s", OS_NAME, OS_ARCH);

private static Platform getCurrentPlatform() {
public static Platform getCurrentPlatform() {
if (RuntimeDetector.isWindows()) {
if (RuntimeDetector.is32BitIntel()) {
return WINDOWS_32;
Expand Down
Loading