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 8a0c755ad8..a3b4812202 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 @@ -51,6 +51,7 @@ static class TableKeys { static final String CAM_UNIQUE_NAME = "unique_name"; static final String CONFIG_JSON = "config_json"; static final String DRIVERMODE_JSON = "drivermode_json"; + static final String OTHERPATHS_JSON = "otherpaths_json"; static final String PIPELINE_JSONS = "pipeline_jsons"; static final String NETWORK_CONFIG = "networkConfig"; @@ -131,9 +132,9 @@ private void initDatabase() { createGlobalTableStatement = conn.createStatement(); String sql = "CREATE TABLE IF NOT EXISTS global (\n" - + " filename TINYTEXT PRIMARY KEY,\n" - + " contents mediumtext NOT NULL\n" - + ");"; + + " filename TINYTEXT PRIMARY KEY,\n" + + " contents mediumtext NOT NULL\n" + + ");"; createGlobalTableStatement.execute(sql); } catch (SQLException e) { logger.error("Err creating global table", e); @@ -144,11 +145,12 @@ private void initDatabase() { createCameraTableStatement = conn.createStatement(); var sql = "CREATE TABLE IF NOT EXISTS cameras (\n" - + " unique_name TINYTEXT PRIMARY KEY,\n" - + " config_json text NOT NULL,\n" - + " drivermode_json text NOT NULL,\n" - + " pipeline_jsons mediumtext NOT NULL\n" - + ");"; + + " unique_name TINYTEXT PRIMARY KEY,\n" + + " config_json text NOT NULL,\n" + + " drivermode_json text NOT NULL,\n" + + " otherpaths_json text NOT NULL,\n" + + " pipeline_jsons mediumtext NOT NULL\n" + + ");"; createCameraTableStatement.execute(sql); } catch (SQLException e) { logger.error("Err creating cameras table", e); @@ -210,7 +212,7 @@ public void load() { try { hardwareConfig = JacksonUtils.deserialize( - getOneConfigFile(conn, TableKeys.HARDWARE_CONFIG), HardwareConfig.class); + getOneConfigFile(conn, TableKeys.HARDWARE_CONFIG), HardwareConfig.class); } catch (IOException e) { logger.error("Could not deserialize hardware config! Loading defaults"); hardwareConfig = new HardwareConfig(); @@ -219,7 +221,7 @@ public void load() { try { hardwareSettings = JacksonUtils.deserialize( - getOneConfigFile(conn, TableKeys.HARDWARE_SETTINGS), HardwareSettings.class); + getOneConfigFile(conn, TableKeys.HARDWARE_SETTINGS), HardwareSettings.class); } catch (IOException e) { logger.error("Could not deserialize hardware settings! Loading defaults"); hardwareSettings = new HardwareSettings(); @@ -228,7 +230,7 @@ public void load() { try { networkConfig = JacksonUtils.deserialize( - getOneConfigFile(conn, TableKeys.NETWORK_CONFIG), NetworkConfig.class); + getOneConfigFile(conn, TableKeys.NETWORK_CONFIG), NetworkConfig.class); } catch (IOException e) { logger.error("Could not deserialize network config! Loading defaults"); networkConfig = new NetworkConfig(); @@ -237,7 +239,7 @@ public void load() { try { atfl = JacksonUtils.deserialize( - getOneConfigFile(conn, TableKeys.ATFL_CONFIG_FILE), AprilTagFieldLayout.class); + getOneConfigFile(conn, TableKeys.ATFL_CONFIG_FILE), AprilTagFieldLayout.class); } catch (IOException e) { logger.error("Could not deserialize apriltag layout! Loading defaults"); try { @@ -295,8 +297,8 @@ private void saveCameras(Connection conn) { try { // Replace this camera's row with the new settings var sqlString = - "REPLACE INTO cameras (unique_name, config_json, drivermode_json, pipeline_jsons) VALUES " - + "(?,?,?,?);"; + "REPLACE INTO cameras (unique_name, config_json, drivermode_json, otherpaths_json, pipeline_jsons) VALUES " + + "(?,?,?,?,?);"; for (var c : config.getCameraConfigurations().entrySet()) { PreparedStatement statement = conn.prepareStatement(sqlString); @@ -305,23 +307,24 @@ 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 List settings = - config.pipelineSettings.stream() - .map( - it -> { - try { - return JacksonUtils.serializeToString(it); - } catch (IOException e) { - e.printStackTrace(); - return null; - } - }) - .filter(Objects::nonNull) - .collect(Collectors.toList()); - statement.setString(4, JacksonUtils.serializeToString(settings)); + config.pipelineSettings.stream() + .map( + it -> { + try { + return JacksonUtils.serializeToString(it); + } catch (IOException e) { + e.printStackTrace(); + return null; + } + }) + .filter(Objects::nonNull) + .collect(Collectors.toList()); + statement.setString(5, JacksonUtils.serializeToString(settings)); statement.executeUpdate(); } @@ -454,12 +457,13 @@ private HashMap loadCameraConfigs(Connection conn) try { query = conn.prepareStatement( - String.format( - "SELECT %s, %s, %s, %s FROM cameras", - TableKeys.CAM_UNIQUE_NAME, - TableKeys.CONFIG_JSON, - TableKeys.DRIVERMODE_JSON, - TableKeys.PIPELINE_JSONS)); + String.format( + "SELECT %s, %s, %s, %s, %s FROM cameras", + TableKeys.CAM_UNIQUE_NAME, + TableKeys.CONFIG_JSON, + TableKeys.DRIVERMODE_JSON, + TableKeys.OTHERPATHS_JSON, + TableKeys.PIPELINE_JSONS)); var result = query.executeQuery(); @@ -474,6 +478,9 @@ private HashMap loadCameraConfigs(Connection conn) var driverMode = JacksonUtils.deserialize( result.getString(TableKeys.DRIVERMODE_JSON), DriverModePipelineSettings.class); + var otherPaths = + JacksonUtils.deserialize( + result.getString(TableKeys.OTHERPATHS_JSON), String[].class); List pipelineSettings = JacksonUtils.deserialize( result.getString(TableKeys.PIPELINE_JSONS), dummyList.getClass()); @@ -487,6 +494,7 @@ 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/vision/camera/USBCameraSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java index 6717f4edd8..d23f14aa67 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java @@ -346,8 +346,9 @@ public boolean isVendorCamera() { public boolean equals(Object o) { if (this == o) return true; if (o == null || getClass() != o.getClass()) return false; - USBCameraSource that = (USBCameraSource) o; - return cameraQuirks.equals(that.cameraQuirks); + // USBCameraSource that = (USBCameraSource) o; + // return cameraQuirks.equals(that.cameraQuirks); + return false; } @Override 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 4b31ba0691..5d909ca860 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 @@ -148,8 +148,8 @@ protected List tryMatchUSBCamImpl(boolean createSources) { logger.warn( () -> "After matching, " - + unmatchedLoadedConfigs.size() - + " configs remained unmatched. Is your camera disconnected?"); + + unmatchedLoadedConfigs.size() + + " configs remained unmatched. Is your camera disconnected?"); logger.warn( "Unloaded configs: " + unmatchedLoadedConfigs.stream() @@ -179,10 +179,10 @@ protected List tryMatchUSBCamImpl(boolean createSources) { logger.debug( () -> "Matched config for camera \"" - + src.getFrameProvider().getName() - + "\" and loaded " - + src.getCameraConfiguration().pipelineSettings.size() - + " pipelines"); + + src.getFrameProvider().getName() + + "\" and loaded " + + src.getCameraConfiguration().pipelineSettings.size() + + " pipelines"); } return sources; @@ -201,6 +201,8 @@ private List matchUSBCameras( var detectedCameraList = new ArrayList<>(detectedCamInfos); ArrayList cameraConfigurations = new ArrayList<>(); + List unmatchedUsbConfigs = new CopyOnWriteArrayList<>(loadedUsbCamConfigs); + // loop over all the configs loaded from disk for (CameraConfiguration config : loadedUsbCamConfigs) { UsbCameraInfo cameraInfo; @@ -212,25 +214,38 @@ private List matchUSBCameras( + " with path " + config.path); cameraInfo = - detectedCameraList.stream() - .filter( - usbCameraInfo -> - usbCameraInfo.path.equals(config.path) - && cameraNameToBaseName(usbCameraInfo.name).equals(config.baseName)) - .findFirst() - .orElse(null); - - // if path based fails, attempt basename only match - if (cameraInfo == null) { - logger.debug("Failed to match by path and name, falling back to name-only match"); - cameraInfo = - detectedCameraList.stream() - .filter( - usbCameraInfo -> - cameraNameToBaseName(usbCameraInfo.name).equals(config.baseName)) - .findFirst() - .orElse(null); + detectedCameraList.stream() + .filter( + usbCameraInfo -> + usbCameraInfo.otherPaths.length != 0 + && config.otherPaths.length != 0 + && usbCameraInfo.otherPaths[0].equals(config.otherPaths[0]) + && cameraNameToBaseName(usbCameraInfo.name).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!"); + detectedCameraList.remove(cameraInfo); + unmatchedUsbConfigs.remove(config); + cameraConfigurations.add(mergeInfoIntoConfig(config, cameraInfo)); } + } + + // if path based fails, attempt basename only match + for (CameraConfiguration config : unmatchedUsbConfigs) { + UsbCameraInfo cameraInfo; + + logger.debug("Failed to match by path and name, falling back to name-only match"); + cameraInfo = + detectedCameraList.stream() + .filter( + usbCameraInfo -> + cameraNameToBaseName(usbCameraInfo.name).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 @@ -250,7 +265,7 @@ && cameraNameToBaseName(usbCameraInfo.name).equals(config.baseName)) String uniqueName = baseNameToUniqueName(baseName); int suffix = 0; - while (containsName(cameraConfigurations, uniqueName)) { + while (containsName(cameraConfigurations, uniqueName) || containsName(uniqueName)) { suffix++; uniqueName = String.format("%s (%d)", uniqueName, suffix); } @@ -283,6 +298,21 @@ private CameraConfiguration mergeInfoIntoConfig(CameraConfiguration cfg, UsbCame cfg.path = info.path; } + 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; + } + } + } + return cfg; } @@ -334,7 +364,7 @@ private static List loadVisionSourcesFromCamConfigs( // Picams should have csi-video in the path boolean is_picam = (Arrays.stream(configuration.otherPaths).anyMatch(it -> it.contains("csi-video")) - || configuration.baseName.equals("unicam")); + || configuration.baseName.equals("unicam")); boolean is_pi = Platform.isRaspberryPi(); if (is_picam && is_pi) { configuration.cameraType = CameraType.ZeroCopyPicam; @@ -363,4 +393,16 @@ private boolean containsName( return configList.stream() .anyMatch(configuration -> configuration.uniqueName.equals(uniqueName)); } + + /** + * 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 knownUsbCameras.stream() + .anyMatch(camera -> camera.name.equals(uniqueName)); + } }